Public Member Functions | Private Attributes | List of all members
hardware_interface::PositionVelocityTorqueGainsJointHandle Class Reference

A handle used to read and command a single joint. More...

#include <position_velocity_torque_gains_command_interface.h>

Inheritance diagram for hardware_interface::PositionVelocityTorqueGainsJointHandle:
Inheritance graph
[legend]

Public Member Functions

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)
 

Private Attributes

double * cmd_eff_ = {nullptr}
 
double * cmd_kd_ = {nullptr}
 
double * cmd_kp_ = {nullptr}
 

Detailed Description

A handle used to read and command a single joint.

Definition at line 42 of file position_velocity_torque_gains_command_interface.h.

Constructor & Destructor Documentation

◆ PositionVelocityTorqueGainsJointHandle() [1/2]

hardware_interface::PositionVelocityTorqueGainsJointHandle::PositionVelocityTorqueGainsJointHandle ( )
default

◆ PositionVelocityTorqueGainsJointHandle() [2/2]

hardware_interface::PositionVelocityTorqueGainsJointHandle::PositionVelocityTorqueGainsJointHandle ( const JointStateHandle js,
double *  cmd_pos,
double *  cmd_vel,
double *  cmd_eff,
double *  cmd_kp,
double *  cmd_kd 
)
inline
Parameters
jsThis joint's state handle
cmd_posA pointer to the storage for this joint's output command position
cmd_velA pointer to the storage for this joint's output command velocity
cmd_effA pointer to the storage for this joint's output command feed-forward torque
cmd_kpA pointer to the storage for this joint's position tracking gain
cmd_kdA pointer to the storage for this joint's velocity tracking gain

Definition at line 55 of file position_velocity_torque_gains_command_interface.h.

Member Function Documentation

◆ getCommandEffort()

double hardware_interface::PositionVelocityTorqueGainsJointHandle::getCommandEffort ( ) const
inline

◆ getCommandKd()

double hardware_interface::PositionVelocityTorqueGainsJointHandle::getCommandKd ( ) const
inline

◆ getCommandKp()

double hardware_interface::PositionVelocityTorqueGainsJointHandle::getCommandKp ( ) const
inline

◆ setCommand()

void hardware_interface::PositionVelocityTorqueGainsJointHandle::setCommand ( double  cmd_pos,
double  cmd_vel,
double  cmd_eff,
double  cmd_kp,
double  cmd_kd 
)
inline

◆ setCommandEffort()

void hardware_interface::PositionVelocityTorqueGainsJointHandle::setCommandEffort ( double  cmd_eff)
inline

◆ setCommandKd()

void hardware_interface::PositionVelocityTorqueGainsJointHandle::setCommandKd ( double  cmd_kd)
inline

◆ setCommandKp()

void hardware_interface::PositionVelocityTorqueGainsJointHandle::setCommandKp ( double  cmd_kp)
inline

Member Data Documentation

◆ cmd_eff_

double* hardware_interface::PositionVelocityTorqueGainsJointHandle::cmd_eff_ = {nullptr}
private

◆ cmd_kd_

double* hardware_interface::PositionVelocityTorqueGainsJointHandle::cmd_kd_ = {nullptr}
private

◆ cmd_kp_

double* hardware_interface::PositionVelocityTorqueGainsJointHandle::cmd_kp_ = {nullptr}
private

The documentation for this class was generated from the following file:


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Nov 3 2023 02:07:57