Wiki

Download and Run

Version: DARRT only compiles and runs against Fuerte.

Downloading DARRT+Sushi code

You need both the DARRT code and the Fuerte version of the "sushi code" developed for the mobile manipulation challenge. To obtain both pieces of code:

  1. Download the rosinstall file.

  2. Install:
    rosinstall . darrth.rosinstall
    If you see the error:
    ERROR: Invalid scm entry having no uri attribute for path /opt/ros/fuerte/setup.sh
    you are using an older version of rosinstall. Comment out the setup-file line in the rosinstall file. After installing everything, rosinstall will give you another error that you can ignore. If you are prompted for a password, that is your password to kforge.ros.org. You must be a member of the sandbox project to download this code. You may need to hit enter a couple times to clear messages that rosinstall does not display.
  3. Add the darrth and the sushi_all folders to your ROS_PACKAGE_PATH. Make sure that your ROS_PACKAGE_PATH points to the version of the distance_field package in darrth. There is currently a bug in the released version of the distance_field that keeps DARRT from doing collision checking (it also causes some errors with the 3D Nav stack in sushi). The folks in charge are looking into this but for now you need the patched version in the darrth folder. Ensure that
    roscd distance_field
    takes you to darrth/distance_field.
  4. Make everything by rosmaking the darrt_actions package
    rosmake darrt_actions
    Compilation, especially of darrt_msgs, may take up to five or ten minutes.

Downloading DARRT

If you already have the sushi code, you can download DARRT alone using

svn co https://kforge.ros.org/sandbox/darrt/fuerte-tag-July-18-2012-Bug-Fix darrth

If you are not a member of the kforge project, you can also get it from the mit-ros-pkg:

svn co https://svn.csail.mit.edu/mit-ros-pkg/branches/sandbox-uncrawled/darrt/fuerte-tag-July-18-2012-Bug-Fix darrth

The most recent version of DARRT is also in the mit-ros-pkg. This is my experimental code and not guaranteed to work. The instructions on this wiki are out of date for this version of the code:

svn co https://svn.csail.mit.edu/mit-ros-pkg/branches/sandbox/darrth darrth

You should then follow steps 3-4 under Downloading DARRT+Sushi.

Run

To run DARRT, just launch darrt.launch on the robot or in simulation using the laser data as an octomap, use

roslaunch darrt darrt.launch

There may be warnings, but should be no errors while launching this file. It expects a local version of the objects database.

This starts interactive manipulation on the robot side and the sushi code for use in executing DARRT plans. It also starts the darrt_action which can be sent DARRTGoal messages. If you want to use interactive manipulation while running DARRT, you only need to launch the desktop file. On the desktop computer (not the robot) launch

roslaunch pr2_interactive_manipulation pr2_interactive_manipulation_desktop.launch

ROS API

All interactions with the DARRT planner can take place through the action interface. This section describes that interface and its input and output.

Action Interface

The DARRTAction provides an action server that takes in goals of the type darrt_msgs/DARRTGoal.

Subscribed Topics

darrt_planning/darrt_action/goal (darrt_msgs/DARRTGoal) darrt_planning/darrt_action/cancel (actionlib_msgs/GoalID)

Goal

The DARRTGoal message is long and complicated but most of the parameters are optional. For a simple pick and place, for example, only two fields matter: the pickup_goal and the place_goal. For other tasks, it is necessary to tell DARRT which primitives it should use.

Pickup Goal

Within the pickup message, the following fields must be defined. All other fields are ignored.

Place Goal

The place goal just tells the planner where the object should end up. This may or may not actually be a "place" on a surface. It is fine for the place goal to in fact be in midair somewhere. The gripper will open at the end of the execution only if the object is actually placed on a support surface. The following fields of the place goal are used (all others are ignored):

Primitives

DARRT plans over primitives that can be used to manipulate objects. At the moment, DARRT can plan with five different primitives:

The primitives DARRT will use to plan are assigned using the primitives field. If this field is left empty, it defaults to PICK, PLACE, and WARP. If no primitives that allow base movement are given (i.e. no BASE_TRANSIT or WARP), DARRT will only do collision checking for the arm rather than the whole robot.

Optional Parameters

The DARRT action also has a number of optional parameters:

Result

DARRT returns a plan but does not execute it. The DARRTResult message duplicates some of the fields of the DARRTGoal message to make it possible to execute a DARRT plan by just sending the result. The darrt_actions package provides a Python script (darrt_actions/src/darrt_actions/darrt_trajectories.py) that can execute DARRT plans. For using the Python script, see the tutorials.

Primitive Trajectories

DARRT returns a plan consisting of many trajectories each corresponding to one primitive. The primitives in DARRTResult do not match those in DARRTGoal because extra information is needed to accurately execute the primitives. In fact, the primitives in DARRTResult much more closely match the underlying primitives used in planning. The primitives are:

DARRT returns a list of primitive types (primitive_types) and corresponding trajectories (primitive_trajectories). primitive_trajectories[i] is an execution of primitive_type[i]. Every trajectory is a trajectory for the full robot - it fills in all of the joints, not just the ones that move. For example if primitive_type[3] = ARM_TRANSIT this means that primitive_trajectories[3] is a collision-free path for the arm. primitive_trajectories[3] is an arm_navigation_msgs/RobotTrajectory and each point contains a joint value for every joint on the robot regardless of whether that joint moves or even whether DARRT planned for the joint. However, it is guaranteed that throughout primitive_trajectories[3] only the arm joints actually do change.

For examples of interpreting and executing DARRT plans, see the tutorials.

Error Codes

DARRT also returns an error code. The possible values for this code are:

Notes

Planning Description File

DARRT uses its own version of pr2_planning_description.yaml both to change the world frame of the robot when using an Octomap (see Using an Octomap) and to define more planning groups than just the arms. Be careful when running DARRT that you do not load a different version of the planning description onto the parameter server! The /robot_description_planning should include the pr2_base as a group (which it does not by default):

jbarry@pr2mm1:~$ rosparam get /robot_description_planning/groups
- joints: [world_joint]
  name: pr2_base
- {base_link: torso_lift_link, name: left_arm, tip_link: l_wrist_roll_link}
- {base_link: torso_lift_link, name: right_arm, tip_link: r_wrist_roll_link}
- joints: [l_gripper_palm_joint, l_gripper_l_finger_joint, l_gripper_l_finger_tip_joint,
    l_gripper_led_joint, l_gripper_motor_accelerometer_joint, l_gripper_motor_slider_joint,
    l_gripper_motor_screw_joint, l_gripper_r_finger_joint, l_gripper_r_finger_tip_joint,
    l_gripper_joint, l_gripper_tool_joint]
  name: l_end_effector
- joints: [r_gripper_palm_joint, r_gripper_l_finger_joint, r_gripper_l_finger_tip_joint,
    r_gripper_led_joint, r_gripper_motor_accelerometer_joint, r_gripper_motor_slider_joint,
    r_gripper_motor_screw_joint, r_gripper_r_finger_joint, r_gripper_r_finger_tip_joint,
    r_gripper_joint, r_gripper_tool_joint]
  name: r_end_effector
- joints: [fr_caster_r_wheel_joint, fr_caster_l_wheel_joint, fl_caster_r_wheel_joint,
    fl_caster_l_wheel_joint, br_caster_r_wheel_joint, br_caster_l_wheel_joint, bl_caster_r_wheel_joint,
    bl_caster_l_wheel_joint, fr_caster_rotation_joint, fl_caster_rotation_joint, br_caster_rotation_joint,
    bl_caster_rotation_joint]
  name: wheels
- name: arms
  subgroups: [left_arm, right_arm]

Using an Octomap

DARRT does collision checking using the planning_environment. This means that it does collision checking only with objects added to the collision environment and with the collision map. By default the collision map is the one collected by the tilting laser. However, it is also possible to use a pre-constructed octomap as the collision map. This allows much more accurate collision checking when moving the base. If you have a 3D map, you should launch darrt with the use_map argument set to true:

roslaunch darrt darrt.launch use_map:=true

This will by default use the Willow Garage sushi environment maps. You can change the maps being used by setting the map_suffix argument. Currently the other map available in the repository is g415, which is a map of the robot environment at MIT. You can add maps by adding the appropriate map-<map_suffix>.pgm, map-<map_suffix>.yaml, and octomap-<map_suffix>.bt files to darrt/config and a pr2_both_arms_<map-suffix>.yaml file to sbpl_full_body_planner/config.

The darrt.launch file also brings up localization when running with a 3D map. Because you may want to add things from many parts of the environment to the collision environment, it's important that any object added to the collision environment be added in the localized /map frame and not the /odom_combined frame. This is done by changing the parent_frame_id of the multi DOF joint defined in pr2_planning_description.yaml to be map so the planning description that DARRT loads on the parameter server depends on the use_map argument.

jbarry@pr2mm1:~$ rosparam get /robot_description_planning/multi_dof_joints
- {child_frame_id: base_footprint, name: world_joint, parent_frame_id: map, type: Floating}

Note that running with an octomap as the collision map may make DARRT significantly slower.

Examples

See the tutorials for examples of using DARRT.

Known Problems

DARRT is very much a work in progress. There are several known bugs.

Wiki: darrt (last edited 2013-06-12 17:36:31 by JennyBarry)