15 #ifndef CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
16 #define CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
23 #include "controller_interface/visibility_control.h"
24 #include "realtime_tools/async_function_handler.hpp"
26 #include "hardware_interface/handle.hpp"
27 #include "hardware_interface/loaned_command_interface.hpp"
28 #include "hardware_interface/loaned_state_interface.hpp"
30 #include "rclcpp/version.h"
31 #include "rclcpp_lifecycle/lifecycle_node.hpp"
33 namespace controller_interface
35 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
37 enum class return_type : std::uint8_t
49 enum class interface_configuration_type : std::uint8_t
59 interface_configuration_type type;
60 std::vector<std::string> names = {};
71 unsigned int total_triggers;
72 unsigned int failed_triggers;
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;
101 CONTROLLER_INTERFACE_PUBLIC
104 CONTROLLER_INTERFACE_PUBLIC
119 CONTROLLER_INTERFACE_PUBLIC
136 CONTROLLER_INTERFACE_PUBLIC
148 CONTROLLER_INTERFACE_PUBLIC
150 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
151 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
157 CONTROLLER_INTERFACE_PUBLIC
160 CONTROLLER_INTERFACE_PUBLIC
162 const std::string & controller_name,
const std::string & urdf,
unsigned int cm_update_rate,
163 const std::string & node_namespace,
const rclcpp::NodeOptions & node_options);
169 CONTROLLER_INTERFACE_PUBLIC
170 const rclcpp_lifecycle::State &
configure();
173 CONTROLLER_INTERFACE_PUBLIC
185 CONTROLLER_INTERFACE_PUBLIC
186 virtual return_type
update(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
200 CONTROLLER_INTERFACE_PUBLIC
203 CONTROLLER_INTERFACE_PUBLIC
204 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
206 CONTROLLER_INTERFACE_PUBLIC
207 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node()
const;
209 CONTROLLER_INTERFACE_PUBLIC
210 const rclcpp_lifecycle::State & get_lifecycle_state()
const;
212 CONTROLLER_INTERFACE_PUBLIC
213 unsigned int get_update_rate()
const;
215 CONTROLLER_INTERFACE_PUBLIC
216 bool is_async()
const;
218 CONTROLLER_INTERFACE_PUBLIC
219 const std::string & get_robot_description()
const;
232 CONTROLLER_INTERFACE_PUBLIC
235 rclcpp::NodeOptions node_options;
237 #if RCLCPP_VERSION_MAJOR >= 21
238 node_options.enable_logger_service(
true);
240 node_options.allow_undeclared_parameters(
true);
241 node_options.automatically_declare_parameters_from_overrides(
true);
253 template <
typename ParameterT>
254 auto auto_declare(
const std::string & name,
const ParameterT & default_value)
256 if (!node_->has_parameter(name))
258 return node_->declare_parameter<ParameterT>(name, default_value);
262 return node_->get_parameter(name).get_value<ParameterT>();
275 CONTROLLER_INTERFACE_PUBLIC
284 CONTROLLER_INTERFACE_PUBLIC
285 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
294 CONTROLLER_INTERFACE_PUBLIC
295 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
306 CONTROLLER_INTERFACE_PUBLIC
317 CONTROLLER_INTERFACE_PUBLIC
330 CONTROLLER_INTERFACE_PUBLIC
334 std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
335 std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
338 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
339 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
340 unsigned int update_rate_ = 0;
341 bool is_async_ =
false;
342 std::string urdf_ =
"";
346 using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
Definition: controller_interface_base.hpp:99
auto auto_declare(const std::string &name, const ParameterT &default_value)
Declare and initialize a parameter with a type.
Definition: controller_interface_base.hpp:254
virtual CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::StateInterface::ConstSharedPtr > export_state_interfaces()=0
virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration state_interface_configuration() const =0
Get configuration for controller's required state interfaces.
CONTROLLER_INTERFACE_PUBLIC void wait_for_trigger_update_to_finish()
Definition: controller_interface_base.cpp:229
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 std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces()=0
virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration command_interface_configuration() const =0
Get configuration for controller's required command interfaces.
virtual CONTROLLER_INTERFACE_PUBLIC void release_interfaces()
Method that releases the Loaned interfaces from the controller.
Definition: controller_interface_base.cpp:153
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:94
CONTROLLER_INTERFACE_PUBLIC ControllerUpdateStatus trigger_update(const rclcpp::Time &time, const rclcpp::Duration &period)
Definition: controller_interface_base.cpp:164
virtual CONTROLLER_INTERFACE_PUBLIC 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:145
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
virtual CONTROLLER_INTERFACE_PUBLIC rclcpp::NodeOptions define_custom_node_options() const
Definition: controller_interface_base.hpp:233
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