ros2_control - rolling
Loading...
Searching...
No Matches
controller_interface_base.hpp
1// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
16#define CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
17
18#include <memory>
19#include <string>
20#include <unordered_map>
21#include <utility>
22#include <vector>
23
24#include "realtime_tools/async_function_handler.hpp"
25
26#include "controller_interface/controller_interface_params.hpp"
27#include "hardware_interface/handle.hpp"
28#include "hardware_interface/introspection.hpp"
29#include "hardware_interface/loaned_command_interface.hpp"
30#include "hardware_interface/loaned_state_interface.hpp"
31
32#include "rclcpp/version.h"
33#include "rclcpp_lifecycle/lifecycle_node.hpp"
34
35namespace controller_interface
36{
37using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
38
39enum class return_type : std::uint8_t
40{
41 OK = 0,
42 ERROR = 1,
43};
44
46
51enum class interface_configuration_type : std::uint8_t
52{
53 ALL = 0,
54 INDIVIDUAL = 1,
55 NONE = 2,
56};
57
60{
61 interface_configuration_type type;
62 std::vector<std::string> names = {};
63};
64
66{
67 void reset()
68 {
69 total_triggers = 0;
70 failed_triggers = 0;
71 }
72
73 unsigned int total_triggers;
74 unsigned int failed_triggers;
75};
76
88{
89 bool successful = true;
90 return_type result = return_type::OK;
91 std::optional<std::chrono::nanoseconds> execution_time = std::nullopt;
92 std::optional<rclcpp::Duration> period = std::nullopt;
93};
94
100class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
101{
102public:
103 ControllerInterfaceBase() = default;
104
105 virtual ~ControllerInterfaceBase();
106
108
120
122
136
138
146 virtual void assign_interfaces(
147 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
148 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
149
151
154 virtual void release_interfaces();
155
156 [[deprecated(
157 "Use the init(const controller_interface::ControllerInterfaceParams & params) method instead. "
158 "This method will be removed in the future ROS 2 releases.")]]
159 return_type init(
160 const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate,
161 const std::string & node_namespace, const rclcpp::NodeOptions & node_options);
162
163 return_type init(const controller_interface::ControllerInterfaceParams & params);
164
166 /*
167 * Override default implementation for configure of LifecycleNode to get parameters.
168 */
169 const rclcpp_lifecycle::State & configure();
170
172 virtual CallbackReturn on_init() = 0;
173
183 virtual return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
184
197 ControllerUpdateStatus trigger_update(const rclcpp::Time & time, const rclcpp::Duration & period);
198
199 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
200
201 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node() const;
202
203 const rclcpp_lifecycle::State & get_lifecycle_state() const;
204
205 unsigned int get_update_rate() const;
206
207 bool is_async() const;
208
209 const std::string & get_robot_description() const;
210
214 const std::unordered_map<std::string, joint_limits::JointLimits> & get_hard_joint_limits() const;
215
219 const std::unordered_map<std::string, joint_limits::SoftJointLimits> & get_soft_joint_limits()
220 const;
221
233 virtual rclcpp::NodeOptions define_custom_node_options() const
234 {
235 rclcpp::NodeOptions node_options;
236// \note The versions conditioning is added here to support the source-compatibility with Humble
237#if RCLCPP_VERSION_MAJOR >= 21
238 node_options.enable_logger_service(true);
239#else
240 node_options.allow_undeclared_parameters(true);
241 node_options.automatically_declare_parameters_from_overrides(true);
242#endif
243 return node_options;
244 }
245
247
253 template <typename ParameterT>
254 auto auto_declare(const std::string & name, const ParameterT & default_value)
255 {
256 if (!node_->has_parameter(name))
257 {
258 return node_->declare_parameter<ParameterT>(name, default_value);
259 }
260 else
261 {
262 return node_->get_parameter(name).get_value<ParameterT>();
263 }
264 }
265
266 // Methods for chainable controller types with default values so we can put all controllers into
267 // one list in Controller Manager
268
270
275 virtual bool is_chainable() const = 0;
276
283 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
285
292 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
294
303 virtual bool set_chained_mode(bool chained_mode) = 0;
304
306
313 virtual bool is_in_chained_mode() const = 0;
314
326
339
340 std::string get_name() const;
341
343
346 void enable_introspection(bool enable);
347
348protected:
358 std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
368 std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
369
370private:
375 void stop_async_handler_thread();
376
377 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
378 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
379 bool is_async_ = false;
381 std::atomic_bool skip_async_triggers_ = false;
382 ControllerUpdateStats trigger_stats_;
383
384protected:
385 pal_statistics::RegistrationsRAII stats_registrations_;
386};
387
388using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
389
390} // namespace controller_interface
391
392#endif // CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
Definition controller_interface_base.hpp:101
virtual InterfaceConfiguration command_interface_configuration() const =0
Get configuration for controller's required command interfaces.
auto auto_declare(const std::string &name, const ParameterT &default_value)
Declare and initialize a parameter with a type.
Definition controller_interface_base.hpp:254
std::vector< hardware_interface::LoanedCommandInterface > command_interfaces_
Definition controller_interface_base.hpp:358
virtual CallbackReturn on_init()=0
Extending interface with initialization method which is individual for each controller.
const std::unordered_map< std::string, joint_limits::JointLimits > & get_hard_joint_limits() const
Definition controller_interface_base.cpp:321
const std::unordered_map< std::string, joint_limits::SoftJointLimits > & get_soft_joint_limits() const
Definition controller_interface_base.cpp:327
virtual std::vector< hardware_interface::StateInterface::ConstSharedPtr > export_state_interfaces()=0
void enable_introspection(bool enable)
Enable or disable introspection of the controller.
Definition controller_interface_base.cpp:356
void wait_for_trigger_update_to_finish()
Definition controller_interface_base.cpp:332
virtual std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces()=0
virtual void release_interfaces()
Method that releases the Loaned interfaces from the controller.
Definition controller_interface_base.cpp:227
virtual bool is_in_chained_mode() const =0
Get information if a controller is currently in chained mode.
virtual InterfaceConfiguration state_interface_configuration() const =0
Get configuration for controller's required state interfaces.
const rclcpp_lifecycle::State & configure()
Custom configure method to read additional parameters for controller-nodes.
Definition controller_interface_base.cpp:147
ControllerUpdateStatus trigger_update(const rclcpp::Time &time, const rclcpp::Duration &period)
Definition controller_interface_base.cpp:242
virtual void assign_interfaces(std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces)
Method that assigns the Loaned interfaces to the controller.
Definition controller_interface_base.cpp:219
virtual rclcpp::NodeOptions define_custom_node_options() const
Definition controller_interface_base.hpp:233
std::vector< hardware_interface::LoanedStateInterface > state_interfaces_
Definition controller_interface_base.hpp:368
virtual bool is_chainable() const =0
Get information if a controller is chainable.
void prepare_for_deactivation()
Definition controller_interface_base.cpp:340
virtual bool set_chained_mode(bool chained_mode)=0
virtual return_type update(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Definition controller_interface_params.hpp:44
Definition controller_interface_base.hpp:66
Definition controller_interface_base.hpp:88
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:60