![]() |
ros2_control - foxy
|
Forward command controller for a set of position controlled joints (linear or angular). More...
#include <joint_group_position_controller.hpp>


Public Member Functions | |
| POSITION_CONTROLLERS_PUBLIC controller_interface::return_type | init (const std::string &controller_name) override |
Public Member Functions inherited from forward_command_controller::ForwardCommandController | |
| FORWARD_COMMAND_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration | command_interface_configuration () const override |
| FORWARD_COMMAND_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration | state_interface_configuration () const override |
| FORWARD_COMMAND_CONTROLLER_PUBLIC CallbackReturn | on_configure (const rclcpp_lifecycle::State &previous_state) override |
| FORWARD_COMMAND_CONTROLLER_PUBLIC CallbackReturn | on_activate (const rclcpp_lifecycle::State &previous_state) override |
| FORWARD_COMMAND_CONTROLLER_PUBLIC CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &previous_state) override |
| FORWARD_COMMAND_CONTROLLER_PUBLIC controller_interface::return_type | update () override |
Public Member Functions inherited from controller_interface::ControllerInterface | |
| CONTROLLER_INTERFACE_PUBLIC void | assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces) |
| CONTROLLER_INTERFACE_PUBLIC void | release_interfaces () |
| virtual CONTROLLER_INTERFACE_PUBLIC return_type | init (const std::string &controller_name, rclcpp::NodeOptions &node_options) |
| CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp::Node > | get_node () |
| template<typename ParameterT > | |
| auto | auto_declare (const std::string &name, const ParameterT &default_value) |
| Declare and initialize a parameter with a type. | |
| CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | configure () |
| CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | cleanup () |
| CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | deactivate () |
| CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | activate () |
| CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | shutdown () |
| CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | get_current_state () const |
Additional Inherited Members | |
Protected Attributes inherited from forward_command_controller::ForwardCommandController | |
| std::vector< std::string > | joint_names_ |
| std::string | interface_name_ |
| realtime_tools::RealtimeBuffer< std::shared_ptr< CmdType > > | rt_command_ptr_ |
| rclcpp::Subscription< CmdType >::SharedPtr | joints_command_subscriber_ |
| std::string | logger_name_ |
Protected Attributes inherited from controller_interface::ControllerInterface | |
| std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ |
| std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
| std::shared_ptr< rclcpp::Node > | node_ |
| rclcpp_lifecycle::State | lifecycle_state_ |
Forward command controller for a set of position controlled joints (linear or angular).
This class forwards the commanded positions down to a set of joints.
| joints | Names of the joints to control. |
Subscribes to:
|
overridevirtual |
Reimplemented from forward_command_controller::ForwardCommandController.