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 "pal_statistics/pal_statistics_utils.hpp"
34#include "rclcpp/version.h"
35#include "rclcpp_lifecycle/lifecycle_node.hpp"
36
37namespace controller_interface
38{
39using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
40
41enum class return_type : std::uint8_t
42{
43 OK = 0,
44 ERROR = 1,
45};
46
59enum class interface_configuration_type : std::uint8_t
60{
61 ALL = 0,
62 INDIVIDUAL = 1,
63 NONE = 2,
64 INDIVIDUAL_BEST_EFFORT = 3,
65 REGEX = 10
66};
67
72{
73 interface_configuration_type type = interface_configuration_type::NONE;
74 std::vector<std::string> names = {};
75};
76
78{
79 void reset()
80 {
81 total_triggers = 0;
82 failed_triggers = 0;
83 }
84
85 unsigned int total_triggers;
86 unsigned int failed_triggers;
87};
88
100{
101 bool successful = true;
102 return_type result = return_type::OK;
103 std::optional<std::chrono::nanoseconds> execution_time = std::nullopt;
104 std::optional<rclcpp::Duration> period = std::nullopt;
105};
106
112class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
113{
114public:
116
117 virtual ~ControllerInterfaceBase();
118
133
150
161 virtual void assign_interfaces(
162 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
163 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
164
170 virtual void release_interfaces();
171
172 [[deprecated(
173 "Use the init(const controller_interface::ControllerInterfaceParams & params) method instead. "
174 "This method will be removed in the future ROS 2 releases.")]]
175 return_type init(
176 const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate,
177 const std::string & node_namespace, const rclcpp::NodeOptions & node_options);
178
179 return_type init(const controller_interface::ControllerInterfaceParams & params);
180
186 const rclcpp_lifecycle::State & configure();
187
191 virtual CallbackReturn on_init() = 0;
192
202 virtual return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
203
215 ControllerUpdateStatus trigger_update(const rclcpp::Time & time, const rclcpp::Duration & period);
216
217 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
218
219 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node() const;
220
228 const rclcpp_lifecycle::State & get_lifecycle_state() const;
229
236 uint8_t get_lifecycle_id() const;
237
238 unsigned int get_update_rate() const;
239
240 bool is_async() const;
241
242 const std::string & get_robot_description() const;
243
247 const std::unordered_map<std::string, joint_limits::JointLimits> & get_hard_joint_limits() const;
248
252 const std::unordered_map<std::string, joint_limits::SoftJointLimits> & get_soft_joint_limits()
253 const;
254
266 virtual rclcpp::NodeOptions define_custom_node_options() const
267 {
268 rclcpp::NodeOptions node_options;
269// @note The versions conditioning is added here to support the source-compatibility with Humble
270#if RCLCPP_VERSION_MAJOR >= 21
271 node_options.enable_logger_service(true);
272#else
273 node_options.allow_undeclared_parameters(true);
274 node_options.automatically_declare_parameters_from_overrides(true);
275#endif
276 return node_options;
277 }
278
286 template <typename ParameterT>
287 auto auto_declare(const std::string & name, const ParameterT & default_value)
288 {
289 if (!get_node()->has_parameter(name))
290 {
291 return get_node()->declare_parameter<ParameterT>(name, default_value);
292 }
293 else
294 {
295 return get_node()->get_parameter(name).get_value<ParameterT>();
296 }
297 }
298
299 // Methods for chainable controller types with default values so we can put all controllers into
300 // one list in Controller Manager
301
309 virtual bool is_chainable() const = 0;
310
317 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
319
326 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
328
337 virtual bool set_chained_mode(bool chained_mode) = 0;
338
348 virtual bool is_in_chained_mode() const = 0;
349
362
376
377 std::string get_name() const;
378
384 void enable_introspection(bool enable);
385
386protected:
401 std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
416 std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
417
418private:
423 void stop_async_handler_thread();
424
426 std::unique_ptr<ControllerInterfaceBaseImpl> impl_;
427
428protected:
429 pal_statistics::RegistrationsRAII stats_registrations_;
430};
431
432using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
433
434} // namespace controller_interface
435
436#endif // CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
Base interface class for an controller. The interface may not be used to implement a controller....
Definition controller_interface_base.hpp:113
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:287
std::vector< hardware_interface::LoanedCommandInterface > command_interfaces_
Loaned command interfaces.
Definition controller_interface_base.hpp:401
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
Get the unordered map of joint limits that are defined in the robot description.
Definition controller_interface_base.cpp:407
const std::unordered_map< std::string, joint_limits::SoftJointLimits > & get_soft_joint_limits() const
Get the unordered map of soft joint limits that are defined in the robot description.
Definition controller_interface_base.cpp:413
virtual std::vector< hardware_interface::StateInterface::ConstSharedPtr > export_state_interfaces()=0
Export interfaces for a chainable controller that can be used as state interface by other controllers...
void enable_introspection(bool enable)
Enable or disable introspection of the controller.
Definition controller_interface_base.cpp:442
void wait_for_trigger_update_to_finish()
Method to wait for any running async update cycle to finish after finishing the current cycle....
Definition controller_interface_base.cpp:418
uint8_t get_lifecycle_id() const
Get the lifecycle id of the controller node that is cached internally to avoid calls to get_lifecycle...
Definition controller_interface_base.cpp:310
virtual std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces()=0
Export interfaces for a chainable controller that can be used as command interface of other controlle...
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get the current lifecycle state of the controller node.
Definition controller_interface_base.cpp:301
virtual void release_interfaces()
Method that releases the Loaned interfaces from the controller.
Definition controller_interface_base.cpp:295
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:187
ControllerUpdateStatus trigger_update(const rclcpp::Time &time, const rclcpp::Duration &period)
Trigger update method. This method is used by the controller_manager to trigger the update method of ...
Definition controller_interface_base.cpp:328
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:287
virtual rclcpp::NodeOptions define_custom_node_options() const
Method used by the controller_manager for base NodeOptions to instantiate the Lifecycle node of the c...
Definition controller_interface_base.hpp:266
std::vector< hardware_interface::LoanedStateInterface > state_interfaces_
Loaned state interfaces.
Definition controller_interface_base.hpp:416
virtual bool is_chainable() const =0
Get information if a controller is chainable.
void prepare_for_deactivation()
Method to prepare the controller for deactivation. This method is called by the controller manager be...
Definition controller_interface_base.cpp:426
virtual bool set_chained_mode(bool chained_mode)=0
Set chained mode of a chainable controller. This method triggers internal processes to switch a chain...
virtual return_type update(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Control step update. Command interfaces are updated based on on reference inputs and current states....
Definition controller_interface_params.hpp:44
Definition controller_interface_base.hpp:78
Definition controller_interface_base.hpp:100
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:72