Only released in EOL distros:  

rail_pick_and_place: graspdb | rail_grasp_collection | rail_pick_and_place_msgs | rail_pick_and_place_tools | rail_recognition

Package Summary

Grasp Collection for Constructing a Grasping and Recognition Database

rail_pick_and_place: graspdb | rail_grasp_collection | rail_pick_and_place_msgs | rail_pick_and_place_tools | rail_recognition

Package Summary

Grasp Collection for Constructing a Grasping and Recognition Database

About

The rail_grasp_collection package contains nodes to collect demonstration grasps for detected point cloud objects. These demonstrations can then be used to build object models for recognition and manipulation using the rail_recognition package. Demonstrations are stored in a grasp database, handled by graspdb.

Nodes

rail_grasp_collection

Collect demonstrated grasps with associated point clouds and store them in the grasp database.

Action Goal

rail_grasp_collection/grasp_and_store (rail_pick_and_place_msgs/GraspAndStoreGoal)
  • Execute a grasp and store the result in the grasp database.

Action Result

rail_grasp_collection/grasp_and_store (rail_pick_and_place_msgs/GraspAndStoreResult)
  • Grasp collection result.

Actions Called

gripper_action_server param (rail_manipulation_msgs/GripperAction)
  • Close gripper action.
lift_action_server param (rail_manipulation_msgs/LiftAction)
  • End effector lifting action.
verify_grasp_action_server param (rail_manipulation_msgs/VerifyGraspAction)
  • Determine whether or not a grasp was successful.

Subscribed Topics

segmented_objects_topic param (rail_manipulation_msgs/SegmentedObjectList)
  • Incoming segmented object data.

Published Topics

rail_grasp_collection/debug (sensor_msgs/PointCloud2)
  • Debug publisher for the segmented point cloud collected on calling the grasp_and_store action.

Parameters

debug (bool, default: false)
  • Display debugging information if true.
robot_fixed_frame_id (string, default: "base_footprint")
  • Fixed coordinate frame within the robot's coordinate system.
eef_frame_id (string, default: "eef_link")
  • End effector coordinate frame, used for storing grasp poses.
segmented_objects_topic (string, default: "/segmentation/segmented_objects")
  • Topic for incoming segmented object data.
gripper_action_server (string, default: "/manipulation/gripper")
  • Action server topic for controlling the robot's end effector.
lift_action_server (string, default: "/manipulation/lift")
  • Action server topic for raising the end effector.
verify_grasp_action_server (string, default: "/manipulation/verify_grasp")
  • Action server topic for verifying whether or not a grasp was successful.
/graspdb/host (string, default: "127.0.0.1")
  • Grasp database host ip.
/graspdb/port (int, default: graspdb::Client::DEFAULT_PORT)
  • Grasp database port.
/graspdb/user (string, default: "ros")
  • Grasp database username.
/graspdb/password (string, default: "")
  • Grasp database password.
/graspdb/db (string, default: "graspdb")
  • Grasp database name.

rail_grasp_retriever

Retrieve stored grasps from the grasp database training set.

Action Goal

rail_grasp_retriever/retrieve_grasp (rail_pick_and_place_msgs/RetrieveGraspDemonstrationGoal)
  • Retrieve a specified grasp demonstration from the grasp database.

Action Result

rail_grasp_retriever/retrieve_grasp (rail_pick_and_place_msgs/RetrieveGraspDemonstrationResult)
  • Retrieved grasp result.

Published Topics

rail_grasp_retriever/point_cloud (sensor_msgs/PointCloud2)
  • Retrieved point cloud.
rail_grasp_retriever/pose (geometry_msgs/PoseStamped)
  • Retrieved grasp pose.

Parameters

/graspdb/host (string, default: "127.0.0.1")
  • Grasp database host ip.
/graspdb/port (int, default: graspdb::Client::DEFAULT_PORT)
  • Grasp database port.
/graspdb/user (string, default: "ros")
  • Grasp database username.
/graspdb/password (string, default: "")
  • Grasp database password.
/graspdb/db (string, default: "graspdb")
  • Grasp database name.

Installation

To install the rail_pick_and_place package, you can install from source with the following commands:

  •    1 cd /(your catkin workspace)/src
       2 git clone https://github.com/WPI-RAIL/rail_pick_and_place.git
       3 cd ..
       4 catkin_make
       5 catkin_make install
    

Startup

The rail_grasp_collection package contains launch files for launching either the rail_grasp_collection node or the rail_grasp_retriever node individually, and for launching both nodes together. These can be launched with the following commands, respectively:

  • roslaunch rail_grasp_collection rail_grasp_collection.launch
  • roslaunch rail_grasp_collection rail_grasp_retriever.launch
  • roslaunch rail_grasp_collection rail_grasp_collection_and_retriever.launch

Grasp collection can also be run and executed with an rviz plugin found in rail_pick_and_place_tools.

Wiki: rail_grasp_collection (last edited 2015-03-27 19:25:57 by davidkent)