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

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

#include <joint_command_interface.h>

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

Public Member Functions

double getCommand () const
 
const double * getCommandPtr () const
 
 JointHandle ()=default
 
 JointHandle (const JointStateHandle &js, double *cmd)
 
void setCommand (double command)
 
- 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_ = {nullptr}
 

Detailed Description

A handle used to read and command a single joint.

Definition at line 42 of file joint_command_interface.h.

Constructor & Destructor Documentation

◆ JointHandle() [1/2]

hardware_interface::JointHandle::JointHandle ( )
default

◆ JointHandle() [2/2]

hardware_interface::JointHandle::JointHandle ( const JointStateHandle js,
double *  cmd 
)
inline
Parameters
jsThis joint's state handle
cmdA pointer to the storage for this joint's output command

Definition at line 51 of file joint_command_interface.h.

Member Function Documentation

◆ getCommand()

double hardware_interface::JointHandle::getCommand ( ) const
inline

Definition at line 61 of file joint_command_interface.h.

◆ getCommandPtr()

const double* hardware_interface::JointHandle::getCommandPtr ( ) const
inline

Definition at line 62 of file joint_command_interface.h.

◆ setCommand()

void hardware_interface::JointHandle::setCommand ( double  command)
inline

Definition at line 60 of file joint_command_interface.h.

Member Data Documentation

◆ cmd_

double* hardware_interface::JointHandle::cmd_ = {nullptr}
private

Definition at line 65 of file joint_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