Skip to content

CartesIO

Luca Muratore edited this page Oct 1, 2018 · 4 revisions

Cartesian Interface

Package for generic cartesian control of floating base robots. It includes a ROS-based front end, as well as a programmatic API that can be used inside a real-time loop.

Table of contents

ROS Cartesian Server

Programmatic API

ROS Cartesian Server

The ROS Cartesian Server is the core of the CartesianInterface ROS API. It is a ROS node that serves two purposes:

  1. Loading and executing an instance (i.e. one specific implementation) of the CartesianInterface class
  2. Exposing a full ROS interface through topics, services, and actions
  3. Through an external node, it also exposes an Rviz interface based on interactive markers

Running the ROS Cartesian Server

The ROS Cartesian Server is run by simply writing on the command line rosrun cartesian_interface ros_server_node.

However, the Cartesian Server needs some information in order to run properly. At the current time, there are two ways of configuring the node: via the XBotCore YAML file, or via ROS parameters.

Configuration via XBotCore YAML file

If you have already integrated your robot with the XbotCore framework, then it means that you did set the path to your Xbot config file by calling set_xbot_config /path/to/config_file (you can get the path by calling get_xbot_config). It is now easy to integrate the Cartesian Server by following these steps:

  1. open the XBot config file with any text editor
  2. add a YAML node with name CartesianInterface
  3. add a subnode with key solver; provide as a value the name of the CartesianInterface implementation that you want to load. The default choice is OpenSot.
  4. add a subnode problem_description that will host:
    • a subnode stack whose value is a list of vectors of tasks, one for each priority level
    • a subnode constraints whose value is a list of constraints
    • the description of each task/constraint that is listed above

Further information on how to write a problem description is provided in the following section. The resulting structure should be as in the following example of a three-stack IK proble for a humanoid robot:

CartesianInterface:
  solver: "OpenSot"
  problem_description:
    stack:
      - ["LeftFoot", "RightFoot", "ComXY"]
      - ["LeftHand", "RightHand"]
      - ["Postural"]
    constraints: ["JointLimits", "VelocityLimits"]

    LeftFoot:
      type: "Cartesian"
      distal_link: "l_sole"
    
    RightFoot:
      type: "Cartesian"
      distal_link: "r_sole"

    ComXY:
      type: "Com"
      indices: [0, 1]
      
    Postural:
      type: "Postural"
      lambda: 0.01
    
    LeftHand:
      type: "Cartesian"
      distal_link: "left_hand"
      lambda: 0.1
    
    RightHand:
      type: "Cartesian"
      distal_link: "right_hand"
      lambda: 0.1

NOTE: to specify that the XBot config should be used, the ros_server_node needs the private parameter ~/use_xbot_config to be set true:

rosrun cartesian_interface ros_server_node _use_xbot_config:=true

Configuration via ROS parameters

  1. upload the robot URDF to /robot_description parameter

  2. upload the robot SRDF to /robot_description_semantic parameter

  3. upload the cartesian control problem description to the /problem_description parameter

  4. if you just want to visualize the IK solution (no commands sent to the robot):

    rosparam set /xbotcore/cartesian/visual_mode true

  5. roslaunch cartesian_interface cartesio.launch runs both cartesian server and interactive marker spawner

Writing an IK problem for your robot

A useful feature of the ROS Cartesian Server is that it enables the user to quickly specify rather complex IK problems from a configuration file, without the need to edit any source code. This is done by customizing the problem_description, as it was briefly explained in the previous section. More in detail, CartesianInterface supports hierarchical optimization problems: therefore, hard priorities can be assigned to tasks or combination of task, in such a way that low priority task will never affect higher priority tasks. Finally, all priority levels can be subject to equality and inequality constraint. The kind of IK problem that is described above can be simply modeled as follows

  1. First, we need to specify, for each priority level, a list of tasks. These tasks are aggregated together in a weighted manner, in order to model soft priorities. In terms of YAML nodes, this is achieved with the stack node, whose elements are vectors of strings that represent task labels.
problem_description:
    stack:
      - ["TaskHigh"]
      - ["TaskMidA", "TaskMidB", "TaskMidC"]
      - ["TaskLow"]
  1. Then, we need to specify global constraints that apply to all hierarchy levels. This is done with the constraints YAML node, which is a vector of string representing constraint labels.
problem_description:
    constraints: ["Constraint1", "Constraint2"]
  1. Finally, for each task/constraint label that we introduced during the previous steps, we need to provide nodes specifying the kind of task/constraint, and its parameters. For example, we specify that TaskMidA is indeed a cartesian task from the world to the left hand.
TaskMidA:
  type: "Cartesian"
  distal_link: "left_hand"
  base_link: "world" # optional, defaults to "world"
  lambda: 0.1 # optional, defaults to 1.0

A list of supported tasks/constraints, together with a list of supported parameters, can be found here

ROS API explained

  • Namespace: /xbotcore/cartesian
  • Topics:
    • task_name/state (type geometry_msgs/PoseStamped): current end effector pose according to the current IK solution
    • task_name/reference (type geometry_msgs/PoseStamped): user-defined task-space reference to be continuously followed w.r.t. the task base link (see get_task_info service)
    • posture/reference and posture/state (type sensor_msgs/JointState) for the postural task
    • task_name/velocity_reference (type geometry_msgs/TwistStamped): user-defined task-space velocity reference to be continuously followed w.r.t. the task base link (see get_task_properties service). In order to obtain pure velocity control, the control mode must be changed to velocity (see set_task_properties service)
  • Actions:
    • task_name/reach (type cartesian_interface/ReachPose): reach a given pose in a given amount of time (possibly with specified waypoints)
  • Services:
    • load_controller: load the specified cartesian controller at run-time (libCartesianCONTROLLERNAME.so must be found inside some path defined in LD_LIBRARY_PATH environment variable)
    • task_name/get_task_properties: get information about the task (base link name, control mode, task state)
    • task_name/set_task_properties: set task properties (base link name, control mode)
    • task_name/spawn_marker
    • task_name/clear_marker
  • Interactive markers:
    • right click to display the menu
    • continuous mode / point-to-point trajectory mode
    • reset marker position
    • local/global control
    • base link change
  • Parameters:
    • task_name/max_velocity_linear, task_name/max_velocity_angular, task_name/max_acceleration_linear, task_name/max_acceleration_angular can be used to change velocity and acceleration limits for all tasks (implemented on top of the Reflexxes Type II library). In order to apply the changes during runtime, a call to update_velocity_limits is necessary.

Programmatic API

All the above functionalities are available through an (hopefully) intuitive programmatic API. Names and arguments are similar.

Supported tasks

Task parameters

All tasks inherit the following parameters:

  • type: the type of task
  • weight: a positive-definite matrix representing the soft priority of the task inside an aggregated task
  • indices a vector of indices ranging from 0 to size-1 specifying the specific subtask that has to be considered (default is indices = [0 1 ... size-1]
  • lambda: a gain that specifies the proportion in which a task error should affect the corresponding task velocity (default is lambda = 1)

Cartesian

  • type = "Cartesian"
  • distal_link
  • base_link (default is world)
  • orientation_gain (default is one)

Integration state:

  • send references via ROS topics / actions: YES
  • interactive control (RVIZ): YES

Center of mass

  • type = "Com"

Integration state:

  • send references via ROS topics / actions: YES
  • interactive control (RVIZ): YES

Postural

  • type = "Postural"
  • weight can be given as a joint name -> joint weight map:
Postural:
      type: "Postural"
      weight:
        WaistLat: 5.0
        LKneePitch: 0.1
        RKneePitch: 0.1

Integration state:

  • send references via ROS topics / actions: YES
  • interactive control (RVIZ): YeS

Supported constraints

Joint limits

  • type = "JointLimits"

Joint velocity limits

  • type = "VelocityLimits"