Go to the documentation of this file.
56 JointStateHandle(
const std::string& name,
const double* pos,
const double* vel,
const double* eff)
81 JointStateHandle(
const std::string& name,
const double* pos,
const double* vel,
const double* eff,
82 const double* absolute_pos,
const double* torque_sensor)
114 JointStateHandle(
const std::string& name,
const double* pos,
const double* vel,
const double* eff,
115 const double* absolute_pos)
144 JointStateHandle(
const std::string& name,
const double* pos,
const double* vel,
const double* eff,
145 const double* torque_sensor,
bool)
175 throw std::runtime_error(
"Joint state handle does not contain absolute encoder position information");
184 throw std::runtime_error(
"Joint state handle does not contain torque sensor information");
197 throw std::runtime_error(
"Joint state handle does not contain absolute position sensor information");
206 throw std::runtime_error(
"Joint state handle does not contain torque sensor information");
216 const double*
pos_ = {
nullptr};
217 const double*
vel_ = {
nullptr};
218 const double*
eff_ = {
nullptr};
const double * getAbsolutePositionPtr() const
Hardware interface to support reading the state of an array of joints.
JointStateHandle(const std::string &name, const double *pos, const double *vel, const double *eff)
JointStateHandle()=default
double getAbsolutePosition() const
bool hasTorqueSensor() const
const double * getEffortPtr() const
const double * absolute_pos_
const double * getTorqueSensorPtr() const
JointStateHandle(const std::string &name, const double *pos, const double *vel, const double *eff, const double *torque_sensor, bool)
const double * getVelocityPtr() const
A handle used to read the state of a single joint. Currently, position, velocity and effort fields ar...
std::string getName() const
JointStateHandle(const std::string &name, const double *pos, const double *vel, const double *eff, const double *absolute_pos)
bool hasAbsolutePosition() const
An exception related to a HardwareInterface.
double getVelocity() const
JointStateHandle(const std::string &name, const double *pos, const double *vel, const double *eff, const double *absolute_pos, const double *torque_sensor)
double getPosition() const
const double * torque_sensor_
Base class for handling hardware resources.
const double * getPositionPtr() const
double getTorqueSensor() const
hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Tue Oct 15 2024 02:08:19