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>
|
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) |
|
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.
◆ 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
-
name | The name of the joint |
pos | A pointer to the storage for this joint's position |
vel | A pointer to the storage for this joint's velocity |
eff | A 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
-
name | The name of the joint |
pos | A pointer to the storage for this joint's position |
vel | A pointer to the storage for this joint's velocity |
eff | A pointer to the storage for this joint's effort (force or torque) |
absolute_pos | A pointer to the storage for this joint's absolute position encoder |
torque_sensor | A 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
-
name | The name of the joint |
pos | A pointer to the storage for this joint's position |
vel | A pointer to the storage for this joint's velocity |
eff | A pointer to the storage for this joint's effort (force or torque) |
absolute_pos | A 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
-
name | The name of the joint |
pos | A pointer to the storage for this joint's position |
vel | A pointer to the storage for this joint's velocity |
eff | A pointer to the storage for this joint's effort (force or torque) |
torque_sensor | A pointer to the storage for this joint's torque sensor |
bool | Dummy parameter to differentiate from absolute encoder constructor |
Definition at line 144 of file joint_state_interface.h.
◆ getAbsolutePosition()
double hardware_interface::JointStateHandle::getAbsolutePosition |
( |
| ) |
const |
|
inline |
◆ getAbsolutePositionPtr()
const double* hardware_interface::JointStateHandle::getAbsolutePositionPtr |
( |
| ) |
const |
|
inline |
◆ getEffort()
double hardware_interface::JointStateHandle::getEffort |
( |
| ) |
const |
|
inline |
◆ getEffortPtr()
const double* hardware_interface::JointStateHandle::getEffortPtr |
( |
| ) |
const |
|
inline |
◆ getName()
std::string hardware_interface::JointStateHandle::getName |
( |
| ) |
const |
|
inline |
◆ getPosition()
double hardware_interface::JointStateHandle::getPosition |
( |
| ) |
const |
|
inline |
◆ getPositionPtr()
const double* hardware_interface::JointStateHandle::getPositionPtr |
( |
| ) |
const |
|
inline |
◆ getTorqueSensor()
double hardware_interface::JointStateHandle::getTorqueSensor |
( |
| ) |
const |
|
inline |
◆ getTorqueSensorPtr()
const double* hardware_interface::JointStateHandle::getTorqueSensorPtr |
( |
| ) |
const |
|
inline |
◆ getVelocity()
double hardware_interface::JointStateHandle::getVelocity |
( |
| ) |
const |
|
inline |
◆ getVelocityPtr()
const double* hardware_interface::JointStateHandle::getVelocityPtr |
( |
| ) |
const |
|
inline |
◆ hasAbsolutePosition()
bool hardware_interface::JointStateHandle::hasAbsolutePosition |
( |
| ) |
const |
|
inline |
◆ hasTorqueSensor()
bool hardware_interface::JointStateHandle::hasTorqueSensor |
( |
| ) |
const |
|
inline |
◆ absolute_pos_
const double* hardware_interface::JointStateHandle::absolute_pos_ = {nullptr} |
|
private |
◆ eff_
const double* hardware_interface::JointStateHandle::eff_ = {nullptr} |
|
private |
◆ name_
std::string hardware_interface::JointStateHandle::name_ |
|
private |
◆ pos_
const double* hardware_interface::JointStateHandle::pos_ = {nullptr} |
|
private |
◆ torque_sensor_
const double* hardware_interface::JointStateHandle::torque_sensor_ = {nullptr} |
|
private |
◆ vel_
const double* hardware_interface::JointStateHandle::vel_ = {nullptr} |
|
private |
The documentation for this class was generated from the following file: