#include <joint_state_interface.h>

Public Member Functions | |
| 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 | |
| const double * | eff_ |
| std::string | name_ |
| const double * | pos_ |
| const double * | vel_ |
A handle used to read the state of a single joint.
Definition at line 41 of file joint_state_interface.h.
Definition at line 44 of file joint_state_interface.h.
| hardware_interface::JointStateHandle::JointStateHandle | ( | const std::string & | name, |
| const double * | pos, | ||
| const double * | vel, | ||
| const double * | eff | ||
| ) | [inline] |
| 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 52 of file joint_state_interface.h.
| double hardware_interface::JointStateHandle::getEffort | ( | ) | const [inline] |
Definition at line 72 of file joint_state_interface.h.
| std::string hardware_interface::JointStateHandle::getName | ( | ) | const [inline] |
Definition at line 69 of file joint_state_interface.h.
| double hardware_interface::JointStateHandle::getPosition | ( | ) | const [inline] |
Definition at line 70 of file joint_state_interface.h.
| double hardware_interface::JointStateHandle::getVelocity | ( | ) | const [inline] |
Definition at line 71 of file joint_state_interface.h.
const double* hardware_interface::JointStateHandle::eff_ [private] |
Definition at line 78 of file joint_state_interface.h.
std::string hardware_interface::JointStateHandle::name_ [private] |
Definition at line 75 of file joint_state_interface.h.
const double* hardware_interface::JointStateHandle::pos_ [private] |
Definition at line 76 of file joint_state_interface.h.
const double* hardware_interface::JointStateHandle::vel_ [private] |
Definition at line 77 of file joint_state_interface.h.