Note: This tutorial assumes that you have completed the previous tutorials: ROS 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.

Moving the PR2 arm using command line

Description: This tutorial is a brief introduction on how to start up motion planning for the arm.

Tutorial Level: BEGINNER

Setup

To be able to move the arm, three components need to be running:

  • perception : this processes the sensor data so it can be used for collision checking. For more details on this, please see collision_map and collision_space

  • planning : uses perception information to compute paths for a set of joints. For the purpose of this document we only care about the set joints that make up the right arm. For more details on this, please see planning_environment. The paths consist of a sequence of states (not all planners provide velocity information).

  • action interface between planning for the arm and arm controller :

    • listens to requests from the user (for instance, a request to move the arm move_arm),

    • uses the planning component to figure out solution paths,
    • sends the solution paths to the controller so the robot moves,
    • monitors the execution of the path until completion
      • if the path becomes invalid at any point in time, the motion is stopped and a new solution is requested from the planner.

Compiling code

Assuming pr2_alpha (on the robot) or pr2_gazebo (in simulation) are already built, you need to:

   rosmake 3dnav_pr2

Launching things

Assuming the robot is running (or simulation is running):

  • Bring up the robot
       roscd pr2_alpha
       roslaunch [pr[e|f|g] | hc[a|b|c]].launch
    • alternatively, if you are running PR2 in simulation, follow the basic simulator tutorials up to this point, and setting

    • export ROBOT=sim
  • start perception
       roscd 3dnav_pr2
       roslaunch launch/perception/laser-perception.launch
  • Using rviz, check that collision_map_occ topic is being published (you will need the Collision Map panel).On your local machine:

        rosrun rviz rviz
    • Click the "Add" button in the lower left corner of rviz
    • Select "Collision Map" from the pop-up window
    • Click okay, and modify the new "Collision Map" panel to point to the correct topic.
    • Click the "Add" button again
    • Select "Point Cloud" from the pop-up window
      • The point cloud can be used to determine 3D locations of points
        • Select the "View" menu option, and make sure the "Selection" option is enabled
        • Click the "Select" button located near the top left
        • Use the mouse to left-click and drag a box around some points in the point cloud
        • The selected points will appear in a list on the right
  • start planning
       roscd 3dnav_pr2
       roslaunch launch/planning/ompl_fake_planning.launch
    • Check the output produced (or the dashboard) and make sure that right_arm appears in the list of known models.

  • start action
       roscd 3dnav_pr2
       roslaunch launch/actions/right_arm.launch
    • Make sure the message Starting move_arm for 'right_arm' (IK is enabled) appears and no errors about the action being invalid follow.

Commanding the arm

  •    roscd move_arm
       roslaunch launch/arm_cmd_line.launch
    • You should now see a prompt expecting commands for the arm. Type the help command and you should be able to continue from there.

    • The "go" command requires a 3D position. Rviz can be used to select point in a point cloud and print out their positions (see the above section).


Wiki: motion_planning/Tutorials/MovingArmUsingCommandLine (last edited 2009-10-23 21:12:32 by hsu)