A handle used to enforce position and velocity limits of a position-controlled joint. More...
#include <qb_device_joint_limits_interface.h>
Public Member Functions | |
Real-Time Safe Functions | |
void | reset () |
Reset all managed handles. More... | |
Public Member Functions inherited from joint_limits_interface::JointLimitsInterface< HandleType > | |
void | enforceLimits (const ros::Duration &period) |
void | enforceLimits (const ros::Duration &period) |
HandleType | getHandle (const std::string &name) |
A handle used to enforce position and velocity limits of a position-controlled joint.
This class implements a very simple position and velocity limits enforcing policy, and tries to impose the least amount of requisites on the underlying hardware platform. This lowers considerably the entry barrier to use it, but also implies some limitations.
Requisites
k_velocity
parameter is not used.Open loop nature
Joint position and velocity limits are enforced in an open-loop fashion, that is, the command is checked for validity without relying on the actual position/velocity values.
The downside of the open loop behavior is that velocity limits will not be enforced when recovering from large position tracking errors. Only the command is guaranteed to comply with the limits specification.
joint_handle | The joint handle of interest. |
limits | The pointer to the joint limits structure of the joint. Enforce position and velocity limits for a joint that is subject to soft limits. |
period | The control period. |
Definition at line 201 of file qb_device_joint_limits_interface.h.
|
inline |
Reset all managed handles.
Definition at line 207 of file qb_device_joint_limits_interface.h.