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

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

#include <posvel_command_interface.h>

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

Public Member Functions

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, const double *torque_sensor)
 
 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 *torque_sensor, bool)
 

Private Attributes

double * cmd_pos_ = {nullptr}
 
double * cmd_vel_ = {nullptr}
 

Detailed Description

A handle used to read and command a single joint.

Definition at line 42 of file posvel_command_interface.h.

Constructor & Destructor Documentation

◆ 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
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

Definition at line 52 of file posvel_command_interface.h.

Member Function Documentation

◆ getCommandPosition()

double hardware_interface::PosVelJointHandle::getCommandPosition ( ) const
inline

Definition at line 74 of file posvel_command_interface.h.

◆ getCommandVelocity()

double hardware_interface::PosVelJointHandle::getCommandVelocity ( ) const
inline

Definition at line 75 of file posvel_command_interface.h.

◆ setCommand()

void hardware_interface::PosVelJointHandle::setCommand ( double  cmd_pos,
double  cmd_vel 
)
inline

Definition at line 65 of file posvel_command_interface.h.

◆ setCommandPosition()

void hardware_interface::PosVelJointHandle::setCommandPosition ( double  cmd_pos)
inline

Definition at line 71 of file posvel_command_interface.h.

◆ setCommandVelocity()

void hardware_interface::PosVelJointHandle::setCommandVelocity ( double  cmd_vel)
inline

Definition at line 72 of file posvel_command_interface.h.

Member Data Documentation

◆ cmd_pos_

double* hardware_interface::PosVelJointHandle::cmd_pos_ = {nullptr}
private

Definition at line 78 of file posvel_command_interface.h.

◆ cmd_vel_

double* hardware_interface::PosVelJointHandle::cmd_vel_ = {nullptr}
private

Definition at line 79 of file posvel_command_interface.h.


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


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Mon Feb 28 2022 23:30:10