Note: This tutorial assumes that you have completed the previous tutorials: ROS tutorials, Gazebo Tutorials, Controller Tutorials.
(!) 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.

Getting started with arm navigation

Description: This tutorial describes how to get started with using the arm navigation stack to plan and control a robot arm.

Keywords: planning,arm,move_arm,arm planning

Tutorial Level: INTERMEDIATE

Next Tutorial: move_arm/Tutorials/MoveArmJointGoal

The move_arm package integrates complex functionality, moving the arm while also performing motion planning and obstacle avoidance. To perform the simpler task of moving the arm along a pre-specified joint trajectory, without advanced motion planning or obstacle avoidance, please see Moving the arm using the Joint Trajectory Action.

Compiling the arm navigation stack

The arm navigation stack depends on a lot of nodes that provide the set of services that it needs to function. move_arm is a node within the arm_navigation stack that does most of the coordination between motion planning, control, trajectory filtering and inverse kinematics. It is deliberately setup to do little computation internally so that the whole package is more modular and individual parts can be easily replaced. We provide default implementations of all these nodes, some of which are pr2-specific. This tutorial will show you how to launch these nodes in the pr2 gazebo simulation and then get move_arm up and running. We start by compiling all the packages that move_arm needs.

roscd pr2_arm_navigation_actions
rosmake

Required nodes

Move arm needs nodes for planning, control, IK and trajectory monitoring. We will generate a launch file for move_arm to launch all these nodes together. First, open a launch file called move_right_arm.launch and add the following lines:

<launch>

</launch>

You are now ready to populate this file with everything you need to run move_arm.

Planning

Move arm uses a planning node to generate plans for the actions that it wants to execute. There are three different planners that are currently supported and we will use the OMPL planner for this tutorial. Each planner has its own custom launch file that starts up the planner. The launch file for OMPL is located in the pr2_arm_navigation_planning directory. We will include this file in move_right_arm.launch

  <!-- load planning -->
  <include file="$(find pr2_arm_navigation_planning)/launch/ompl_planning.launch"/>

Perception

The perception pipeline is intended to provide information about the environment to the planners. The move_arm action itself does not use the perception pipeline but the nodes associated with it use the pipeline to provide information about the environment in the form of a collision_map. The collision map node documentation provides more information on how the collision map works.

Include the perception pipeline that uses the tilting laser on the pr2 to generate a collision map in your launch file:

  <!-- load perception -->
  <include file="$(find pr2_arm_navigation_perception)/launch/laser-perception.launch"/>

Trajectory filtering

Move arm uses a smoother that takes an incoming path, smooths it and adds velocity information to the path. The launch files for this node are in the pr2_arm_navigation_filtering package.

  <!-- load filtering -->
  <include file="$(find pr2_arm_navigation_filtering)/launch/right_arm_filter.launch"/>

IK

Move arm uses a service call to perform IK. In this tutorial, we will use a particular implementation of the IK for the PR2. To launch this node, include the following line in your launch file:

 <!-- load ik -->
 <include file="$(find pr2_arm_navigation_kinematics)/launch/right_arm_collision_free_ik.launch"/>

Monitor/Collision checking node

Move arm requires a collision checking/monitoring node that provides information about collisions, can be used to monitor safe execution of a trajectory and can provide information about the whole robot. All these services are implemented in one node environment_server. To launch this node, include the following lines in your launch file:

  <!-- load monitor -->
  <include file="$(find pr2_arm_navigation_actions)/launch/environment_server_right_arm.launch"/>

Move arm simple action node

The move_arm_simple_action executable itself does all the heavy lifting including implementing the state machine that move_arm uses, listening for goals, asking for plans, sending out trajectories and monitoring execution. To launch this node, include the following lines in your launch file:

  <!-- load move_arm -->
  <include file="$(find pr2_arm_navigation_actions)/launch/move_right_arm.launch"/>

The complete launch file

The complete arm navigation launch files for both the left and right arms of the PR2 can be found in the pr2_3dnav packages (left_arm_navigation.launch and right_arm_navigation.launch). After all the nodes finish launch, you should see output similar to the following:

[ INFO] 706.573999990: Move arm action started

Wiki: move_arm/Tutorials/GettingStarted (last edited 2011-01-06 14:32:15 by MartinGuenther)