Note: This tutorial refers to software in the Electric distribution.. This tutorial assumes that you have completed the previous tutorials: Planning Description Configuration Wizard.
(!) 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.

Understanding and adjusting the auto-generated arm navigation application

Description: This tutorial will walk you through the launch files generated by the planning description visualization wizard and describe aspects you may wish to change for your robot.

Keywords: arm_navigation planning motion_planning trajectory_filtering electric

Tutorial Level: INTERMEDIATE

Next Tutorial: Planning Components Visualizer

Introduction

This tutorial will walk you through the configuration and launch files created by the planning components visualization wizard and indicate which values you may be interested in changing for your particular robot. Please see individual node documentation for full parameter lists

This tutorial assumes that you have run the planning components configuration wizard and have a directory called <your_robot_name>_arm_navigation. Throughout this tutorial we'll be referring to auto-generated launch files for the PR2.

YAML Parameter files

There are a number of YAML-formatted configuration files that should appear in the directory <your_robot_name>_arm_navigation/config.

<your_robot_name>_planning_description.yaml

This is the lowest-level configuration file used by any node that creates a planning_environment/robot_models or planning_environment/collision_models class.

multi_dof_joints

The first entry in the file is the multi_dof_joints field. For the PR2 the auto-generated entry looks like this:

multi_dof_joints:
  - name: world_joint
    type: Floating
    parent_frame_id: base_footprint
    child_frame_id: base_footprint

This joint represents the connection between the root joint of our robot - in this case base_footprint, and a fixed frame associated with the world. By default this world fixed frame is just set to the robot's local frame, essentially meaning that all locations are defined relative to the current position of the robot.

Potential adjustments

For many applications there may be a different fixed frame associated with the world - an odometric or map frame, for instance. In this case you can substitute a the new fixed frame for the parent_frame_id field - for instance /map or /odom_combined. You should only do this if you have a publisher for this frame.

groups

This field contains the groups you configured during the planning components visualizer process.

Potential adjustments

If you need to alter this we recommend re-running the configuration wizard as you will potentially need to touch many different files by hand.

default_collision_operations

This long list contains all the link pairs that are being disabled for the self-collision check - collision checking between link pairs is enabled by default. There is a comment for each entry with the designation of why the link pair was disabled.

Potential adjustments

We do not recommend editing this list by hand. If you need to adjust the list we recommend re-running the wizard in advanced mode and using the tools there.

Additional parameters

There are several additional parameters that can be set in this file. For more information see the notes on the planning_environment package.

joint_limits.yaml

This file contains additional information about joints that appear in your planning groups that is not contained in the URDF, as well as allowing you to set lower limits for velocity and acceleration than those contained in your URDF. As our planners are exclusively kinematic planners, this information is used by our trajectory filtering system to assign reasonable velocities and timing for the trajectory before it is passed to your controllers.

Potential adjustments

We do not recommend that you alter the fields has_position_limits, has_velocity_limits, has_acceleration_limits, or angle_wraparound. You may wish to alter the max_velocity and max_acceleration values for each of your joints. The max_velocity parameter has been set to the value in your URDF and you should not raise it. You may wish to lower this value, however - just because your robot can move that quickly doesn't mean it should. Lower limits may result in trajectories that are longer in duration but may be easier to achieve for your controllers, more stable, and less dangerous. The max_acceleration has been set arbitrarily to 1 - if you have better information about what this value should be you can include it.

ompl_planning.yaml

The next auto-generated YAML file configures the OMPL planning node for your robot. In addition to some basic parameterization for OMPL it contains two groups per planning group - a <group_name> group and a <group_name>_cartesian group. The <group_name> group is configured to support configuration space planning for your groups - sampling in the joint space in order to reach joint goals. The <group_name>_cartesian group is configured to support task space planning for your robot. This is particularly useful as it allows you to specify path constraints on allowable paths, for instance to instruct the robot to keep its end effector upright while moving a glass. The task space planner likely will not successfully plan for your robot in a reasonable amount of time using the auto-configured nodes, as it requires robust and very fast inverse kinematics, generally from an analytic solver.

Possible adjustments

If you have implemented a custom analytic inverse kinematics solver plugin for your robot you can substitute that solver in this file. In each <group_name>_cartesian group find the line that specifies kinematics_solver:. Replace arm_kinematics_constraint_aware/KDLArmKinematicsPlugin with your plugin name and OMPL will use it when making IK calls.

You may also improve performance by specifying a single joint of a 7-DOF arm for the redundancy - note that your inverse kinematics solver must be configured to set the same redundancy joint. This will allow OMPL to sample more consistently and to provide better joint seed states during the search. To do this find the state_spaces entry for each <group_arm>_cartesian group and add an entry that specifies the joint name for the redundancy. This joint must be a member of the planning group.

Making both changes for the PR2 leads to this entry in ompl_planning.yaml:

right_arm_cartesian:
  parent_frame: torso_lift_link
  physical_group: right_arm
  planner_type: RPYIKTaskSpacePlanner
  state_spaces:
    - x
    - y
    - z
    - roll
    - pitch
    - yaw
    - r_upper_arm_roll_joint
  x:
    type: Linear
    min: -2.0
    max: 2.0
  y:
    type: Linear
    min: -2.0
    max: 2.0
  z:
    type: Linear
    min: -2.0
    max: 2.0
  roll:
    type: Revolute
  pitch:
    type: Revolute
  yaw:
    type: Revolute
  planner_configs:
    - SBLkConfig1 
    - LBKPIECEkConfig1
  kinematics_solver: pr2_arm_kinematics/PR2ArmKinematicsPlugin
  tip_name: r_wrist_roll_link
  root_name: torso_lift_link
  projection_evaluator: joint_state
  longest_valid_segment_fraction: 0.001

planning_components_visualizer.vcg

This file contains an auto-generated Rviz configuration file for the planning components visualizer.

Possible adjustments

If you've set a new fixed frame you can load that automatically for the planning components visualizer by changing the entry that starts Fixed\ Frame= to reflect your new fixed frame.

Launch files

There are also a number of useful auto-generated launch files produced by the wizard.

<your_robot_name>_planning_environment.launch

This launch file pushes your URDF file and the <your_robot_name>_planning_description.yaml file to the parameter server. It should not need to be altered.

constraint_aware_kinematics.launch

This file launches generic kinematics for each of your configured planning groups.

Potential adjustments

If you have a custom IK solver you can substitute your plugin for the generic solver. We recommend using the same parameter structure for your plugin.

trajectory_filter_server.launch

This file launches the trajectory filter. You should not need to alter it.

planning_components_visualizer.launch

This file brings up the planning components visualizer and an Rviz interactive program that lets you explore the capabilities of our system for your robot. You should not need to alter it.

move_<group_name>.launch files

For each planning group we create a move_<group_name>.launch file. This launches a move_arm_simple_action node, which will plan, filter, and actually deploy trajectories to your controllers.

REQUIRED ALTERATION

You must substitute the name for the action topic for your controller's implementation of the control_msgs/FollowJointTrajectory action in the parameter controller_action_name.

move_groups.launch

This launch file just launches all the individual move_<group_name> launch files. You should not need to alter it

<your_robot_name>_arm_navigation.launch

This file launches everything you should need to run arm navigation on your robot given that your robot has been launched (controller running, /joint_states topic is being published, etc.). In addition to launching the components this launch file also launches the environment_server as a monitor - it will listen to the joint_states topic as well as any published collision objects to get the current state of the world.

Possible adjustments

The environment_server is launched with use_collision_map parameter set to false. This means that it will not subscribe to or wait for a message on the collision_map topic before beginning operation. If you want perception in your application you should set this value to true and add your perception pipeline to this launch file - in this configuration the environment_server will not fully start up until it receives a collision_map message. We will cover the creation of the perception pipeline in a different tutorial (coming soon).

Wiki: arm_navigation/Tutorials/tools/Understanding and adjusting the autogenerated arm_navigation application (last edited 2012-02-21 12:55:23 by Mark Pitchless)