ros2_control - humble
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 <vector>
21
22#include "controller_interface/visibility_control.h"
23
24#include "hardware_interface/handle.hpp"
25#include "hardware_interface/loaned_command_interface.hpp"
26#include "hardware_interface/loaned_state_interface.hpp"
27
28#include "rclcpp/rclcpp.hpp"
29#include "rclcpp_lifecycle/lifecycle_node.hpp"
30
31namespace controller_interface
32{
33using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
34
35enum class return_type : std::uint8_t
36{
37 OK = 0,
38 ERROR = 1,
39};
40
42
47enum class interface_configuration_type : std::uint8_t
48{
49 ALL = 0,
50 INDIVIDUAL = 1,
51 NONE = 2,
52};
53
56{
57 interface_configuration_type type;
58 std::vector<std::string> names = {};
59};
60
66class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
67{
68public:
69 CONTROLLER_INTERFACE_PUBLIC
70 ControllerInterfaceBase() = default;
71
72 CONTROLLER_INTERFACE_PUBLIC
73 virtual ~ControllerInterfaceBase() = default;
74
76
87 CONTROLLER_INTERFACE_PUBLIC
89
91
104 CONTROLLER_INTERFACE_PUBLIC
106
107 CONTROLLER_INTERFACE_PUBLIC
108 void assign_interfaces(
109 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
110 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
111
112 CONTROLLER_INTERFACE_PUBLIC
113 void release_interfaces();
114
115 CONTROLLER_INTERFACE_PUBLIC
116 virtual return_type init(
117 const std::string & controller_name, const std::string & namespace_ = "",
118 const rclcpp::NodeOptions & node_options =
119 rclcpp::NodeOptions()
120 .allow_undeclared_parameters(true)
121 .automatically_declare_parameters_from_overrides(true));
122
124 /*
125 * Override default implementation for configure of LifecycleNode to get parameters.
126 */
127 CONTROLLER_INTERFACE_PUBLIC
128 const rclcpp_lifecycle::State & configure();
129
131 CONTROLLER_INTERFACE_PUBLIC
132 virtual CallbackReturn on_init() = 0;
133
143 CONTROLLER_INTERFACE_PUBLIC
144 virtual return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
145
146 CONTROLLER_INTERFACE_PUBLIC
147 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
148
149 CONTROLLER_INTERFACE_PUBLIC
150 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node() const;
151
152 CONTROLLER_INTERFACE_PUBLIC
153 const rclcpp_lifecycle::State & get_state() const;
154
155 CONTROLLER_INTERFACE_PUBLIC
156 unsigned int get_update_rate() const;
157
159
165 template <typename ParameterT>
166 auto auto_declare(const std::string & name, const ParameterT & default_value)
167 {
168 if (!node_->has_parameter(name))
169 {
170 return node_->declare_parameter<ParameterT>(name, default_value);
171 }
172 else
173 {
174 return node_->get_parameter(name).get_value<ParameterT>();
175 }
176 }
177
178 // Methods for chainable controller types with default values so we can put all controllers into
179 // one list in Controller Manager
180
182
187 CONTROLLER_INTERFACE_PUBLIC
188 virtual bool is_chainable() const = 0;
189
196 CONTROLLER_INTERFACE_PUBLIC
197 virtual std::vector<hardware_interface::CommandInterface> export_reference_interfaces() = 0;
198
207 CONTROLLER_INTERFACE_PUBLIC
208 virtual bool set_chained_mode(bool chained_mode) = 0;
209
211
218 CONTROLLER_INTERFACE_PUBLIC
219 virtual bool is_in_chained_mode() const = 0;
220
221protected:
222 std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
223 std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
224 unsigned int update_rate_ = 0;
225
226private:
227 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
228};
229
230using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
231
232} // namespace controller_interface
233
234#endif // CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
Definition controller_interface_base.hpp:67
virtual CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::CommandInterface > export_reference_interfaces()=0
auto auto_declare(const std::string &name, const ParameterT &default_value)
Declare and initialize a parameter with a type.
Definition controller_interface_base.hpp:166
virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration state_interface_configuration() const =0
Get configuration for controller's required state interfaces.
virtual CONTROLLER_INTERFACE_PUBLIC CallbackReturn on_init()=0
Extending interface with initialization method which is individual for each controller.
virtual CONTROLLER_INTERFACE_PUBLIC bool set_chained_mode(bool chained_mode)=0
virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration command_interface_configuration() const =0
Get configuration for controller's required command interfaces.
virtual CONTROLLER_INTERFACE_PUBLIC bool is_in_chained_mode() const =0
Get information if a controller is currently in chained mode.
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure()
Custom configure method to read additional parameters for controller-nodes.
Definition controller_interface_base.cpp:74
virtual CONTROLLER_INTERFACE_PUBLIC bool is_chainable() const =0
Get information if a controller is chainable.
virtual CONTROLLER_INTERFACE_PUBLIC return_type update(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:56