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

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

#include <posvelacc_command_interface.h>

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

Public Member Functions

double getCommandAcceleration () const
 
 PosVelAccJointHandle ()
 
 PosVelAccJointHandle (const JointStateHandle &js, double *cmd_pos, double *cmd_vel, double *cmd_acc)
 
void setCommand (double cmd_pos, double cmd_vel, double cmd_acc)
 
void setCommandAcceleration (double cmd_acc)
 
- Public Member Functions inherited from hardware_interface::PosVelJointHandle
double getCommandPosition () const
 
double getCommandVelocity () const
 
 PosVelJointHandle ()
 
 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 getEffort () const
 
std::string getName () const
 
double getPosition () const
 
double getVelocity () const
 
 JointStateHandle ()
 
 JointStateHandle (const std::string &name, const double *pos, const double *vel, const double *eff)
 

Private Attributes

double * cmd_acc_
 

Detailed Description

A handle used to read and command a single joint.

Definition at line 42 of file posvelacc_command_interface.h.

Constructor & Destructor Documentation

hardware_interface::PosVelAccJointHandle::PosVelAccJointHandle ( )
inline

Definition at line 45 of file posvelacc_command_interface.h.

hardware_interface::PosVelAccJointHandle::PosVelAccJointHandle ( const JointStateHandle js,
double *  cmd_pos,
double *  cmd_vel,
double *  cmd_acc 
)
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
eff_cmdA pointer to the storage for this joint's output command acceleration

Definition at line 53 of file posvelacc_command_interface.h.

Member Function Documentation

double hardware_interface::PosVelAccJointHandle::getCommandAcceleration ( ) const
inline

Definition at line 70 of file posvelacc_command_interface.h.

void hardware_interface::PosVelAccJointHandle::setCommand ( double  cmd_pos,
double  cmd_vel,
double  cmd_acc 
)
inline

Definition at line 62 of file posvelacc_command_interface.h.

void hardware_interface::PosVelAccJointHandle::setCommandAcceleration ( double  cmd_acc)
inline

Definition at line 69 of file posvelacc_command_interface.h.

Member Data Documentation

double* hardware_interface::PosVelAccJointHandle::cmd_acc_
private

Definition at line 73 of file posvelacc_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 Apr 20 2020 03:52:05