$search
00001 #include <ros/ros.h> 00002 #include <tabletop_object_detector/TabletopDetection.h> 00003 #include <tabletop_collision_map_processing/TabletopCollisionMapProcessing.h> 00004 00005 int main(int argc, char **argv) 00006 { 00007 //initialize the ROS node 00008 ros::init(argc, argv, "tabletop_perception_test"); 00009 ros::NodeHandle nh; 00010 00011 //set service and action names 00012 const std::string OBJECT_DETECTION_SERVICE_NAME = 00013 "/object_detection"; 00014 const std::string COLLISION_PROCESSING_SERVICE_NAME = 00015 "/tabletop_collision_map_processing/tabletop_collision_map_processing"; 00016 00017 //create service and action clients 00018 ros::ServiceClient object_detection_srv; 00019 ros::ServiceClient collision_processing_srv; 00020 00021 //wait for detection client 00022 while (!ros::service::waitForService(OBJECT_DETECTION_SERVICE_NAME, 00023 ros::Duration(2.0)) && nh.ok() ) 00024 { 00025 ROS_INFO("Waiting for object detection service to come up"); 00026 } 00027 if (!nh.ok()) exit(0); 00028 object_detection_srv = 00029 nh.serviceClient<tabletop_object_detector::TabletopDetection> 00030 (OBJECT_DETECTION_SERVICE_NAME, true); 00031 00032 //wait for collision map processing client 00033 while ( !ros::service::waitForService(COLLISION_PROCESSING_SERVICE_NAME, 00034 ros::Duration(2.0)) && nh.ok() ) 00035 { 00036 ROS_INFO("Waiting for collision processing service to come up"); 00037 } 00038 if (!nh.ok()) exit(0); 00039 collision_processing_srv = 00040 nh.serviceClient 00041 <tabletop_collision_map_processing::TabletopCollisionMapProcessing> 00042 (COLLISION_PROCESSING_SERVICE_NAME, true); 00043 00044 00045 //call the tabletop detection 00046 ROS_INFO("Calling Tabletop Detector"); 00047 tabletop_object_detector::TabletopDetection detection_call; 00048 //we want recognized database objects returned 00049 //set this to false if you are using the pipeline without the database 00050 detection_call.request.return_clusters = false; 00051 //we want the individual object point clouds returned as well 00052 detection_call.request.return_models = false; 00053 if (!object_detection_srv.call(detection_call)) 00054 { 00055 ROS_ERROR("Tabletop detection service failed"); 00056 return -1; 00057 } 00058 if (detection_call.response.detection.result != 00059 detection_call.response.detection.SUCCESS) 00060 { 00061 ROS_ERROR("Tabletop detection returned error code %d", 00062 detection_call.response.detection.result); 00063 return -1; 00064 } 00065 if (detection_call.response.detection.clusters.empty() && 00066 detection_call.response.detection.models.empty() ) 00067 { 00068 ROS_ERROR("The tabletop detector detected the table, " 00069 "but found no objects"); 00070 return -1; 00071 } 00072 else 00073 { 00074 ROS_WARN("Tabletop suceeded and found %d unknown clusters and %d known objects, and the table", detection_call.response.detection.clusters.size(), detection_call.response.detection.models.size()); 00075 } 00076 00077 //call collision map processing 00078 ROS_INFO("Calling collision map processing"); 00079 tabletop_collision_map_processing::TabletopCollisionMapProcessing 00080 processing_call; 00081 //pass the result of the tabletop detection 00082 processing_call.request.detection_result = 00083 detection_call.response.detection; 00084 //ask for the exising map and collision models to be reset 00085 processing_call.request.reset_static_map = true; 00086 processing_call.request.reset_collision_models = true; 00087 processing_call.request.reset_attached_models = true; 00088 //ask for a new static collision map to be taken with the laser 00089 //after the new models are added to the environment 00090 processing_call.request.take_static_collision_map = true; 00091 //ask for the results to be returned in base link frame 00092 processing_call.request.desired_frame = "katana_base_link"; 00093 if (!collision_processing_srv.call(processing_call)) 00094 { 00095 ROS_ERROR("Collision map processing service failed"); 00096 return -1; 00097 } 00098 //the collision map processor returns instances of graspable objects 00099 if (processing_call.response.graspable_objects.empty()) 00100 { 00101 ROS_ERROR("Collision map processing returned no graspable objects"); 00102 return -1; 00103 } 00104 else 00105 { 00106 ROS_WARN("Collision map processing succeeded and returned %d graspable objects", processing_call.response.graspable_objects.size() ); 00107 } 00108 00109 }