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
57enum class interface_configuration_type : std::uint8_t
58{
59 ALL = 0,
60 INDIVIDUAL = 1,
61 NONE = 2,
62 INDIVIDUAL_BEST_EFFORT = 3,
63 REGEX = 10
64};
65
68{
69 interface_configuration_type type = interface_configuration_type::NONE;
70 std::vector<std::string> names = {};
71};
72
74{
75 void reset()
76 {
77 total_triggers = 0;
78 failed_triggers = 0;
79 }
80
81 unsigned int total_triggers;
82 unsigned int failed_triggers;
83};
84
96{
97 bool successful = true;
98 return_type result = return_type::OK;
99 std::optional<std::chrono::nanoseconds> execution_time = std::nullopt;
100 std::optional<rclcpp::Duration> period = std::nullopt;
101};
102
108class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
109{
110public:
112
113 virtual ~ControllerInterfaceBase();
114
116
128
130
144
146
154 virtual void assign_interfaces(
155 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
156 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
157
159
162 virtual void release_interfaces();
163
164 [[deprecated(
165 "Use the init(const controller_interface::ControllerInterfaceParams & params) method instead. "
166 "This method will be removed in the future ROS 2 releases.")]]
167 return_type init(
168 const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate,
169 const std::string & node_namespace, const rclcpp::NodeOptions & node_options);
170
171 return_type init(const controller_interface::ControllerInterfaceParams & params);
172
174 /*
175 * Override default implementation for configure of LifecycleNode to get parameters.
176 */
177 const rclcpp_lifecycle::State & configure();
178
180 virtual CallbackReturn on_init() = 0;
181
191 virtual return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
192
205 ControllerUpdateStatus trigger_update(const rclcpp::Time & time, const rclcpp::Duration & period);
206
207 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
208
209 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node() const;
210
218 const rclcpp_lifecycle::State & get_lifecycle_state() const;
219
226 uint8_t get_lifecycle_id() const;
227
228 unsigned int get_update_rate() const;
229
230 bool is_async() const;
231
232 const std::string & get_robot_description() const;
233
237 const std::unordered_map<std::string, joint_limits::JointLimits> & get_hard_joint_limits() const;
238
242 const std::unordered_map<std::string, joint_limits::SoftJointLimits> & get_soft_joint_limits()
243 const;
244
256 virtual rclcpp::NodeOptions define_custom_node_options() const
257 {
258 rclcpp::NodeOptions node_options;
259// \note The versions conditioning is added here to support the source-compatibility with Humble
260#if RCLCPP_VERSION_MAJOR >= 21
261 node_options.enable_logger_service(true);
262#else
263 node_options.allow_undeclared_parameters(true);
264 node_options.automatically_declare_parameters_from_overrides(true);
265#endif
266 return node_options;
267 }
268
270
276 template <typename ParameterT>
277 auto auto_declare(const std::string & name, const ParameterT & default_value)
278 {
279 if (!get_node()->has_parameter(name))
280 {
281 return get_node()->declare_parameter<ParameterT>(name, default_value);
282 }
283 else
284 {
285 return get_node()->get_parameter(name).get_value<ParameterT>();
286 }
287 }
288
289 // Methods for chainable controller types with default values so we can put all controllers into
290 // one list in Controller Manager
291
293
298 virtual bool is_chainable() const = 0;
299
306 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
308
315 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
317
326 virtual bool set_chained_mode(bool chained_mode) = 0;
327
329
336 virtual bool is_in_chained_mode() const = 0;
337
349
362
363 std::string get_name() const;
364
366
369 void enable_introspection(bool enable);
370
371protected:
385 std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
399 std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
400
401private:
406 void stop_async_handler_thread();
407
409 std::unique_ptr<ControllerInterfaceBaseImpl> impl_;
410
411protected:
412 pal_statistics::RegistrationsRAII stats_registrations_;
413};
414
415using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
416
417} // namespace controller_interface
418
419#endif // CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
Definition controller_interface_base.hpp:109
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:277
std::vector< hardware_interface::LoanedCommandInterface > command_interfaces_
Definition controller_interface_base.hpp:385
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:407
const std::unordered_map< std::string, joint_limits::SoftJointLimits > & get_soft_joint_limits() const
Definition controller_interface_base.cpp:413
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:442
void wait_for_trigger_update_to_finish()
Definition controller_interface_base.cpp:418
uint8_t get_lifecycle_id() const
Definition controller_interface_base.cpp:310
virtual std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces()=0
const rclcpp_lifecycle::State & get_lifecycle_state() const
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)
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
Definition controller_interface_base.hpp:256
std::vector< hardware_interface::LoanedStateInterface > state_interfaces_
Definition controller_interface_base.hpp:399
virtual bool is_chainable() const =0
Get information if a controller is chainable.
void prepare_for_deactivation()
Definition controller_interface_base.cpp:426
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:74
Definition controller_interface_base.hpp:96
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:68