15#ifndef CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
16#define CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_BASE_HPP_
20#include <unordered_map>
24#include "realtime_tools/async_function_handler.hpp"
26#include "controller_interface/controller_interface_params.hpp"
27#include "hardware_interface/handle.hpp"
28#include "hardware_interface/introspection.hpp"
29#include "hardware_interface/loaned_command_interface.hpp"
30#include "hardware_interface/loaned_state_interface.hpp"
32#include "lifecycle_msgs/msg/state.hpp"
33#include "rclcpp/version.h"
34#include "rclcpp_lifecycle/lifecycle_node.hpp"
36namespace controller_interface
38using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
40enum class return_type : std::uint8_t
57enum class interface_configuration_type : std::uint8_t
62 INDIVIDUAL_BEST_EFFORT = 3,
69 interface_configuration_type type = interface_configuration_type::NONE;
70 std::vector<std::string> names = {};
81 unsigned int total_triggers;
82 unsigned int failed_triggers;
97 bool successful =
true;
98 return_type result = return_type::OK;
99 std::optional<std::chrono::nanoseconds> execution_time = std::nullopt;
100 std::optional<rclcpp::Duration> period = std::nullopt;
155 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
156 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
165 "Use the init(const controller_interface::ControllerInterfaceParams & params) method instead. "
166 "This method will be removed in the future ROS 2 releases.")]]
168 const std::string & controller_name,
const std::string & urdf,
unsigned int cm_update_rate,
169 const std::string & node_namespace,
const rclcpp::NodeOptions & node_options);
177 const rclcpp_lifecycle::State &
configure();
191 virtual return_type
update(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
207 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
209 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node()
const;
228 unsigned int get_update_rate()
const;
230 bool is_async()
const;
232 const std::string & get_robot_description()
const;
258 rclcpp::NodeOptions node_options;
260#if RCLCPP_VERSION_MAJOR >= 21
261 node_options.enable_logger_service(
true);
263 node_options.allow_undeclared_parameters(
true);
264 node_options.automatically_declare_parameters_from_overrides(
true);
276 template <
typename ParameterT>
277 auto auto_declare(
const std::string & name,
const ParameterT & default_value)
279 if (!get_node()->has_parameter(name))
281 return get_node()->declare_parameter<ParameterT>(name, default_value);
285 return get_node()->get_parameter(name).get_value<ParameterT>();
306 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
315 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
363 std::string get_name()
const;
406 void stop_async_handler_thread();
409 std::unique_ptr<ControllerInterfaceBaseImpl> impl_;
412 pal_statistics::RegistrationsRAII stats_registrations_;
415using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
Definition controller_interface_base.hpp:109
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:277
std::vector< hardware_interface::LoanedCommandInterface > command_interfaces_
Definition controller_interface_base.hpp:385
virtual CallbackReturn on_init()=0
Extending interface with initialization method which is individual for each controller.
const std::unordered_map< std::string, joint_limits::JointLimits > & get_hard_joint_limits() const
Definition controller_interface_base.cpp:407
const std::unordered_map< std::string, joint_limits::SoftJointLimits > & get_soft_joint_limits() const
Definition controller_interface_base.cpp:413
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:442
void wait_for_trigger_update_to_finish()
Definition controller_interface_base.cpp:418
uint8_t get_lifecycle_id() const
Definition controller_interface_base.cpp:310
virtual std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces()=0
const rclcpp_lifecycle::State & get_lifecycle_state() const
Definition controller_interface_base.cpp:301
virtual void release_interfaces()
Method that releases the Loaned interfaces from the controller.
Definition controller_interface_base.cpp:295
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:187
ControllerUpdateStatus trigger_update(const rclcpp::Time &time, const rclcpp::Duration &period)
Definition controller_interface_base.cpp:328
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:287
virtual rclcpp::NodeOptions define_custom_node_options() const
Definition controller_interface_base.hpp:256
std::vector< hardware_interface::LoanedStateInterface > state_interfaces_
Definition controller_interface_base.hpp:399
virtual bool is_chainable() const =0
Get information if a controller is chainable.
void prepare_for_deactivation()
Definition controller_interface_base.cpp:426
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.cpp:27
Definition controller_interface_params.hpp:44
Definition controller_interface_base.hpp:74
Definition controller_interface_base.hpp:96
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:68