Forward command controller for a set of joints. More...
#include <forward_joint_group_command_controller.h>
Public Member Functions | |
ForwardJointGroupCommandController () | |
bool | init (T *hw, ros::NodeHandle &n) |
void | starting (const ros::Time &time) |
void | update (const ros::Time &, const ros::Duration &) |
~ForwardJointGroupCommandController () | |
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_ |
Private Member Functions | |
void | commandCB (const std_msgs::Float64MultiArrayConstPtr &msg) |
Private Attributes | |
ros::Subscriber | sub_command_ |
Forward command controller for a set of joints.
This class forwards the command signal down to a set of joints. Command signal and joint hardware interface are of the same type, e.g. effort commands for an effort-controlled joint.
T | Type implementing the JointCommandInterface. |
type | hardware interface type. |
joints | Names of the joints to control. |
Subscribes to:
Definition at line 73 of file forward_joint_group_command_controller.h.
forward_command_controller::ForwardJointGroupCommandController< T >::ForwardJointGroupCommandController | ( | ) | [inline] |
Definition at line 76 of file forward_joint_group_command_controller.h.
forward_command_controller::ForwardJointGroupCommandController< T >::~ForwardJointGroupCommandController | ( | ) | [inline] |
Definition at line 77 of file forward_joint_group_command_controller.h.
void forward_command_controller::ForwardJointGroupCommandController< T >::commandCB | ( | const std_msgs::Float64MultiArrayConstPtr & | msg | ) | [inline, private] |
Definition at line 128 of file forward_joint_group_command_controller.h.
bool forward_command_controller::ForwardJointGroupCommandController< T >::init | ( | T * | hw, |
ros::NodeHandle & | n | ||
) | [inline, virtual] |
Reimplemented from controller_interface::Controller< T >.
Definition at line 79 of file forward_joint_group_command_controller.h.
void forward_command_controller::ForwardJointGroupCommandController< T >::starting | ( | const ros::Time & | time | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
void forward_command_controller::ForwardJointGroupCommandController< T >::update | ( | const ros::Time & | , |
const ros::Duration & | |||
) | [inline, virtual] |
Implements controller_interface::ControllerBase.
Definition at line 114 of file forward_joint_group_command_controller.h.
realtime_tools::RealtimeBuffer<std::vector<double> > forward_command_controller::ForwardJointGroupCommandController< T >::commands_buffer_ |
Definition at line 123 of file forward_joint_group_command_controller.h.
std::vector< std::string > forward_command_controller::ForwardJointGroupCommandController< T >::joint_names_ |
Definition at line 121 of file forward_joint_group_command_controller.h.
std::vector< hardware_interface::JointHandle > forward_command_controller::ForwardJointGroupCommandController< T >::joints_ |
Definition at line 122 of file forward_joint_group_command_controller.h.
unsigned int forward_command_controller::ForwardJointGroupCommandController< T >::n_joints_ |
Definition at line 124 of file forward_joint_group_command_controller.h.
ros::Subscriber forward_command_controller::ForwardJointGroupCommandController< T >::sub_command_ [private] |
Definition at line 127 of file forward_joint_group_command_controller.h.