Only released in EOL distros:  

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_tabletop_manipulation_launch | pr2_wrappers | rgbd_assembler | robot_self_filter_color | segmented_clutter_grasp_planner | simple_Jtranspose_controller | tabletop_collision_map_processing | tabletop_object_detector | tabletop_vfh_cluster_detector | vfh_recognition | vfh_recognizer_db | vfh_recognizer_fs

Package Summary

Executes a grasp with the PR2 gripper, starting from the pre-grasp stage and using the tactile sensors to correct for unexpected contacts encountered along the way.

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

Executes a grasp with the PR2 gripper, starting from the pre-grasp stage and using the tactile sensors to correct for unexpected contacts encountered along the way.

pr2_object_manipulation: interactive_perception_msgs | manipulation_worlds | object_recognition_gui | pr2_create_object_model | 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_interactive_gripper_pose_action | pr2_interactive_manipulation | pr2_interactive_manipulation_frontend | pr2_interactive_object_detection | pr2_interactive_object_detection_frontend | pr2_manipulation_controllers | pr2_marker_control | pr2_navigation_controllers | pr2_object_manipulation_launch | pr2_object_manipulation_msgs | pr2_pick_and_place_demos | 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

Executes a grasp with the PR2 gripper, starting from the pre-grasp stage and using the tactile sensors to correct for unexpected contacts encountered along the way.

Overview

This package provides reactive grasp, reactive lift, and reactive approach actions, and compliant close and grasp adjustment services for the PR2 gripper. All of the above use the pressure sensors on the fingertips to improve object grasping. Details on this module can be found in the following paper: '''Contact-Reactive Grasping of Objects with Partial Shape Information'''.

In order to use these actions and services, you probably want to launch either

  • pr2_tabletop_manipulation_launch/launch/pr2_tabletop_manipulation.launch (no slip detection)

or

  • pr2_tabletop_manipulation_launch/launch/pr2_tabletop_manipulation_slip.launch (with slip detection)

    NOTE: with trunk of c-turtle/d-turtle you must manually edit pr2_tabletop_manipulation.launch and set <arg name="use_slip_controllers" default="true"/>

ROS API

  • The reactive approach action moves the gripper from a pre-grasp position to a grasp position while monitoring the fingertip sensors; unexpected tip contacts cause the gripper to back up and try to move around the object.
  • The compliant close service closes the gripper while watching the fingertip sensors, so that seeing one contact early causes the arm to counter-move such that the finger that contacted first holds its position.
  • The grasp adjustment service tries to adjust the position of the gripper relative to a grasp such that the contacts do not look unstable (contact only at the edge or only at the tip of the front of a fingertip sensor).
  • The reactive grasp action executes reactive approach, followed by compliant close, followed by grasp adjustment, doing each step multiple times as necessary.
  • The reactive lift action tries to lift an object while using the slip-avoidance controller in package slipgrip_controller to avoid crushing deformable objects more than is necessary to grasp them. It also leaves the slip-avoidance controller in slip-servo mode after it returns, so the controller can continue to adjust the grasp force as needed until the object is released.

API Stability

The ROS API is UNREVIEWED and UNSTABLE

ROS Parameters

Parameters

side_step (double, default: .015 m)
  • How far to move to the side (in the direction of the tip that contacted) during reactive approach.
back_step (double, default: .03 m)
  • How far to back up when a tip contact is detected during reactive approach.
approach_num_tries (int, default: 5)
  • How many times to attempt to back up and move around upon detecting unexpected contacts during reactive approach.
goal_pos_thres (double, default: .01 m)
  • How close you have to be to the goal before reactive approach will ignore tip contacts (and assume it's at a goal that may have desired tip contact).
min_contact_row (int (between 0 and 5), default: 1)
  • How far in contact has to be seen on the 5x3 front array of each fingertip pressure sensor (0=none/disable grasp adjustment in the gripper x-direction, 1=the row nearest to the tip,... 5=the row farthest in) for a grasp to be considered stable
min_gripper_opening (double, default: .0011 m)
  • If the gripper closes to a value lower than this, it will assume that it is empty.
max_gripper_opening (double, default: .1 m)
  • If the gripper closes and has a value higher than this, it will assume that the grasp failed (useful if you know the width of the desired grasp).
grasp_adjust_x_step (double, default: .02 m)
  • How far to move the gripper along the gripper x-axis during grasp adjustment when only tip contacts are seen
grasp_adjust_z_step (double, default: .015 m)
  • How far to move the gripper along the gripper +-z-axis during grasp adjustment when only edge contacts are seen
grasp_num_tries (int, default: 2)
  • Number of times to attempt the reactive approach (upon failure, if this param is more than 1, the gripper will move the goal forward by forward_step and perform reactive approach again).
forward_step (double, default: 0)
  • If non-zero, how far to move the goal forward before attempting reactive approach again. If set to zero, defaults to 3 cm for grasps from the top and 6 cm for grasps from any other direction.
close_force (double, default: 100)
  • The gripper force to use when closing hard (used every time if use_slip_controller is false; used only if the grasp still looks unstable after adjustment if use_slip_controller is true)
use_slip_controller (bool, default: False)
  • If True, uses the pr2_gripper_fingersensor_action; if False, uses the default pr2_gripper_action. If this is False, reactive lift becomes just a Cartesian move up, and reactive grasp will always use close_force when closing on the object.

Action APIs

The reactive_grasp_server node provides implementations of SimpleActionServer (see actionlib documentation). The action servers for reactive grasp and reactive approach take in goals containing object_manipulation_msgs/ReactiveGraspGoal messages, and the action server for reactive lift takes in goals containing object_manipulation_msgs/ReactiveLiftGoal messages. You can communicate with these nodes over ROS directly, but the recommended way to send goals is by using the SimpleActionClient. Please see actionlib documentation for more information.

Reactive Grasp Action Subscribed Topics

reactive_grasp/right/goal (or reactive_grasp/left/goal) (object_manipulation_msgs/ReactiveGraspGoal)

  • A goal for executing a reactive grasp.
reactive_grasp/right/cancel (or reactive_grasp/left/cancel) (actionlib_msgs/GoalID)
  • A request to cancel a specific goal.

Reactive Grasp Action Published Topics

reactive_grasp/right/status (or reactive_grasp/left/status) (actionlib_msgs/GoalStatusArray)

  • Provides status information on the goals that are sent to the reactive grasp action.
reactive_grasp/right/result (or reactive_grasp/left/result) (object_manipulation_msgs/ReactiveGraspResult)
  • Contains a result code of type object_manipulation_msgs/ManipulationResult, that indicates the final result of the reactive grasp.

Reactive Approach Action Subscribed Topics

reactive_approach/right/goal (or reactive_approach/left/goal) (object_manipulation_msgs/ReactiveGraspGoal)

  • A goal for executing a reactive approach.
reactive_approach/right/cancel (or reactive_approach/left/cancel) (actionlib_msgs/GoalID)
  • A request to cancel a specific goal.

Reactive Approach Action Published Topics

reactive_approach/right/status (or reactive_approach/left/status) (actionlib_msgs/GoalStatusArray)

  • Provides status information on the goals that are sent to the reactive approach action.
reactive_approach/right/result (or reactive_approach/left/result) (object_manipulation_msgs/ReactiveGraspResult)
  • Contains a result code of type object_manipulation_msgs/ManipulationResult, that indicates the final result of the reactive approach.

Reactive Lift Action Subscribed Topics

reactive_lift/right/goal (or reactive_lift/left/goal) (object_manipulation_msgs/ReactiveLiftGoal)

  • A goal for executing a reactive lift.
reactive_lift/right/cancel (or reactive_lift/left/cancel) (actionlib_msgs/GoalID)
  • A request to cancel a specific goal.

Reactive Lift Action Published Topics

reactive_lift/right/status (or reactive_lift/left/status) (actionlib_msgs/GoalStatusArray)

  • Provides status information on the goals that are sent to the reactive lift action.
reactive_lift/right/result (or reactive_lift/left/result) (object_manipulation_msgs/ReactiveLiftResult)
  • Contains a result code of type object_manipulation_msgs/ManipulationResult, that indicates the final result of the reactive lift.

Services

Both the compliant close and grasp adjustment services use the std_srvs/Empty service. (If you use these services and would prefer that they be actions, or that they provide feedback of some sort, email hsiao@willowgarage.com with your suggestions, and they're likely to be implemented in a later release.)

The compliant close service is called /l_reactive_grasp/compliant_close (or /r_reactive_grasp/compliant_close) and the grasp adjustment service is called /l_reactive_grasp/grasp_adjustment (or r_reactive_grasp/grasp_adjustment).

Wiki: pr2_gripper_reactive_approach (last edited 2011-04-01 20:11:04 by JoeRomano)