Note: This tutorial assumes that you have completed the previous tutorials: Before you begin planning: Setting up the prerequisites.
(!) 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.

Configuring a joint space planner

Description: Configuring a joint space planner

Keywords: ompl planning planner

Tutorial Level: BEGINNER

Next Tutorial: Launching a joint space planner

In this tutorial, you will learn how to configure a set of joint space planners for OMPL. A joint space planner will be the most-often used planner that OMPL provides. It allows you to plan for a group of joints, e.g. the joints belonging to the arm of a manipulator. The group can be disconnected, e.g. you could write a planner for the arm and head of a robot without planning for the body or torso. The types of joints that are supported are the same set supported by the URDF specification, i.e. rotary, planar and floating joints. OMPL provides access to a wide-variety of planners and you can setup your planning node to use any of them through the YAML configuration (described below).

The configuration of the planning node consists of the specification and configuration of three components:

  1. The set of planners - This is a set of planners that you will configure.
  2. The set of groups - This is a set of planning groups that you want the planning node to function on.
  3. Putting everything together - Put the planners and groups together to get a planning group, i.e. a set of planners that work on a particular group.

Configuration file

All configuration parameters go into a YAML configuration file. An example file can be found for the PR2 in the pr2_arm_navigation_planning package in the config directory. The name of the file is ompl_planning.yaml.

To follow along with this tutorial, first create a package called example_planning with dependencies on ompl_ros_interface. Then open up a new file in your favorite text editor and name it example_planning.yaml and save it in this new package directory.

Specifying a set of planners to use

Planners are specified by specifying a planning configuration. A planning configuration specifies a particular planner to use and the associated configuration parameters to use for it. Unless you are an advanced user, it would be best to use the default parameters specified in an example file. If you are an advanced user, check out the (upcoming) advanced tutorials for the ompl_ros_interface package to see how to modify the parameters.

Here's a simple example of how to configure two planning configurations, one for a planner using SBL and the other for a planner using LBKPIECE. Add these as the first lines in your example_planning.yaml file.

planner_configs:
  SBLkConfig1:
    type: kinematic::SBL
  LBKPIECEkConfig1:
    type: kinematic::LBKPIECE

Specifying the groups

The second step is to specify the groups that you want to plan for. Suppose you want to plan for the right arm of a robot (e.g. the PR2). First, list the right arm under the groups specification in the YAML file.

# the list of groups for which motion planning can be performed
groups: 
  - right_arm 

If you want to specify multiple groups, just add them to the YAML file.

# the list of groups for which motion planning can be performed
groups: 
  - right_arm 
  - left_arm

Putting it together

We now have a list of groups to plan for and a set of configured planners to work with. We can now put these two together to get a planning group, i.e. a set of (configured) planners for a particular group.

A planning group is specified by the name of the group that we are planning for. In addition, there are three configurations parameters for each planning group:

  1. The projection_evaluator parameter which (for joint space planners) should be set to joint_state.

  2. The set of configured planners that you want to be used with this group. Here, we will add the two planner configurations we specified earlier in the file.
  3. The type of planner which in this case is JointPlanner since we are configuring a joint space planner.

right_arm:
  planner_type: JointPlanner
  planner_configs:
    - SBLkConfig1 
    - LBKPIECEkConfig1
  projection_evaluator: joint_state

In addition, you will have to choose one of the planners as a default planner. Assuming you choose SBLkConfig1 as the default planner, add the following line at the end of your configuration file:

default_planner_config: SBLkConfig1

This completes the configuration of a joint space planner for the right arm of your robot. Here's the complete configuration file you generated:

## the list of groups for which motion planning can be performed
groups: 
  - right_arm 
## the planner configurations; each config must have a type, which specifies
## the planner to be used; other parameters can be specified as well, depending 
## on the planner
right_arm:
  planner_type: JointPlanner
  planner_configs:
    - SBLkConfig1 
    - LBKPIECEkConfig1
  projection_evaluator: joint_state
default_planner_config: SBLkConfig1

In the next tutorial, you will learn how to launch this planner.

Wiki: ompl_ros_interface/Tutorials/Configuring a joint space planner (last edited 2013-02-22 14:44:16 by ThomasRuehr)