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/introspection.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"
33namespace controller_interface
35using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
37enum class return_type : std::uint8_t
49enum 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;
145 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
146 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
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);
162 const rclcpp_lifecycle::State &
configure();
176 virtual return_type
update(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
192 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
194 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node()
const;
196 const rclcpp_lifecycle::State & get_lifecycle_state()
const;
198 unsigned int get_update_rate()
const;
200 bool is_async()
const;
202 const std::string & get_robot_description()
const;
217 rclcpp::NodeOptions node_options;
219#if RCLCPP_VERSION_MAJOR >= 21
220 node_options.enable_logger_service(
true);
222 node_options.allow_undeclared_parameters(
true);
223 node_options.automatically_declare_parameters_from_overrides(
true);
235 template <
typename ParameterT>
236 auto auto_declare(
const std::string & name,
const ParameterT & default_value)
238 if (!node_->has_parameter(name))
240 return node_->declare_parameter<ParameterT>(name, default_value);
244 return node_->get_parameter(name).get_value<ParameterT>();
265 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
274 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
322 std::string get_name()
const;
357 void stop_async_handler_thread();
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;
368 pal_statistics::RegistrationsRAII stats_registrations_;
371using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
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