15#ifndef CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
16#define CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
23#include "realtime_tools/async_function_handler.hpp"
25#include "hardware_interface/handle.hpp"
26#include "hardware_interface/loaned_command_interface.hpp"
27#include "hardware_interface/loaned_state_interface.hpp"
29#include "rclcpp/version.h"
30#include "rclcpp_lifecycle/lifecycle_node.hpp"
32namespace controller_interface
34using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
36enum class return_type : std::uint8_t
48enum class interface_configuration_type : std::uint8_t
58 interface_configuration_type type;
59 std::vector<std::string> names = {};
70 unsigned int total_triggers;
71 unsigned int failed_triggers;
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;
144 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
145 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
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);
161 const rclcpp_lifecycle::State &
configure();
175 virtual return_type
update(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
191 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
193 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node()
const;
195 const rclcpp_lifecycle::State & get_lifecycle_state()
const;
197 unsigned int get_update_rate()
const;
199 bool is_async()
const;
201 const std::string & get_robot_description()
const;
216 rclcpp::NodeOptions node_options;
218#if RCLCPP_VERSION_MAJOR >= 21
219 node_options.enable_logger_service(
true);
221 node_options.allow_undeclared_parameters(
true);
222 node_options.automatically_declare_parameters_from_overrides(
true);
234 template <
typename ParameterT>
235 auto auto_declare(
const std::string & name,
const ParameterT & default_value)
237 if (!node_->has_parameter(name))
239 return node_->declare_parameter<ParameterT>(name, default_value);
243 return node_->get_parameter(name).get_value<ParameterT>();
264 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
273 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
309 std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
310 std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
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_ =
"";
321using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
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