joint_limits_interface
Interface for enforcing joint limits.
 
joint_limits_interface contains data structures for representing joint limits, methods for populating them from common formats such as URDF and rosparam, and methods for enforcing limits on different kinds of joint commands.
The joint_limits_interface is not used by controllers themselves (it does not implement a HardwareInterface) but instead operates after the controllers have updated, in the write() method (or equivalent) of the robot abstraction. Enforcing limits will overwrite the commands set by the controllers, it does not operate on a separate raw data buffer.
Code API
There are two main elements involved in setting up a joint_limits_interface:
Joint limits representation
- JointLimits Position, velocity, acceleration, jerk and effort.
- SoftJointLimits Soft position limits, k_p, k_v (as described here ).
- Convenience methods for loading joint limits information (only position, velocity, effort), as well as soft joint limits information from the URDF.
- Convenience methods for loading joint limits from ROS parameter server (all values). Parameter specification is the same used in MoveIt, with the addition that we also parse jerk and effort limits.
Joint limits interface
For effort-controlled joints, position-controlled joints, and velocity-controlled joints, two types of interfaces have been created. The first is a saturation interface, used for joints that have normal limits but not soft limits. The second is an interface that implements soft limits, similar to the one used on the PR2.
- Effort-controlled joints
- Position-controlled joints
- Velocity-controlled joints
Examples
Joint limits representation
The first example shows the different ways of populating joint limits data structures.
 
 
int main(
int argc, 
char** argv)
 
{
  
  std::shared_ptr<urdf::ModelInterface> 
urdf;
  
 
  
 
  
 
  
  
  
  urdf::JointConstSharedPtr urdf_joint = 
urdf->getJoint(
"foo_joint");
 
  
  
  
  const bool rosparam_limits_ok = 
getJointLimits(
"foo_joint", nh, limits);
 
}
 A joint limits specification in YAML format that can be loaded to the ROS parameter server can be found here.
Joint limits interface
The second example integrates joint limits enforcing into an existing robot hardware implementation.
 
 
class MyRobot
{
public:
  MyRobot() {}
 
  {
    
 
    
    JointHandle joint_handle = pos_cmd_interface_.getHandle(
"foo_joint");
 
 
    JointLimits limits;
    SoftJointLimits soft_limits;
    
 
    
    PositionJointSoftLimitsHandle handle(joint_handle, 
                                         limits,       
                                         soft_limits)  
 
    jnt_limits_interface_.registerHandle(handle);
  }
 
  {
    
 
    
  }
 
  {
    
    
    jnt_limits_interface_.enforceLimits(period);
 
    
 
    
  }
 
private:
  PositionJointSoftLimitsInterface jnt_limits_interface_;
};