ros2_control - rolling
|
Forward command controller for a set of joints and interfaces. More...
#include <forward_controllers_base.hpp>
Public Member Functions | |
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) |
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 |
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 () |
Protected Member Functions | |
virtual void | declare_parameters ()=0 |
virtual controller_interface::CallbackReturn | read_parameters ()=0 |
Protected Attributes | |
std::vector< std::string > | joint_names_ |
std::string | interface_name_ |
std::vector< std::string > | command_interface_types_ |
realtime_tools::RealtimeBuffer< std::shared_ptr< CmdType > > | rt_command_ptr_ |
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_ |
Forward command controller for a set of joints and interfaces.
This class forwards the command signal down to a set of joints or interfaces.
Subscribes to:
|
overridevirtual |
Get configuration for controller's required command interfaces.
Method used by the controller_manager to get the set of command interfaces used by the controller. Each controller can use individual method to determine interface names that in simples case have the following format: <joint>/<interface>
. The method is called only in inactive
or active
state, i.e., on_configure
has to be called first. The configuration is used to check if controller can be activated and to claim interfaces from hardware. The claimed interfaces are populated in the command_interfaces_ member.
Implements controller_interface::ControllerInterfaceBase.
|
protectedpure virtual |
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.
Implemented in forward_command_controller::ForwardCommandController, and forward_command_controller::MultiInterfaceForwardCommandController.
|
overridevirtual |
Extending interface with initialization method which is individual for each controller.
Implements controller_interface::ControllerInterfaceBase.
Reimplemented in effort_controllers::JointGroupEffortController, position_controllers::JointGroupPositionController, and velocity_controllers::JointGroupVelocityController.
|
protectedpure virtual |
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.
Implemented in forward_command_controller::ForwardCommandController, and forward_command_controller::MultiInterfaceForwardCommandController.
|
overridevirtual |
Get configuration for controller's required state interfaces.
Method used by the controller_manager to get the set of state interface used by the controller. Each controller can use individual method to determine interface names that in simples case have the following format: <joint>/<interface>
. The method is called only in inactive
or active
state, i.e., on_configure
has to be called first. The configuration is used to check if controller can be activated and to claim interfaces from hardware. The claimed interfaces are populated in the state_interfaces_ member.
Implements controller_interface::ControllerInterfaceBase.
|
overridevirtual |
Control step update. Command interfaces are updated based on on reference inputs and current states. The method called in the (real-time) control loop.
[in] | time | The time at the start of this control loop iteration |
[in] | period | The measured time since the last control loop iteration |
Implements controller_interface::ControllerInterfaceBase.