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 () | |
![]() | |
Controller () | |
virtual bool | init (T *, ros::NodeHandle &, ros::NodeHandle &) |
virtual | ~Controller () |
![]() | |
ControllerBase () | |
bool | isRunning () |
bool | isRunning () |
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 | ~ControllerBase () |
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_ |
![]() | |
CONSTRUCTED | |
INITIALIZED | |
RUNNING | |
enum controller_interface::ControllerBase:: { ... } | state_ |
Private Member Functions | |
void | commandCB (const std_msgs::Float64MultiArrayConstPtr &msg) |
Private Attributes | |
ros::Subscriber | sub_command_ |
Additional Inherited Members | |
![]() | |
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
![]() | |
std::string | getHardwareInterfaceType () const |
virtual bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) |
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.
|
inline |
Definition at line 76 of file forward_joint_group_command_controller.h.
|
inline |
Definition at line 77 of file forward_joint_group_command_controller.h.
|
inlineprivate |
Definition at line 128 of file forward_joint_group_command_controller.h.
|
inlinevirtual |
Reimplemented from controller_interface::Controller< T >.
Definition at line 79 of file forward_joint_group_command_controller.h.
|
virtual |
Reimplemented from controller_interface::ControllerBase.
|
inlinevirtual |
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.
|
private |
Definition at line 127 of file forward_joint_group_command_controller.h.