A handle used to enforce position and velocity limits of a position-controlled joint that does not have soft limits.
More...
#include <qb_device_joint_limits_interface.h>
A handle used to enforce position and velocity limits of a position-controlled joint that does not have soft limits.
- Note
- : The only difference from joint_limits_interface::PositionJointSaturationHandle is that this exploit a dynamical management of the joint limits, i.e. the limits can be modified at runtime by others.
Definition at line 37 of file qb_device_joint_limits_interface.h.
Construct the saturation handle with dynamic joint limits.
- Parameters
-
joint_handle | The joint handle of interest. |
limits | The pointer to the joint limits structure of the joint. |
Definition at line 44 of file qb_device_joint_limits_interface.h.
void qb_device_joint_limits_interface::PositionJointSaturationHandle::enforceLimits |
( |
const ros::Duration & |
period | ) |
|
|
inline |
Enforce position and velocity limits for a joint that is not subject to soft limits.
- Note
- : Be aware of dynamic joint limits.
- Parameters
-
period | The control period. |
Definition at line 59 of file qb_device_joint_limits_interface.h.
std::string qb_device_joint_limits_interface::PositionJointSaturationHandle::getName |
( |
| ) |
const |
|
inline |
void qb_device_joint_limits_interface::PositionJointSaturationHandle::reset |
( |
| ) |
|
|
inline |
double qb_device_joint_limits_interface::PositionJointSaturationHandle::command_old_ |
|
private |
The documentation for this class was generated from the following file: