A handle used to read and command a single joint.
More...
#include <posvel_command_interface.h>
|
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 posvel_command_interface.h.
◆ PosVelJointHandle() [1/2]
hardware_interface::PosVelJointHandle::PosVelJointHandle |
( |
| ) |
|
|
default |
◆ PosVelJointHandle() [2/2]
hardware_interface::PosVelJointHandle::PosVelJointHandle |
( |
const JointStateHandle & |
js, |
|
|
double * |
cmd_pos, |
|
|
double * |
cmd_vel |
|
) |
| |
|
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 |
Definition at line 52 of file posvel_command_interface.h.
◆ getCommandPosition()
double hardware_interface::PosVelJointHandle::getCommandPosition |
( |
| ) |
const |
|
inline |
◆ getCommandVelocity()
double hardware_interface::PosVelJointHandle::getCommandVelocity |
( |
| ) |
const |
|
inline |
◆ setCommand()
void hardware_interface::PosVelJointHandle::setCommand |
( |
double |
cmd_pos, |
|
|
double |
cmd_vel |
|
) |
| |
|
inline |
◆ setCommandPosition()
void hardware_interface::PosVelJointHandle::setCommandPosition |
( |
double |
cmd_pos | ) |
|
|
inline |
◆ setCommandVelocity()
void hardware_interface::PosVelJointHandle::setCommandVelocity |
( |
double |
cmd_vel | ) |
|
|
inline |
◆ cmd_pos_
double* hardware_interface::PosVelJointHandle::cmd_pos_ = {nullptr} |
|
private |
◆ cmd_vel_
double* hardware_interface::PosVelJointHandle::cmd_vel_ = {nullptr} |
|
private |
The documentation for this class was generated from the following file: