Public Member Functions | Private Attributes | List of all members
joint_limits_interface::PositionJointSoftLimitsHandle Class Reference

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. More...
 
std::string getName () const
 
 PositionJointSoftLimitsHandle ()
 
 PositionJointSoftLimitsHandle (const hardware_interface::JointHandle &jh, const JointLimits &limits, const SoftJointLimits &soft_limits)
 
void reset ()
 Reset state, in case of mode switch or e-stop. More...
 

Private Attributes

hardware_interface::JointHandle jh_
 
JointLimits limits_
 
double prev_cmd_
 
SoftJointLimits soft_limits_
 

Detailed Description

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

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.

Note
: This handle type is stateful, ie. it stores the previous position command to estimate the command velocity.

Definition at line 161 of file joint_limits_interface.h.

Constructor & Destructor Documentation

joint_limits_interface::PositionJointSoftLimitsHandle::PositionJointSoftLimitsHandle ( )
inline

Definition at line 164 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 168 of file joint_limits_interface.h.

Member Function Documentation

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.

Parameters
periodControl period.

Definition at line 192 of file joint_limits_interface.h.

std::string joint_limits_interface::PositionJointSoftLimitsHandle::getName ( ) const
inline
Returns
Joint name.

Definition at line 184 of file joint_limits_interface.h.

void joint_limits_interface::PositionJointSoftLimitsHandle::reset ( )
inline

Reset state, in case of mode switch or e-stop.

Definition at line 250 of file joint_limits_interface.h.

Member Data Documentation

hardware_interface::JointHandle joint_limits_interface::PositionJointSoftLimitsHandle::jh_
private

Definition at line 255 of file joint_limits_interface.h.

JointLimits joint_limits_interface::PositionJointSoftLimitsHandle::limits_
private

Definition at line 256 of file joint_limits_interface.h.

double joint_limits_interface::PositionJointSoftLimitsHandle::prev_cmd_
private

Definition at line 259 of file joint_limits_interface.h.

SoftJointLimits joint_limits_interface::PositionJointSoftLimitsHandle::soft_limits_
private

Definition at line 257 of file joint_limits_interface.h.


The documentation for this class was generated from the following file:


joint_limits_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Jun 7 2019 22:00:13