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
48
58enum class interface_configuration_type : std::uint8_t
59{
60 ALL = 0,
61 INDIVIDUAL = 1,
62 NONE = 2,
63 INDIVIDUAL_BEST_EFFORT = 3,
64 REGEX = 10
65};
66
69{
70 interface_configuration_type type = interface_configuration_type::NONE;
71 std::vector<std::string> names = {};
72};
73
75{
76 void reset()
77 {
78 total_triggers = 0;
79 failed_triggers = 0;
80 }
81
82 unsigned int total_triggers;
83 unsigned int failed_triggers;
84};
85
97{
98 bool successful = true;
99 return_type result = return_type::OK;
100 std::optional<std::chrono::nanoseconds> execution_time = std::nullopt;
101 std::optional<rclcpp::Duration> period = std::nullopt;
102};
103
109class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
110{
111public:
113
114 virtual ~ControllerInterfaceBase();
115
117
129
131
145
147
155 virtual void assign_interfaces(
156 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
157 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
158
160
163 virtual void release_interfaces();
164
165 [[deprecated(
166 "Use the init(const controller_interface::ControllerInterfaceParams & params) method instead. "
167 "This method will be removed in the future ROS 2 releases.")]]
168 return_type init(
169 const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate,
170 const std::string & node_namespace, const rclcpp::NodeOptions & node_options);
171
172 return_type init(const controller_interface::ControllerInterfaceParams & params);
173
175 /*
176 * Override default implementation for configure of LifecycleNode to get parameters.
177 */
178 const rclcpp_lifecycle::State & configure();
179
181 virtual CallbackReturn on_init() = 0;
182
192 virtual return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
193
206 ControllerUpdateStatus trigger_update(const rclcpp::Time & time, const rclcpp::Duration & period);
207
208 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
209
210 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node() const;
211
219 const rclcpp_lifecycle::State & get_lifecycle_state() const;
220
227 uint8_t get_lifecycle_id() const;
228
229 unsigned int get_update_rate() const;
230
231 bool is_async() const;
232
233 const std::string & get_robot_description() const;
234
238 const std::unordered_map<std::string, joint_limits::JointLimits> & get_hard_joint_limits() const;
239
243 const std::unordered_map<std::string, joint_limits::SoftJointLimits> & get_soft_joint_limits()
244 const;
245
257 virtual rclcpp::NodeOptions define_custom_node_options() const
258 {
259 rclcpp::NodeOptions node_options;
260// \note The versions conditioning is added here to support the source-compatibility with Humble
261#if RCLCPP_VERSION_MAJOR >= 21
262 node_options.enable_logger_service(true);
263#else
264 node_options.allow_undeclared_parameters(true);
265 node_options.automatically_declare_parameters_from_overrides(true);
266#endif
267 return node_options;
268 }
269
271
277 template <typename ParameterT>
278 auto auto_declare(const std::string & name, const ParameterT & default_value)
279 {
280 if (!get_node()->has_parameter(name))
281 {
282 return get_node()->declare_parameter<ParameterT>(name, default_value);
283 }
284 else
285 {
286 return get_node()->get_parameter(name).get_value<ParameterT>();
287 }
288 }
289
290 // Methods for chainable controller types with default values so we can put all controllers into
291 // one list in Controller Manager
292
294
299 virtual bool is_chainable() const = 0;
300
307 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
309
316 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
318
327 virtual bool set_chained_mode(bool chained_mode) = 0;
328
330
337 virtual bool is_in_chained_mode() const = 0;
338
350
363
364 std::string get_name() const;
365
367
370 void enable_introspection(bool enable);
371
372protected:
386 std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
400 std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
401
402private:
407 void stop_async_handler_thread();
408
410 std::unique_ptr<ControllerInterfaceBaseImpl> impl_;
411
412protected:
413 pal_statistics::RegistrationsRAII stats_registrations_;
414};
415
416using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
417
418} // namespace controller_interface
419
420#endif // CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
Definition controller_interface_base.hpp:110
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:278
std::vector< hardware_interface::LoanedCommandInterface > command_interfaces_
Definition controller_interface_base.hpp:386
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:257
std::vector< hardware_interface::LoanedStateInterface > state_interfaces_
Definition controller_interface_base.hpp:400
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:75
Definition controller_interface_base.hpp:97
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:69