ros2_control - humble
Loading...
Searching...
No Matches
Public Member Functions | List of all members
position_controllers::JointGroupPositionController Class Reference

Forward command controller for a set of position controlled joints (linear or angular). More...

#include <joint_group_position_controller.hpp>

Inheritance diagram for position_controllers::JointGroupPositionController:
Inheritance graph
[legend]
Collaboration diagram for position_controllers::JointGroupPositionController:
Collaboration graph
[legend]

Public Member Functions

POSITION_CONTROLLERS_PUBLIC controller_interface::CallbackReturn on_init () override
 Extending interface with initialization method which is individual for each controller.
 
- Public Member Functions inherited from forward_command_controller::ForwardControllersBase
FORWARD_COMMAND_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
 Get configuration for controller's required command interfaces.
 
FORWARD_COMMAND_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
 Get configuration for controller's required state interfaces.
 
FORWARD_COMMAND_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
 
FORWARD_COMMAND_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
 
FORWARD_COMMAND_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
 
FORWARD_COMMAND_CONTROLLER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
 
- Public Member Functions inherited from controller_interface::ControllerInterface
CONTROLLER_INTERFACE_PUBLIC bool is_chainable () const final
 
CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::CommandInterfaceexport_reference_interfaces () final
 
CONTROLLER_INTERFACE_PUBLIC bool set_chained_mode (bool chained_mode) final
 
CONTROLLER_INTERFACE_PUBLIC bool is_in_chained_mode () const final
 
- Public Member Functions inherited from controller_interface::ControllerInterfaceBase
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, const std::string &namespace_="", const rclcpp::NodeOptions &node_options=rclcpp::NodeOptions() .allow_undeclared_parameters(true) .automatically_declare_parameters_from_overrides(true))
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure ()
 Custom configure method to read additional parameters for controller-nodes.
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp_lifecycle::LifecycleNode > get_node ()
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp_lifecycle::LifecycleNode > get_node () const
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_state () const
 
CONTROLLER_INTERFACE_PUBLIC unsigned int get_update_rate () const
 
template<typename ParameterT >
auto auto_declare (const std::string &name, const ParameterT &default_value)
 Declare and initialize a parameter with a type.
 

Additional Inherited Members

- Protected Member Functions inherited from forward_command_controller::ForwardCommandController
void declare_parameters () override
 
controller_interface::CallbackReturn read_parameters () override
 
- Protected Attributes inherited from forward_command_controller::ForwardCommandController
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::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::LoanedCommandInterfacecommand_interfaces_
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 
unsigned int update_rate_ = 0
 

Detailed Description

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.

Parameters
jointsNames of the joints to control.

Subscribes to:

Member Function Documentation

◆ on_init()

controller_interface::CallbackReturn position_controllers::JointGroupPositionController::on_init ( )
overridevirtual

Extending interface with initialization method which is individual for each controller.

Reimplemented from forward_command_controller::ForwardControllersBase.


The documentation for this class was generated from the following files: