joint_limits_interface Documentation

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.

codeapi

There are two main elements involved in setting up a joint_limits_interface:

Joint limits representation

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.

Examples

Joint limits representation

The first example shows the different ways of populating joint limits data structures.

#include <ros/ros.h>

#include <joint_limits_interface/joint_limits.h>
#include <joint_limits_interface/joint_limits_urdf.h>
#include <joint_limits_interface/joint_limits_rosparam.h>

int main(int argc, char** argv)
{
  // Init node handle and URDF model
  ros::NodeHandle nh;
  boost::shared_ptr<urdf::ModelInterface> urdf;
  // ...initialize contents of urdf

  // Data structures
  joint_limits_interface::JointLimits limits;
  joint_limits_interface::SoftJointLimits soft_limits;

  // Manual value setting
  limits.has_velocity_limits = true;
  limits.max_velocity = 2.0;

  // Populate (soft) joint limits from URDF
  // Limits specified in URDF overwrite existing values in 'limits' and 'soft_limits'
  // Limits not specified in URDF preserve their existing values
  boost::shared_ptr<const urdf::Joint> urdf_joint = urdf->getJoint("foo_joint");
  const bool urdf_limits_ok = getJointLimits(urdf_joint, limits);
  const bool urdf_soft_limits_ok = getSoftJointLimits(urdf_joint, soft_limits);

  // Populate (soft) joint limits from the ros parameter server
  // Limits specified in the parameter server overwrite existing values in 'limits' and 'soft_limits'
  // Limits not specified in the parameter server preserve their existing values
  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.

#include <joint_limits_interface/joint_limits_interface.h>

using namespace hardware_interface;
using joint_limits_interface::JointLimits;
using joint_limits_interface::SoftJointLimits;
using joint_limits_interface::PositionJointSoftLimitsHandle;
using joint_limits_interface::PositionJointSoftLimitsInterface;

class MyRobot
{
public:
  MyRobot() {}

  bool init()
  {
    // Populate pos_cmd_interface_ with joint handles...

    // Get joint handle of interest
    JointHandle joint_handle = pos_cmd_interface_.getHandle("foo_joint");

    JointLimits limits;
    SoftJointLimits soft_limits;
    // Populate with any of the methods presented in the previous example...

    // Register handle in joint limits interface
    PositionJointSoftLimitsHandle handle(joint_handle, // We read the state and read/write the command
                                         limits,       // Limits spec
                                         soft_limits)  // Soft limits spec

    jnt_limits_interface_.registerHandle(handle);
  }

  void read(ros::Time time, ros::Duration period)
  {
    // Read actuator state from hardware...

    // Propagate current actuator state to joints...
  }

  void write(ros::Time time, ros::Duration period)
  {
    // Enforce joint limits for all registered handles
    // Note: one can also enforce limits on a per-handle basis: handle.enforceLimits(period)
    jnt_limits_interface_.enforceLimits(period);

    // Propagate joint commands to actuators...

    // Send actuator command to hardware...
  }

private:
  PositionJointInterface pos_cmd_interface_;
  PositionJointSoftLimitsInterface jnt_limits_interface_;
};


joint_limits_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Thu Dec 1 2016 03:46:06