Use the household_objects_database remotely from a Willow Garage server
Description: Shows how to use the household_object_database remotely, by using the services provided by a database wrapper node running on a Willow Garage server.Tutorial Level: BEGINNER
All you have to do to use the household_objects_database remotely is to launch the following file on your local machine, after starting a ROS master:
roslaunch household_objects_database objects_database_remote_client.launch
This will tell your ROS master that the database services should be sent to a remote ROS master running on a server at Willow Garage. The following services get remapped:
/objects_database_node/database_grasp_planning
/objects_database_node/get_model_description
/objects_database_node/get_model_list
/objects_database_node/get_model_mesh
Testing and troubleshooting
To test that this is working, try the following command:
rosservice call /objects_database_node/get_model_list REDUCED_MODEL_SET
The reply should be along the lines of:
return_code: code: -1 model_ids: [18800, 18798, 18665, 18685, 18802, 18746, 18766, 18783, 18765, 18791, 18799, 18693, 18744, 18807, 18808, 18699, 18691]
If instead you get an error like:
ERROR: Unable to communicate with service [/objects_database_node/get_model_description], address [rosrpc://grasp.willowgarage.com:15432]
this might mean that either your machine does not have access to the Internet, or the remote server is down. Please send an email to the ros-users list informing us of the problem.
To get all the objects use the following command:
rosservice call /objects_database_node/get_model_list ""
Advanced testing
To test that the grasp planning service is working, you can use the following command:
rosservice call /objects_database_node/database_grasp_planning "{arm_name: right_arm, target: {type: 1, model_pose:{model_id: 18744 } } }"You should get back a long lists of grasps, all of them looking something like this:
pre_grasp_posture:
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: ''
name: ['r_gripper_l_finger_joint', 'r_gripper_r_finger_joint', 'r_gripper_r_finger_tip_joint', 'r_gripper_l_finger_tip_joint']
position: [0.52359900000000004, 0.52359900000000004, 0.52359900000000004, 0.52359900000000004]
velocity: []
effort: []
grasp_posture:
header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: ''
name: ['r_gripper_l_finger_joint', 'r_gripper_r_finger_joint', 'r_gripper_r_finger_tip_joint', 'r_gripper_l_finger_tip_joint']
position: [0.39125900000000002, 0.39125900000000002, 0.39125900000000002, 0.39125900000000002]
velocity: []
effort: [10000.0, 10000.0, 10000.0, 10000.0]
grasp_pose:
position:
x: -0.121641
y: 0.09348
z: 0.125899
orientation:
x: -0.919996
y: 0.336396
z: 0.187844
w: 0.0718267





