(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Before you begin planning: Setting up the Prerequisites

Description: Before you begin planning: Setting up the Pre-requisites

Tutorial Level: BEGINNER

Next Tutorial: Configuring a joint space planner

Configuring the collision space

Robot planning description (Required)

The first step in setting up the motion planner is to make sure that a full planning description is available for your robot. The planning description includes information about the joints and links that are part of the planning group. Documentation on creating this description and an example description can be found here. Follow those instructions and put the planning description in a file named example_planning_description.yaml in your example_planning package.

The full description for the PR2 robot can be found in pr2_arm_navigation_config/config/planning_groups.yaml.

Multi-dof joints (Required)

Certain multi-dof joints are not specified in the URDF, e.g. the joint connecting the robot to the world. These should be specified separately. If you have a manipulator that is directly connected to the world without a mobile base in between, you can simply connect it to the world in this manner:

multi_dof_joints:
  - name: world_joint
    type: Fixed
    parent_frame_id: world
    child_frame_id: world

Here, world should have been specified as the parent link of the base link of your robot. Put the above lines in your file named example_planning_description.yaml.

The full multi-dof joint description for the PR2 robot can be found in pr2_arm_navigation_config/config/multi_dof_joints.yaml. It shows how a multi-dof joint is specified as a floating joint connecting the base_footprint link of the PR2 to the odom_combined frame.

Collision operations (Required)

When checking collisions, it is often necessary to take self-collisions into account, i.e. collisions between links on the robot. Quite often, because of the geometry of the robot, some links will never collide with others on the robot. It is advantageous to specify this explicitly in a configuration file since this will reduce the number of collision checks needed. Such a configuration is specified using collision operations which allow the user to enable or disable the collision checks between certain sets of links. If the collision checks are disabled, the system will ignore a collision between the two links.

By default, all collisions are disabled, i.e. any configuration of the robot is considered a valid configuration. Any possibility of collision between two links must thus be completely specified in a configuration file. This set of default collision operations that will always be applied can be specified in a yaml file. More documentation on how to specify these operations can be found on the second half of this page.

As you can see from the example, collision operations can be specified between links, between a link and a group or between two groups. For example, you can enable all collisions between the right arm and the left arm (if it exists) using the following configuration lines:

default_collision_operations:
  - object1: right_arm
    object2: left_arm
    operation: enable

Save this text to a file named example_collision_operations.yaml.

The default collision operations for the PR2 robot can be found in pr2_arm_navigation_config/config/collision_checks_both_arms.yaml.

Loading the configuration onto the ROS parameter space

As a result of your configuration above, you should now have two files:

  1. example_planning_description.yaml - contains planning description and a list of multi degree of freedom joints.
  2. example_collision_operations.yaml - contains a complete list of collision operations for an arm.

You need to upload these two files onto the ROS param server in the correct namespace. Given below is a launch file that will do that for you. Save it in your example_planning package under the name example_robot_description.launch.

Note the two namespaces that we are loading parameters into: robot_description_planning is the namespace into which all the planning parameters are loaded while robot_description_collision is the namespace into which all collision parameters are loaded.

<launch> 
        <rosparam command="load" ns="robot_description_collision" file="$(find example_planning)/example_collision_operations.yaml" />
        <rosparam command="load" ns="robot_description_planning" file="$(find example_planning)/example_planning_description.yaml" />
</launch>

Make sure you load this file onto the parameter server.

roslaunch example_planning example_robot_description.launch

Now, go on to the next tutorial which will teach you how to configure the joint space planner.

Wiki: ompl_ros_interface/Tutorials/Before you begin planning: Setting up the Prerequisites (last edited 2011-05-24 09:15:46 by MartinGuenther)