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 "pal_statistics/pal_statistics_utils.hpp"
34#include "rclcpp/version.h"
35#include "rclcpp_lifecycle/lifecycle_node.hpp"
37namespace controller_interface
39using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
41enum class return_type : std::uint8_t
59enum class interface_configuration_type : std::uint8_t
64 INDIVIDUAL_BEST_EFFORT = 3,
73 interface_configuration_type type = interface_configuration_type::NONE;
74 std::vector<std::string> names = {};
85 unsigned int total_triggers;
86 unsigned int failed_triggers;
101 bool successful =
true;
102 return_type result = return_type::OK;
103 std::optional<std::chrono::nanoseconds> execution_time = std::nullopt;
104 std::optional<rclcpp::Duration> period = std::nullopt;
162 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
163 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
173 "Use the init(const controller_interface::ControllerInterfaceParams & params) method instead. "
174 "This method will be removed in the future ROS 2 releases.")]]
176 const std::string & controller_name,
const std::string & urdf,
unsigned int cm_update_rate,
177 const std::string & node_namespace,
const rclcpp::NodeOptions & node_options);
186 const rclcpp_lifecycle::State &
configure();
202 virtual return_type
update(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
217 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
219 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node()
const;
238 unsigned int get_update_rate()
const;
240 bool is_async()
const;
242 const std::string & get_robot_description()
const;
268 rclcpp::NodeOptions node_options;
270#if RCLCPP_VERSION_MAJOR >= 21
271 node_options.enable_logger_service(
true);
273 node_options.allow_undeclared_parameters(
true);
274 node_options.automatically_declare_parameters_from_overrides(
true);
286 template <
typename ParameterT>
287 auto auto_declare(
const std::string & name,
const ParameterT & default_value)
289 if (!get_node()->has_parameter(name))
291 return get_node()->declare_parameter<ParameterT>(name, default_value);
295 return get_node()->get_parameter(name).get_value<ParameterT>();
317 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
326 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
377 std::string get_name()
const;
423 void stop_async_handler_thread();
426 std::unique_ptr<ControllerInterfaceBaseImpl> impl_;
429 pal_statistics::RegistrationsRAII stats_registrations_;
432using ControllerInterfaceBaseSharedPtr = std::shared_ptr<ControllerInterfaceBase>;
Base interface class for an controller. The interface may not be used to implement a controller....
Definition controller_interface_base.hpp:113
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:287
std::vector< hardware_interface::LoanedCommandInterface > command_interfaces_
Loaned command interfaces.
Definition controller_interface_base.hpp:401
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
Get the unordered map of joint limits that are defined in the robot description.
Definition controller_interface_base.cpp:407
const std::unordered_map< std::string, joint_limits::SoftJointLimits > & get_soft_joint_limits() const
Get the unordered map of soft joint limits that are defined in the robot description.
Definition controller_interface_base.cpp:413
virtual std::vector< hardware_interface::StateInterface::ConstSharedPtr > export_state_interfaces()=0
Export interfaces for a chainable controller that can be used as state interface by other controllers...
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()
Method to wait for any running async update cycle to finish after finishing the current cycle....
Definition controller_interface_base.cpp:418
uint8_t get_lifecycle_id() const
Get the lifecycle id of the controller node that is cached internally to avoid calls to get_lifecycle...
Definition controller_interface_base.cpp:310
virtual std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces()=0
Export interfaces for a chainable controller that can be used as command interface of other controlle...
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get the current lifecycle state of the controller node.
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)
Trigger update method. This method is used by the controller_manager to trigger the update method of ...
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
Method used by the controller_manager for base NodeOptions to instantiate the Lifecycle node of the c...
Definition controller_interface_base.hpp:266
std::vector< hardware_interface::LoanedStateInterface > state_interfaces_
Loaned state interfaces.
Definition controller_interface_base.hpp:416
virtual bool is_chainable() const =0
Get information if a controller is chainable.
void prepare_for_deactivation()
Method to prepare the controller for deactivation. This method is called by the controller manager be...
Definition controller_interface_base.cpp:426
virtual bool set_chained_mode(bool chained_mode)=0
Set chained mode of a chainable controller. This method triggers internal processes to switch a chain...
virtual return_type update(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Control step update. Command interfaces are updated based on on reference inputs and current states....
Definition controller_interface_base.cpp:27
Definition controller_interface_params.hpp:44
Definition controller_interface_base.hpp:78
Definition controller_interface_base.hpp:100
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:72