ros2_control - jazzy
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/introspection.hpp"
27#include "hardware_interface/loaned_command_interface.hpp"
28#include "hardware_interface/loaned_state_interface.hpp"
29
30#include "rclcpp/version.h"
31#include "rclcpp_lifecycle/lifecycle_node.hpp"
32
33namespace controller_interface
34{
35using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
36
37enum class return_type : std::uint8_t
38{
39 OK = 0,
40 ERROR = 1,
41};
42
44
49enum class interface_configuration_type : std::uint8_t
50{
51 ALL = 0,
52 INDIVIDUAL = 1,
53 NONE = 2,
54};
55
58{
59 interface_configuration_type type;
60 std::vector<std::string> names = {};
61};
62
64{
65 void reset()
66 {
67 total_triggers = 0;
68 failed_triggers = 0;
69 }
70
71 unsigned int total_triggers;
72 unsigned int failed_triggers;
73};
74
86{
87 bool successful = true;
88 return_type result = return_type::OK;
89 std::optional<std::chrono::nanoseconds> execution_time = std::nullopt;
90 std::optional<rclcpp::Duration> period = std::nullopt;
91};
92
98class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
99{
100public:
101 ControllerInterfaceBase() = default;
102
103 virtual ~ControllerInterfaceBase();
104
106
118
120
134
136
144 virtual void assign_interfaces(
145 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
146 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
147
149
152 virtual void release_interfaces();
153
154 return_type init(
155 const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate,
156 const std::string & node_namespace, const rclcpp::NodeOptions & node_options);
157
159 /*
160 * Override default implementation for configure of LifecycleNode to get parameters.
161 */
162 const rclcpp_lifecycle::State & configure();
163
165 virtual CallbackReturn on_init() = 0;
166
176 virtual return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
177
190 ControllerUpdateStatus trigger_update(const rclcpp::Time & time, const rclcpp::Duration & period);
191
192 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
193
194 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node() const;
195
196 const rclcpp_lifecycle::State & get_lifecycle_state() const;
197
198 unsigned int get_update_rate() const;
199
200 bool is_async() const;
201
202 const std::string & get_robot_description() const;
203
215 virtual rclcpp::NodeOptions define_custom_node_options() const
216 {
217 rclcpp::NodeOptions node_options;
218// \note The versions conditioning is added here to support the source-compatibility with Humble
219#if RCLCPP_VERSION_MAJOR >= 21
220 node_options.enable_logger_service(true);
221#else
222 node_options.allow_undeclared_parameters(true);
223 node_options.automatically_declare_parameters_from_overrides(true);
224#endif
225 return node_options;
226 }
227
229
235 template <typename ParameterT>
236 auto auto_declare(const std::string & name, const ParameterT & default_value)
237 {
238 if (!node_->has_parameter(name))
239 {
240 return node_->declare_parameter<ParameterT>(name, default_value);
241 }
242 else
243 {
244 return node_->get_parameter(name).get_value<ParameterT>();
245 }
246 }
247
248 // Methods for chainable controller types with default values so we can put all controllers into
249 // one list in Controller Manager
250
252
257 virtual bool is_chainable() const = 0;
258
265 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
267
274 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
276
285 virtual bool set_chained_mode(bool chained_mode) = 0;
286
288
295 virtual bool is_in_chained_mode() const = 0;
296
308
321
322 std::string get_name() const;
323
325
328 void enable_introspection(bool enable);
329
330protected:
340 std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
350 std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
351
352private:
357 void stop_async_handler_thread();
358
359 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
360 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
361 unsigned int update_rate_ = 0;
362 bool is_async_ = false;
363 std::string urdf_ = "";
364 std::atomic_bool skip_async_triggers_ = false;
365 ControllerUpdateStats trigger_stats_;
366
367protected:
368 pal_statistics::RegistrationsRAII stats_registrations_;
369};
370
371using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
372
373} // namespace controller_interface
374
375#endif // CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
Definition controller_interface_base.hpp:99
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:236
std::vector< hardware_interface::LoanedCommandInterface > command_interfaces_
Definition controller_interface_base.hpp:340
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 enable_introspection(bool enable)
Enable or disable introspection of the controller.
Definition controller_interface_base.cpp:306
void wait_for_trigger_update_to_finish()
Definition controller_interface_base.cpp:282
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:195
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:134
ControllerUpdateStatus trigger_update(const rclcpp::Time &time, const rclcpp::Duration &period)
Definition controller_interface_base.cpp:210
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:187
virtual rclcpp::NodeOptions define_custom_node_options() const
Definition controller_interface_base.hpp:215
std::vector< hardware_interface::LoanedStateInterface > state_interfaces_
Definition controller_interface_base.hpp:350
virtual bool is_chainable() const =0
Get information if a controller is chainable.
void prepare_for_deactivation()
Definition controller_interface_base.cpp:290
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:64
Definition controller_interface_base.hpp:86
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:58