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 "lifecycle_msgs/msg/state.hpp"
33#include "rclcpp/version.h"
34#include "rclcpp_lifecycle/lifecycle_node.hpp"
35
36namespace controller_interface
37{
38using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
39
40enum class return_type : std::uint8_t
41{
42 OK = 0,
43 ERROR = 1,
44};
45
47
52enum class interface_configuration_type : std::uint8_t
53{
54 ALL = 0,
55 INDIVIDUAL = 1,
56 NONE = 2,
57};
58
61{
62 interface_configuration_type type;
63 std::vector<std::string> names = {};
64};
65
67{
68 void reset()
69 {
70 total_triggers = 0;
71 failed_triggers = 0;
72 }
73
74 unsigned int total_triggers;
75 unsigned int failed_triggers;
76};
77
89{
90 bool successful = true;
91 return_type result = return_type::OK;
92 std::optional<std::chrono::nanoseconds> execution_time = std::nullopt;
93 std::optional<rclcpp::Duration> period = std::nullopt;
94};
95
101class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
102{
103public:
104 ControllerInterfaceBase() = default;
105
106 virtual ~ControllerInterfaceBase();
107
109
121
123
137
139
147 virtual void assign_interfaces(
148 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
149 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
150
152
155 virtual void release_interfaces();
156
157 [[deprecated(
158 "Use the init(const controller_interface::ControllerInterfaceParams & params) method instead. "
159 "This method will be removed in the future ROS 2 releases.")]]
160 return_type init(
161 const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate,
162 const std::string & node_namespace, const rclcpp::NodeOptions & node_options);
163
164 return_type init(const controller_interface::ControllerInterfaceParams & params);
165
167 /*
168 * Override default implementation for configure of LifecycleNode to get parameters.
169 */
170 const rclcpp_lifecycle::State & configure();
171
173 virtual CallbackReturn on_init() = 0;
174
184 virtual return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
185
198 ControllerUpdateStatus trigger_update(const rclcpp::Time & time, const rclcpp::Duration & period);
199
200 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
201
202 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node() const;
203
211 const rclcpp_lifecycle::State & get_lifecycle_state() const;
212
219 uint8_t get_lifecycle_id() const;
220
221 unsigned int get_update_rate() const;
222
223 bool is_async() const;
224
225 const std::string & get_robot_description() const;
226
230 const std::unordered_map<std::string, joint_limits::JointLimits> & get_hard_joint_limits() const;
231
235 const std::unordered_map<std::string, joint_limits::SoftJointLimits> & get_soft_joint_limits()
236 const;
237
249 virtual rclcpp::NodeOptions define_custom_node_options() const
250 {
251 rclcpp::NodeOptions node_options;
252// \note The versions conditioning is added here to support the source-compatibility with Humble
253#if RCLCPP_VERSION_MAJOR >= 21
254 node_options.enable_logger_service(true);
255#else
256 node_options.allow_undeclared_parameters(true);
257 node_options.automatically_declare_parameters_from_overrides(true);
258#endif
259 return node_options;
260 }
261
263
269 template <typename ParameterT>
270 auto auto_declare(const std::string & name, const ParameterT & default_value)
271 {
272 if (!node_->has_parameter(name))
273 {
274 return node_->declare_parameter<ParameterT>(name, default_value);
275 }
276 else
277 {
278 return node_->get_parameter(name).get_value<ParameterT>();
279 }
280 }
281
282 // Methods for chainable controller types with default values so we can put all controllers into
283 // one list in Controller Manager
284
286
291 virtual bool is_chainable() const = 0;
292
299 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
301
308 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
310
319 virtual bool set_chained_mode(bool chained_mode) = 0;
320
322
329 virtual bool is_in_chained_mode() const = 0;
330
342
355
356 std::string get_name() const;
357
359
362 void enable_introspection(bool enable);
363
364protected:
374 std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
384 std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
385
386private:
391 void stop_async_handler_thread();
392
393 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
394 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
395 bool is_async_ = false;
397 std::atomic_bool skip_async_triggers_ = false;
398 ControllerUpdateStats trigger_stats_;
399 mutable std::atomic<uint8_t> lifecycle_id_ = lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
400
401protected:
402 pal_statistics::RegistrationsRAII stats_registrations_;
403};
404
405using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
406
407} // namespace controller_interface
408
409#endif // CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
Definition controller_interface_base.hpp:102
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:270
std::vector< hardware_interface::LoanedCommandInterface > command_interfaces_
Definition controller_interface_base.hpp:374
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:392
const std::unordered_map< std::string, joint_limits::SoftJointLimits > & get_soft_joint_limits() const
Definition controller_interface_base.cpp:398
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:427
void wait_for_trigger_update_to_finish()
Definition controller_interface_base.cpp:403
uint8_t get_lifecycle_id() const
Definition controller_interface_base.cpp:295
virtual std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces()=0
const rclcpp_lifecycle::State & get_lifecycle_state() const
Definition controller_interface_base.cpp:286
virtual void release_interfaces()
Method that releases the Loaned interfaces from the controller.
Definition controller_interface_base.cpp:280
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:173
ControllerUpdateStatus trigger_update(const rclcpp::Time &time, const rclcpp::Duration &period)
Definition controller_interface_base.cpp:313
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:272
virtual rclcpp::NodeOptions define_custom_node_options() const
Definition controller_interface_base.hpp:249
std::vector< hardware_interface::LoanedStateInterface > state_interfaces_
Definition controller_interface_base.hpp:384
virtual bool is_chainable() const =0
Get information if a controller is chainable.
void prepare_for_deactivation()
Definition controller_interface_base.cpp:411
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:67
Definition controller_interface_base.hpp:89
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:61