A handle used to read and command a single joint. More...
#include <posvelacc_command_interface.h>
Public Member Functions | |
double | getCommandAcceleration () const |
PosVelAccJointHandle () | |
PosVelAccJointHandle (const JointStateHandle &js, double *cmd_pos, double *cmd_vel, double *cmd_acc) | |
void | setCommand (double cmd_pos, double cmd_vel, double cmd_acc) |
void | setCommandAcceleration (double cmd_acc) |
Private Attributes | |
double * | cmd_acc_ |
A handle used to read and command a single joint.
Definition at line 42 of file posvelacc_command_interface.h.
Definition at line 45 of file posvelacc_command_interface.h.
hardware_interface::PosVelAccJointHandle::PosVelAccJointHandle | ( | const JointStateHandle & | js, |
double * | cmd_pos, | ||
double * | cmd_vel, | ||
double * | cmd_acc | ||
) | [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 |
eff_cmd | A pointer to the storage for this joint's output command acceleration |
Definition at line 53 of file posvelacc_command_interface.h.
double hardware_interface::PosVelAccJointHandle::getCommandAcceleration | ( | ) | const [inline] |
Definition at line 70 of file posvelacc_command_interface.h.
void hardware_interface::PosVelAccJointHandle::setCommand | ( | double | cmd_pos, |
double | cmd_vel, | ||
double | cmd_acc | ||
) | [inline] |
Definition at line 62 of file posvelacc_command_interface.h.
void hardware_interface::PosVelAccJointHandle::setCommandAcceleration | ( | double | cmd_acc | ) | [inline] |
Definition at line 69 of file posvelacc_command_interface.h.
double* hardware_interface::PosVelAccJointHandle::cmd_acc_ [private] |
Definition at line 73 of file posvelacc_command_interface.h.