![]() |
ros2_control - rolling
|
Multi interface forward command controller for a set of interfaces. More...
#include <multi_interface_forward_command_controller.hpp>


Protected Types | |
| using | Params = multi_interface_forward_command_controller::Params |
| using | ParamListener = multi_interface_forward_command_controller::ParamListener |
Protected Member Functions | |
| void | declare_parameters () override |
| controller_interface::CallbackReturn | read_parameters () override |
Protected Attributes | |
| std::shared_ptr< ParamListener > | param_listener_ |
| Params | params_ |
Protected Attributes inherited from forward_command_controller::ForwardControllersBase | |
| std::vector< std::string > | joint_names_ |
| std::string | interface_name_ |
| std::vector< std::string > | command_interface_types_ |
| realtime_tools::RealtimeThreadSafeBox< CmdType > | rt_command_ |
| CmdType | joint_commands_ |
| rclcpp::Subscription< CmdType >::SharedPtr | joints_command_subscriber_ |
Protected Attributes inherited from controller_interface::ControllerInterfaceBase | |
| std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ |
| std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
| pal_statistics::RegistrationsRAII | stats_registrations_ |
Additional Inherited Members | |
Public Member Functions inherited from forward_command_controller::ForwardControllersBase | |
| controller_interface::InterfaceConfiguration | command_interface_configuration () const override |
| Get configuration for controller's required command interfaces. | |
| controller_interface::InterfaceConfiguration | state_interface_configuration () const override |
| Get configuration for controller's required state interfaces. | |
| controller_interface::CallbackReturn | on_init () override |
| Extending interface with initialization method which is individual for each controller. | |
| controller_interface::CallbackReturn | on_configure (const rclcpp_lifecycle::State &previous_state) override |
| controller_interface::CallbackReturn | on_activate (const rclcpp_lifecycle::State &previous_state) override |
| controller_interface::CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &previous_state) override |
| controller_interface::return_type | update (const rclcpp::Time &time, const rclcpp::Duration &period) override |
Public Member Functions inherited from controller_interface::ControllerInterface | |
| bool | is_chainable () const final |
| std::vector< hardware_interface::StateInterface::ConstSharedPtr > | export_state_interfaces () final |
| std::vector< hardware_interface::CommandInterface::SharedPtr > | export_reference_interfaces () final |
| bool | set_chained_mode (bool chained_mode) final |
| bool | is_in_chained_mode () const final |
Public Member Functions inherited from controller_interface::ControllerInterfaceBase | |
| 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. | |
| virtual void | release_interfaces () |
| Method that releases the Loaned interfaces from the controller. | |
| return_type | init (const std::string &controller_name, const std::string &urdf, unsigned int cm_update_rate, const std::string &node_namespace, const rclcpp::NodeOptions &node_options) |
| return_type | init (const controller_interface::ControllerInterfaceParams ¶ms) |
| const rclcpp_lifecycle::State & | configure () |
| Custom configure method to read additional parameters for controller-nodes. | |
| ControllerUpdateStatus | trigger_update (const rclcpp::Time &time, const rclcpp::Duration &period) |
| std::shared_ptr< rclcpp_lifecycle::LifecycleNode > | get_node () |
| std::shared_ptr< const rclcpp_lifecycle::LifecycleNode > | get_node () const |
| const rclcpp_lifecycle::State & | get_lifecycle_state () const |
| unsigned int | get_update_rate () const |
| bool | is_async () const |
| const std::string & | get_robot_description () const |
| const std::unordered_map< std::string, joint_limits::JointLimits > & | get_hard_joint_limits () const |
| const std::unordered_map< std::string, joint_limits::SoftJointLimits > & | get_soft_joint_limits () const |
| virtual rclcpp::NodeOptions | define_custom_node_options () const |
| template<typename ParameterT > | |
| auto | auto_declare (const std::string &name, const ParameterT &default_value) |
| Declare and initialize a parameter with a type. | |
| void | wait_for_trigger_update_to_finish () |
| void | prepare_for_deactivation () |
| std::string | get_name () const |
| void | enable_introspection (bool enable) |
| Enable or disable introspection of the controller. | |
Multi interface forward command controller for a set of interfaces.
This class forwards the command signal down to a set of interfaces on the specified joint.
| joint | Name of the joint to control. |
| interface_names | Names of the interfaces to command. |
Subscribes to:
|
overrideprotectedvirtual |
Derived controllers have to declare parameters in this method. Error handling does not have to be done. It is done in on_init-method of this class.
Implements forward_command_controller::ForwardControllersBase.
|
overrideprotectedvirtual |
Derived controllers have to read parameters in this method and set command_interface_types_ variable. The variable is then used to propagate the command interface configuration to controller manager. The method is called from on_configure-method of this class.
It is expected that error handling of exceptions is done.
Implements forward_command_controller::ForwardControllersBase.