New in Diamondback
Only released in EOL distros:
Package Summary
A package that allows a remote user to request and assist with grasping and manipulation tasks, primarily using an rviz display.
- Author: Matei Ciocarlie
- License: BSD
- Repository: wg-ros-pkg
- Source: svn https://code.ros.org/svn/wg-ros-pkg/stacks/pr2_tabletop_manipulation_apps/tags/pr2_tabletop_manipulation_apps-0.4.5
Package Summary
A package that allows a remote user to request and assist with grasping and manipulation tasks, primarily using an rviz display.
- Author: Matei Ciocarlie, Kaijen Hsiao, Adam Leeper
- License: BSD
- Source: svn https://code.ros.org/svn/wg-ros-pkg/stacks/pr2_object_manipulation/branches/0.5-branch
pr2_object_manipulation: active_realtime_segmentation | fast_plane_detection | manipulation_worlds | object_recognition_gui | object_segmentation_gui | pick_and_place_demo_app | pr2_create_object_model | pr2_grasp_adjust | pr2_gripper_grasp_controller | pr2_gripper_grasp_planner_cluster | pr2_gripper_reactive_approach | pr2_gripper_sensor_action | pr2_gripper_sensor_controller | pr2_gripper_sensor_msgs | pr2_handy_tools | pr2_interactive_gripper_pose_action | pr2_interactive_manipulation | pr2_interactive_object_detection | pr2_manipulation_controllers | pr2_marker_control | pr2_navigation_controllers | pr2_object_manipulation_launch | pr2_object_manipulation_msgs | pr2_pick_and_place_demos | pr2_pick_and_place_tutorial | pr2_tabletop_manipulation_launch | pr2_wrappers | rgbd_assembler | robot_self_filter_color | segmented_clutter_grasp_planner | tabletop_collision_map_processing | tabletop_object_detector | tf_throttle
Package Summary
A package that allows a remote user to request and assist with grasping and manipulation tasks, primarily using an rviz display.
- Author: Matei Ciocarlie, Kaijen Hsiao, Adam Leeper
- License: BSD
- Source: svn https://code.ros.org/svn/wg-ros-pkg/stacks/pr2_object_manipulation/branches/0.6-branch
Package Summary
A package that allows a remote user to request and assist with grasping and manipulation tasks, primarily using an rviz display.
- Author: Matei Ciocarlie, Kaijen Hsiao, Adam Leeper
- License: BSD
- Source: git https://github.com/ros-interactive-manipulation/pr2_object_manipulation.git (branch: groovy-devel)
Contents
Overview
The PR2 interactive manipulation tool is designed to allow a remote user to execute grasping and placing tasks using a PR2 robot. It interfaces with the user via the rviz visualization engine. It is designed to make the task of picking up and placing an object without colliding with the environment as easy for the operator as possible.
There are two main components to executing a remote grasping or placing tasks.
- the PR2 Interactive Manipulation window, described here. This window allows the user to request the execution of the task and to acquire collision maps used for collision-free execution of the task. It also contains interface for a number of simple arm movement primitives, provided here for convenience. Think of it as "high-level mission control" for grasping and placing.
- the Gripper Click interface, contained in the pr2_gripper_click package. This interface allows the operator to specify the desired grasp point in a scene. Think of it as "low-level information gathering" for grasping and placing. 
In addition, you can use the pr2_interactive_object_detection tools to perform tasks such as object segmentation and recognition. Once an object is segmented or recognized, it is often the case that it can be picked up autonomously. The results of the pr2_interactive_object_detection tools will automatically show up in the interactive manipulation controls, as described below.
The documentation on this page will show you how to use these tools to execute remote grasping and placing tasks on the PR2.
Starting the PR2 Interactive Manipulation Tool
You will have to bring up the components of the PR2 Interactive Manipulation tool both on the robot you are teleoperating and on the desktop you are using.
On the robot
Start the following launch file:
roslaunch pr2_interactive_manipulation pr2_interactive_manipulation_robot.launch
On the desktop
Start the following launch file:
roslaunch pr2_interactive_manipulation pr2_interactive_manipulation_desktop.launch
Note that this launch file will bring up rviz. The PR2 Interactive Manipulation tools are implemented as rviz plugins. In particular, you will see the Interactive manipulation dialog pop up:
diamondback/graspplace.png) 
 
The launch file above will also instantiate all the other rviz displays that you need, although some of them will be disabled on launch. For example, the launch file above will also make sure rviz also contains all the display types from the pr2_interactive_object_detection package.
If you do not use the launch file above, but simply start rviz and then create the displays yourself, the PR2 Interactive Manipulation window will show up and grasping and placing functionality will still work, but the convenience functions provided for arm movement will not.
Also on the desktop, you can optionally attach a PS3 joystick (not the one paired with the robot) directly via a USB cable. The launch files above will also bring up the standard PR2 joystick teleop node and make it listen to the joystick connected to your desktop.
Using the PR2 Interactive Manipulation Tool
General setup
Drive the robot within reach of the objects you are trying to manipulate. Note that base positioning is generally outside the scope of this package which is dedicated to manipulation. However, for convenience, the launch files above also start a joystick teleop package using the joystick plugged into your desktop computer.
Here is an example of robot positioning, which was used to get the screenshots in this examples:
diamondback/robot_manip.jpg) 
 
In general, the view from the robot's wide angle camera is very useful for remote operation. The interactive manipulation launch file will automatically create the rviz display to view it; make sure it is enabled so you get a video stream:
diamondback/wide_camera.png) 
 
Collision map acquisition
It is recommended to acquire a new collision map after you are done positioning the base of the robot for grasping, but before you attempt to grasp or place an object. Use the Collision tab of the Interactive Manipulation dialog:
diamondback/collision.png) 
 
Simply click the "Take new static map" button and the robot will acquire a new map from the tilting laser. To see it in rviz, enable the Collision Map plugin (which should already be in your rviz displays list as the interactive manipulation launch file automatically loads it on startup). The map will show up as blue-ish boxes:
diamondback/coll_map.png) 
 
Note that:
- the arms of the robot might occlude parts of the environment
- occasionally, the robot sees its own body as an obstacle (when the self-filter fails to eliminate it from the scan). Such ghost obstacles will prevent arm motion, so it is recommended to get the arms out of the way (see section below on arm movement) and acquire a new map
Grasping and placing
Use the Grasp and place tab of the Interactive Manipulation dialog:
diamondback/graspplace.png) 
 
The grasping method drop down box offers two options:
- gripper click is the default, and always available. This will allow you to manually choose a grasp point, using the tools described in the pr2_gripper_click package. 
- object selection is only available if an object in the scene has been either segmented or recognized, using the Interactive object detection dialog which calls the tools described in the pr2_interactive_object_detection package. 
If you choose this option, you will only have to choose which object from the scene you want to grasp, and the robot will plan a grasp automatically.
Depending on which method above you choose, you will get a pop-up window requiring your input. Once the input is confirmed, the grasp execution should continue. If all goes well, the arm will move and pick up the object. If not, you should get an informative error message in the status area of the Interactive Manipulation window.
For placing, use the Place button. For now, the only selection for choosing a place location is the one described in the pr2_gripper_click package.
Arm movement
For convenience, the Interactive Manipulation tool also provides some arm movement functionality. Use the Helper tools tab of the Interactive manipulation dialog:
diamondback/helper_manip.png) 
 
You can move the arms to a two pre-defined positions
- side position, great for taking collision maps and other sensor data with the arms out of the way. Bad for navigation, as the robot won't fit through doors or narrow corridors.
- front position, with the arms in front of the robot. Meant for driving around while holding an object.
You can move the arm to these positions in two ways:
- using motion planner: the robot will attempt to plan and execute a collision-free path to the destination. Uses the current collision map, acquired as described earlier. Note that occasionally the robot gets into states where the motion planner will not work (such as perceived collisions with the environment or joint angles beyond legal limits). If this happens, the the option below
- open-loop: the robot will execute a pre-defined joint trajectory to get the arm to the desired position. No collision checking is performed, so the arm might hit the environment. This option is useful for getting the robot out of a stuck position that the planner will not plan out of. 
