A handle used to read and command a single joint.
More...
#include <posvelacc_command_interface.h>
|
double | getCommandAcceleration () const |
|
| PosVelAccJointHandle ()=default |
|
| 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) |
|
Public Member Functions inherited from hardware_interface::PosVelJointHandle |
double | getCommandPosition () const |
|
double | getCommandVelocity () const |
|
| PosVelJointHandle ()=default |
|
| 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) |
|
Public Member Functions inherited from hardware_interface::JointStateHandle |
double | getAbsolutePosition () const |
|
const double * | getAbsolutePositionPtr () const |
|
double | getEffort () const |
|
const double * | getEffortPtr () const |
|
std::string | getName () const |
|
double | getPosition () const |
|
const double * | getPositionPtr () const |
|
double | getTorqueSensor () const |
|
const double * | getTorqueSensorPtr () const |
|
double | getVelocity () const |
|
const double * | getVelocityPtr () const |
|
bool | hasAbsolutePosition () const |
|
bool | hasTorqueSensor () const |
|
| JointStateHandle ()=default |
|
| JointStateHandle (const std::string &name, const double *pos, const double *vel, const double *eff) |
|
| JointStateHandle (const std::string &name, const double *pos, const double *vel, const double *eff, const double *absolute_pos) |
|
| JointStateHandle (const std::string &name, const double *pos, const double *vel, const double *eff, const double *absolute_pos, const double *torque_sensor) |
|
| JointStateHandle (const std::string &name, const double *pos, const double *vel, const double *eff, const double *torque_sensor, bool) |
|
A handle used to read and command a single joint.
Definition at line 42 of file posvelacc_command_interface.h.
◆ PosVelAccJointHandle() [1/2]
hardware_interface::PosVelAccJointHandle::PosVelAccJointHandle |
( |
| ) |
|
|
default |
◆ PosVelAccJointHandle() [2/2]
hardware_interface::PosVelAccJointHandle::PosVelAccJointHandle |
( |
const JointStateHandle & |
js, |
|
|
double * |
cmd_pos, |
|
|
double * |
cmd_vel, |
|
|
double * |
cmd_acc |
|
) |
| |
|
inline |
- Parameters
-
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.
◆ getCommandAcceleration()
double hardware_interface::PosVelAccJointHandle::getCommandAcceleration |
( |
| ) |
const |
|
inline |
◆ setCommand()
void hardware_interface::PosVelAccJointHandle::setCommand |
( |
double |
cmd_pos, |
|
|
double |
cmd_vel, |
|
|
double |
cmd_acc |
|
) |
| |
|
inline |
◆ setCommandAcceleration()
void hardware_interface::PosVelAccJointHandle::setCommandAcceleration |
( |
double |
cmd_acc | ) |
|
|
inline |
◆ cmd_acc_
double* hardware_interface::PosVelAccJointHandle::cmd_acc_ = {nullptr} |
|
private |
The documentation for this class was generated from the following file: