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 <utility>
21#include <vector>
22
23#include "realtime_tools/async_function_handler.hpp"
24
25#include "hardware_interface/handle.hpp"
26#include "hardware_interface/loaned_command_interface.hpp"
27#include "hardware_interface/loaned_state_interface.hpp"
28
29#include "rclcpp/version.h"
30#include "rclcpp_lifecycle/lifecycle_node.hpp"
31
32namespace controller_interface
33{
34using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
35
36enum class return_type : std::uint8_t
37{
38 OK = 0,
39 ERROR = 1,
40};
41
43
48enum class interface_configuration_type : std::uint8_t
49{
50 ALL = 0,
51 INDIVIDUAL = 1,
52 NONE = 2,
53};
54
57{
58 interface_configuration_type type;
59 std::vector<std::string> names = {};
60};
61
63{
64 void reset()
65 {
66 total_triggers = 0;
67 failed_triggers = 0;
68 }
69
70 unsigned int total_triggers;
71 unsigned int failed_triggers;
72};
73
85{
86 bool successful = true;
87 return_type result = return_type::OK;
88 std::optional<std::chrono::nanoseconds> execution_time = std::nullopt;
89 std::optional<rclcpp::Duration> period = std::nullopt;
90};
91
97class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
98{
99public:
100 ControllerInterfaceBase() = default;
101
102 virtual ~ControllerInterfaceBase();
103
105
117
119
133
135
143 virtual void assign_interfaces(
144 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
145 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
146
148
151 virtual void release_interfaces();
152
153 return_type init(
154 const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate,
155 const std::string & node_namespace, const rclcpp::NodeOptions & node_options);
156
158 /*
159 * Override default implementation for configure of LifecycleNode to get parameters.
160 */
161 const rclcpp_lifecycle::State & configure();
162
164 virtual CallbackReturn on_init() = 0;
165
175 virtual return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
176
189 ControllerUpdateStatus trigger_update(const rclcpp::Time & time, const rclcpp::Duration & period);
190
191 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
192
193 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node() const;
194
195 const rclcpp_lifecycle::State & get_lifecycle_state() const;
196
197 unsigned int get_update_rate() const;
198
199 bool is_async() const;
200
201 const std::string & get_robot_description() const;
202
214 virtual rclcpp::NodeOptions define_custom_node_options() const
215 {
216 rclcpp::NodeOptions node_options;
217// \note The versions conditioning is added here to support the source-compatibility with Humble
218#if RCLCPP_VERSION_MAJOR >= 21
219 node_options.enable_logger_service(true);
220#else
221 node_options.allow_undeclared_parameters(true);
222 node_options.automatically_declare_parameters_from_overrides(true);
223#endif
224 return node_options;
225 }
226
228
234 template <typename ParameterT>
235 auto auto_declare(const std::string & name, const ParameterT & default_value)
236 {
237 if (!node_->has_parameter(name))
238 {
239 return node_->declare_parameter<ParameterT>(name, default_value);
240 }
241 else
242 {
243 return node_->get_parameter(name).get_value<ParameterT>();
244 }
245 }
246
247 // Methods for chainable controller types with default values so we can put all controllers into
248 // one list in Controller Manager
249
251
256 virtual bool is_chainable() const = 0;
257
264 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
266
273 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
275
284 virtual bool set_chained_mode(bool chained_mode) = 0;
285
287
294 virtual bool is_in_chained_mode() const = 0;
295
307
308protected:
309 std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
310 std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
311
312private:
313 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
314 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
315 unsigned int update_rate_ = 0;
316 bool is_async_ = false;
317 std::string urdf_ = "";
318 ControllerUpdateStats trigger_stats_;
319};
320
321using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
322
323} // namespace controller_interface
324
325#endif // CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
Definition controller_interface_base.hpp:98
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:235
virtual CallbackReturn on_init()=0
Extending interface with initialization method which is individual for each controller.
virtual std::vector< hardware_interface::StateInterface::ConstSharedPtr > export_state_interfaces()=0
void wait_for_trigger_update_to_finish()
Definition controller_interface_base.cpp:254
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:174
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:115
ControllerUpdateStatus trigger_update(const rclcpp::Time &time, const rclcpp::Duration &period)
Definition controller_interface_base.cpp:189
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:166
virtual rclcpp::NodeOptions define_custom_node_options() const
Definition controller_interface_base.hpp:214
virtual bool is_chainable() const =0
Get information if a controller is chainable.
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_base.hpp:63
Definition controller_interface_base.hpp:85
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:57