A handle used to enforce position and velocity limits of a position-controlled joint. More...
#include <joint_limits_interface.h>
Public Member Functions | |
void | enforceLimits (const ros::Duration &period) |
Enforce position and velocity limits for a joint subject to soft limits. | |
std::string | getName () const |
PositionJointSoftLimitsHandle () | |
PositionJointSoftLimitsHandle (const hardware_interface::JointHandle &jh, const JointLimits &limits, const SoftJointLimits &soft_limits) | |
Private Attributes | |
hardware_interface::JointHandle | jh_ |
JointLimits | limits_ |
double | prev_cmd_ |
SoftJointLimits | soft_limits_ |
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.
Definition at line 156 of file joint_limits_interface.h.
Definition at line 159 of file joint_limits_interface.h.
joint_limits_interface::PositionJointSoftLimitsHandle::PositionJointSoftLimitsHandle | ( | const hardware_interface::JointHandle & | jh, |
const JointLimits & | limits, | ||
const SoftJointLimits & | soft_limits | ||
) | [inline] |
Definition at line 163 of file joint_limits_interface.h.
void joint_limits_interface::PositionJointSoftLimitsHandle::enforceLimits | ( | const ros::Duration & | period | ) | [inline] |
Enforce position and velocity limits for a joint subject to soft limits.
If the joint has no position limits (eg. a continuous joint), only velocity limits will be enforced.
period | Control period. |
Definition at line 187 of file joint_limits_interface.h.
std::string joint_limits_interface::PositionJointSoftLimitsHandle::getName | ( | ) | const [inline] |
Definition at line 179 of file joint_limits_interface.h.
hardware_interface::JointHandle joint_limits_interface::PositionJointSoftLimitsHandle::jh_ [private] |
Definition at line 243 of file joint_limits_interface.h.
Definition at line 244 of file joint_limits_interface.h.
double joint_limits_interface::PositionJointSoftLimitsHandle::prev_cmd_ [private] |
Definition at line 247 of file joint_limits_interface.h.
Definition at line 245 of file joint_limits_interface.h.