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

A handle used to read the state of a single joint. Currently, position, velocity and effort fields are required while absolute position and torque sensors are optional. More...

#include <joint_state_interface.h>

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

Public Member Functions

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

const double * absolute_pos_ = {nullptr}
 
const double * eff_ = {nullptr}
 
std::string name_
 
const double * pos_ = {nullptr}
 
const double * torque_sensor_ = {nullptr}
 
const double * vel_ = {nullptr}
 

Detailed Description

A handle used to read the state of a single joint. Currently, position, velocity and effort fields are required while absolute position and torque sensors are optional.

Definition at line 45 of file joint_state_interface.h.

Constructor & Destructor Documentation

◆ JointStateHandle() [1/5]

hardware_interface::JointStateHandle::JointStateHandle ( )
default

◆ JointStateHandle() [2/5]

hardware_interface::JointStateHandle::JointStateHandle ( const std::string &  name,
const double *  pos,
const double *  vel,
const double *  eff 
)
inline
Parameters
nameThe name of the joint
posA pointer to the storage for this joint's position
velA pointer to the storage for this joint's velocity
effA pointer to the storage for this joint's effort (force or torque)

Definition at line 56 of file joint_state_interface.h.

◆ JointStateHandle() [3/5]

hardware_interface::JointStateHandle::JointStateHandle ( const std::string &  name,
const double *  pos,
const double *  vel,
const double *  eff,
const double *  absolute_pos,
const double *  torque_sensor 
)
inline
Parameters
nameThe name of the joint
posA pointer to the storage for this joint's position
velA pointer to the storage for this joint's velocity
effA pointer to the storage for this joint's effort (force or torque)
absolute_posA pointer to the storage for this joint's absolute position encoder
torque_sensorA pointer to the storage for this joint's torque sensor

Definition at line 81 of file joint_state_interface.h.

◆ JointStateHandle() [4/5]

hardware_interface::JointStateHandle::JointStateHandle ( const std::string &  name,
const double *  pos,
const double *  vel,
const double *  eff,
const double *  absolute_pos 
)
inline
Parameters
nameThe name of the joint
posA pointer to the storage for this joint's position
velA pointer to the storage for this joint's velocity
effA pointer to the storage for this joint's effort (force or torque)
absolute_posA pointer to the storage for this joint's absolute position encoder

Definition at line 114 of file joint_state_interface.h.

◆ JointStateHandle() [5/5]

hardware_interface::JointStateHandle::JointStateHandle ( const std::string &  name,
const double *  pos,
const double *  vel,
const double *  eff,
const double *  torque_sensor,
bool   
)
inline
Parameters
nameThe name of the joint
posA pointer to the storage for this joint's position
velA pointer to the storage for this joint's velocity
effA pointer to the storage for this joint's effort (force or torque)
torque_sensorA pointer to the storage for this joint's torque sensor
boolDummy parameter to differentiate from absolute encoder constructor

Definition at line 144 of file joint_state_interface.h.

Member Function Documentation

◆ getAbsolutePosition()

double hardware_interface::JointStateHandle::getAbsolutePosition ( ) const
inline

Definition at line 171 of file joint_state_interface.h.

◆ getAbsolutePositionPtr()

const double* hardware_interface::JointStateHandle::getAbsolutePositionPtr ( ) const
inline

Definition at line 193 of file joint_state_interface.h.

◆ getEffort()

double hardware_interface::JointStateHandle::getEffort ( ) const
inline

Definition at line 169 of file joint_state_interface.h.

◆ getEffortPtr()

const double* hardware_interface::JointStateHandle::getEffortPtr ( ) const
inline

Definition at line 191 of file joint_state_interface.h.

◆ getName()

std::string hardware_interface::JointStateHandle::getName ( ) const
inline

Definition at line 166 of file joint_state_interface.h.

◆ getPosition()

double hardware_interface::JointStateHandle::getPosition ( ) const
inline

Definition at line 167 of file joint_state_interface.h.

◆ getPositionPtr()

const double* hardware_interface::JointStateHandle::getPositionPtr ( ) const
inline

Definition at line 189 of file joint_state_interface.h.

◆ getTorqueSensor()

double hardware_interface::JointStateHandle::getTorqueSensor ( ) const
inline

Definition at line 180 of file joint_state_interface.h.

◆ getTorqueSensorPtr()

const double* hardware_interface::JointStateHandle::getTorqueSensorPtr ( ) const
inline

Definition at line 202 of file joint_state_interface.h.

◆ getVelocity()

double hardware_interface::JointStateHandle::getVelocity ( ) const
inline

Definition at line 168 of file joint_state_interface.h.

◆ getVelocityPtr()

const double* hardware_interface::JointStateHandle::getVelocityPtr ( ) const
inline

Definition at line 190 of file joint_state_interface.h.

◆ hasAbsolutePosition()

bool hardware_interface::JointStateHandle::hasAbsolutePosition ( ) const
inline

Definition at line 211 of file joint_state_interface.h.

◆ hasTorqueSensor()

bool hardware_interface::JointStateHandle::hasTorqueSensor ( ) const
inline

Definition at line 212 of file joint_state_interface.h.

Member Data Documentation

◆ absolute_pos_

const double* hardware_interface::JointStateHandle::absolute_pos_ = {nullptr}
private

Definition at line 219 of file joint_state_interface.h.

◆ eff_

const double* hardware_interface::JointStateHandle::eff_ = {nullptr}
private

Definition at line 218 of file joint_state_interface.h.

◆ name_

std::string hardware_interface::JointStateHandle::name_
private

Definition at line 215 of file joint_state_interface.h.

◆ pos_

const double* hardware_interface::JointStateHandle::pos_ = {nullptr}
private

Definition at line 216 of file joint_state_interface.h.

◆ torque_sensor_

const double* hardware_interface::JointStateHandle::torque_sensor_ = {nullptr}
private

Definition at line 220 of file joint_state_interface.h.

◆ vel_

const double* hardware_interface::JointStateHandle::vel_ = {nullptr}
private

Definition at line 217 of file joint_state_interface.h.


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


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Tue Oct 15 2024 02:08:19