Forward command controller for a set of effort controlled joints (torque or force). More...
#include <joint_group_position_controller.h>

| Public Member Functions | |
| bool | init (hardware_interface::EffortJointInterface *hw, ros::NodeHandle &n) | 
| JointGroupPositionController () | |
| Forward command controller for a set of effort controlled joints (torque or force).  More... | |
| void | update (const ros::Time &, const ros::Duration &) | 
| ~JointGroupPositionController () | |
|  Public Member Functions inherited from controller_interface::Controller< hardware_interface::EffortJointInterface > | |
| virtual bool | init (T *, ros::NodeHandle &) | 
| virtual bool | init (T *, ros::NodeHandle &, ros::NodeHandle &) | 
|  Public Member Functions inherited from controller_interface::ControllerBase | |
| virtual void | aborting (const ros::Time &) | 
| virtual void | aborting (const ros::Time &) | 
| bool | abortRequest (const ros::Time &time) | 
| bool | abortRequest (const ros::Time &time) | 
| ControllerBase ()=default | |
| ControllerBase (const ControllerBase &)=delete | |
| ControllerBase (ControllerBase &&)=delete | |
| bool | isAborted () const | 
| bool | isAborted () const | 
| bool | isInitialized () const | 
| bool | isInitialized () const | 
| bool | isRunning () const | 
| bool | isRunning () const | 
| bool | isStopped () const | 
| bool | isStopped () const | 
| bool | isWaiting () const | 
| bool | isWaiting () const | 
| ControllerBase & | operator= (const ControllerBase &)=delete | 
| ControllerBase & | operator= (ControllerBase &&)=delete | 
| virtual void | starting (const ros::Time &) | 
| virtual void | starting (const ros::Time &) | 
| bool | startRequest (const ros::Time &time) | 
| bool | startRequest (const ros::Time &time) | 
| virtual void | stopping (const ros::Time &) | 
| virtual void | stopping (const ros::Time &) | 
| bool | stopRequest (const ros::Time &time) | 
| bool | stopRequest (const ros::Time &time) | 
| void | updateRequest (const ros::Time &time, const ros::Duration &period) | 
| void | updateRequest (const ros::Time &time, const ros::Duration &period) | 
| virtual void | waiting (const ros::Time &) | 
| virtual void | waiting (const ros::Time &) | 
| bool | waitRequest (const ros::Time &time) | 
| bool | waitRequest (const ros::Time &time) | 
| virtual | ~ControllerBase ()=default | 
| Public Attributes | |
| realtime_tools::RealtimeBuffer< std::vector< double > > | commands_buffer_ | 
| std::vector< std::string > | joint_names_ | 
| std::vector< hardware_interface::JointHandle > | joints_ | 
| unsigned int | n_joints_ | 
|  Public Attributes inherited from controller_interface::ControllerBase | |
| ABORTED | |
| CONSTRUCTED | |
| INITIALIZED | |
| RUNNING | |
| enum controller_interface::ControllerBase:: { ... } | state_ | 
| STOPPED | |
| WAITING | |
| Private Member Functions | |
| void | commandCB (const std_msgs::Float64MultiArrayConstPtr &msg) | 
| void | enforceJointLimits (double &command, unsigned int index) | 
| Private Attributes | |
| std::vector< urdf::JointConstSharedPtr > | joint_urdfs_ | 
| std::vector< control_toolbox::Pid > | pid_controllers_ | 
| ros::Subscriber | sub_command_ | 
| Additional Inherited Members | |
|  Public Types inherited from controller_interface::ControllerBase | |
| typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources | 
|  Protected Member Functions inherited from controller_interface::Controller< hardware_interface::EffortJointInterface > | |
| std::string | getHardwareInterfaceType () const | 
| bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override | 
Forward command controller for a set of effort controlled joints (torque or force).
This class forwards the commanded efforts down to a set of joints.
| type | Must be "JointGroupEffortController". | 
| joints | List of names of the joints to control. | 
Subscribes to:
Definition at line 67 of file joint_group_position_controller.h.
| effort_controllers::JointGroupPositionController::JointGroupPositionController | ( | ) | 
Forward command controller for a set of effort controlled joints (torque or force).
This class forwards the commanded efforts down to a set of joints.
| type | Must be "JointGroupEffortController". | 
| joints | List of names of the joints to control. | 
Subscribes to:
Definition at line 58 of file joint_group_position_controller.cpp.
| effort_controllers::JointGroupPositionController::~JointGroupPositionController | ( | ) | 
Definition at line 59 of file joint_group_position_controller.cpp.
| 
 | private | 
Definition at line 165 of file joint_group_position_controller.cpp.
| 
 | private | 
Definition at line 175 of file joint_group_position_controller.cpp.
| bool effort_controllers::JointGroupPositionController::init | ( | hardware_interface::EffortJointInterface * | hw, | 
| ros::NodeHandle & | n | ||
| ) | 
Definition at line 61 of file joint_group_position_controller.cpp.
| 
 | virtual | 
Implements controller_interface::ControllerBase.
Definition at line 123 of file joint_group_position_controller.cpp.
| realtime_tools::RealtimeBuffer<std::vector<double> > effort_controllers::JointGroupPositionController::commands_buffer_ | 
Definition at line 78 of file joint_group_position_controller.h.
| std::vector< std::string > effort_controllers::JointGroupPositionController::joint_names_ | 
Definition at line 76 of file joint_group_position_controller.h.
| 
 | private | 
Definition at line 86 of file joint_group_position_controller.h.
| std::vector< hardware_interface::JointHandle > effort_controllers::JointGroupPositionController::joints_ | 
Definition at line 77 of file joint_group_position_controller.h.
| unsigned int effort_controllers::JointGroupPositionController::n_joints_ | 
Definition at line 79 of file joint_group_position_controller.h.
| 
 | private | 
Internal PID controllers.
Definition at line 84 of file joint_group_position_controller.h.
| 
 | private | 
Definition at line 82 of file joint_group_position_controller.h.