A handle used to read and command a single joint. More...
#include <posvel_command_interface.h>
Public Member Functions | |
double | getCommandPosition () const |
double | getCommandVelocity () const |
PosVelJointHandle () | |
PosVelJointHandle (const JointStateHandle &js, double *cmd_pos, double *cmd_vel) | |
void | setCommand (double cmd_pos, double cmd_vel) |
void | setCommandPosition (double cmd_pos) |
void | setCommandVelocity (double cmd_vel) |
Private Attributes | |
double * | cmd_pos_ |
double * | cmd_vel_ |
A handle used to read and command a single joint.
Definition at line 42 of file posvel_command_interface.h.
Definition at line 45 of file posvel_command_interface.h.
hardware_interface::PosVelJointHandle::PosVelJointHandle | ( | const JointStateHandle & | js, |
double * | cmd_pos, | ||
double * | cmd_vel | ||
) | [inline] |
js | This joint's state handle |
cmd_pos | A pointer to the storage for this joint's output command position |
cmd_vel | A pointer to the storage for this joint's output command velocity |
Definition at line 52 of file posvel_command_interface.h.
double hardware_interface::PosVelJointHandle::getCommandPosition | ( | ) | const [inline] |
Definition at line 74 of file posvel_command_interface.h.
double hardware_interface::PosVelJointHandle::getCommandVelocity | ( | ) | const [inline] |
Definition at line 75 of file posvel_command_interface.h.
void hardware_interface::PosVelJointHandle::setCommand | ( | double | cmd_pos, |
double | cmd_vel | ||
) | [inline] |
Definition at line 65 of file posvel_command_interface.h.
void hardware_interface::PosVelJointHandle::setCommandPosition | ( | double | cmd_pos | ) | [inline] |
Definition at line 71 of file posvel_command_interface.h.
void hardware_interface::PosVelJointHandle::setCommandVelocity | ( | double | cmd_vel | ) | [inline] |
Definition at line 72 of file posvel_command_interface.h.
double* hardware_interface::PosVelJointHandle::cmd_pos_ [private] |
Definition at line 78 of file posvel_command_interface.h.
double* hardware_interface::PosVelJointHandle::cmd_vel_ [private] |
Definition at line 79 of file posvel_command_interface.h.