|
| double | getCommandEffort () const |
| |
| double | getCommandKd () const |
| |
| double | getCommandKp () const |
| |
| | PositionVelocityTorqueGainsJointHandle ()=default |
| |
| | PositionVelocityTorqueGainsJointHandle (const JointStateHandle &js, double *cmd_pos, double *cmd_vel, double *cmd_eff, double *cmd_kp, double *cmd_kd) |
| |
| void | setCommand (double cmd_pos, double cmd_vel, double cmd_eff, double cmd_kp, double cmd_kd) |
| |
| void | setCommandEffort (double cmd_eff) |
| |
| void | setCommandKd (double cmd_kd) |
| |
| void | setCommandKp (double cmd_kp) |
| |
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 position_velocity_torque_gains_command_interface.h.