$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 // Author(s): Matei Ciocarlie 00036 00039 00040 #include <vector> 00041 #include <boost/shared_ptr.hpp> 00042 00043 #include <ros/ros.h> 00044 00045 #include <actionlib/server/simple_action_server.h> 00046 00047 #include <tf/transform_datatypes.h> 00048 #include <tf/transform_listener.h> 00049 00050 #include <object_manipulation_msgs/GraspPlanning.h> 00051 #include <object_manipulation_msgs/GraspPlanningAction.h> 00052 00053 #include <household_objects_database_msgs/GetModelList.h> 00054 #include <household_objects_database_msgs/GetModelMesh.h> 00055 #include <household_objects_database_msgs/GetModelDescription.h> 00056 #include <household_objects_database_msgs/GetModelScans.h> 00057 #include <household_objects_database_msgs/DatabaseScan.h> 00058 #include <household_objects_database_msgs/SaveScan.h> 00059 #include <household_objects_database_msgs/TranslateRecognitionId.h> 00060 00061 #include "household_objects_database/objects_database.h" 00062 00063 const std::string GET_MODELS_SERVICE_NAME = "get_model_list"; 00064 const std::string GET_MESH_SERVICE_NAME = "get_model_mesh"; 00065 const std::string GET_DESCRIPTION_SERVICE_NAME = "get_model_description"; 00066 const std::string GRASP_PLANNING_SERVICE_NAME = "database_grasp_planning"; 00067 const std::string GET_SCANS_SERVICE_NAME = "get_model_scans"; 00068 const std::string SAVE_SCAN_SERVICE_NAME = "save_model_scan"; 00069 const std::string TRANSLATE_ID_SERVICE_NAME = "translate_id"; 00070 const std::string GRASP_PLANNING_ACTION_NAME = "database_grasp_planning"; 00071 00072 using namespace household_objects_database_msgs; 00073 using namespace household_objects_database; 00074 using namespace object_manipulation_msgs; 00075 00077 00078 class HandDescription 00079 { 00080 private: 00082 ros::NodeHandle root_nh_; 00083 00084 inline std::string getStringParam(std::string name) 00085 { 00086 std::string value; 00087 if (!root_nh_.getParamCached(name, value)) 00088 { 00089 ROS_ERROR("Hand description: could not find parameter %s", name.c_str()); 00090 } 00091 //ROS_INFO_STREAM("Hand description param " << name << " resolved to " << value); 00092 return value; 00093 } 00094 00095 inline std::vector<std::string> getVectorParam(std::string name) 00096 { 00097 std::vector<std::string> values; 00098 XmlRpc::XmlRpcValue list; 00099 if (!root_nh_.getParamCached(name, list)) 00100 { 00101 ROS_ERROR("Hand description: could not find parameter %s", name.c_str()); 00102 } 00103 if (list.getType() != XmlRpc::XmlRpcValue::TypeArray) 00104 { 00105 ROS_ERROR("Hand description: bad parameter %s", name.c_str()); 00106 } 00107 //ROS_INFO_STREAM("Hand description vector param " << name << " resolved to:"); 00108 for (int32_t i=0; i<list.size(); i++) 00109 { 00110 if (list[i].getType() != XmlRpc::XmlRpcValue::TypeString) 00111 { 00112 ROS_ERROR("Hand description: bad parameter %s", name.c_str()); 00113 } 00114 values.push_back( static_cast<std::string>(list[i]) ); 00115 //ROS_INFO_STREAM(" " << values.back()); 00116 } 00117 return values; 00118 } 00119 00120 public: 00121 HandDescription() : root_nh_("~") {} 00122 00123 inline std::string handDatabaseName(std::string arm_name) 00124 { 00125 return getStringParam("/hand_description/" + arm_name + "/hand_database_name"); 00126 } 00127 00128 inline std::vector<std::string> handJointNames(std::string arm_name) 00129 { 00130 return getVectorParam("/hand_description/" + arm_name + "/hand_joints"); 00131 } 00132 00133 }; 00134 00136 00138 class ObjectsDatabaseNode 00139 { 00140 private: 00142 ros::NodeHandle priv_nh_; 00143 00145 ros::NodeHandle root_nh_; 00146 00148 ros::ServiceServer get_models_srv_; 00149 00151 ros::ServiceServer get_mesh_srv_; 00152 00154 ros::ServiceServer get_description_srv_; 00155 00157 ros::ServiceServer grasp_planning_srv_; 00158 00160 actionlib::SimpleActionServer<object_manipulation_msgs::GraspPlanningAction> *grasp_planning_server_; 00161 00163 ros::ServiceServer get_scans_srv_; 00164 00166 ros::ServiceServer save_scan_srv_; 00167 00169 ros::ServiceServer translate_id_srv_; 00170 00172 ObjectsDatabase *database_; 00173 00175 tf::TransformListener listener_; 00176 00178 double prune_gripper_opening_; 00179 00181 double prune_table_clearance_; 00182 00183 bool translateIdCB(TranslateRecognitionId::Request &request, TranslateRecognitionId::Response &response) 00184 { 00185 std::vector<boost::shared_ptr<DatabaseScaledModel> > models; 00186 if (!database_) 00187 { 00188 ROS_ERROR("Translate is service: database not connected"); 00189 response.result = response.DATABASE_ERROR; 00190 return true; 00191 } 00192 if (!database_->getScaledModelsByRecognitionId(models, request.recognition_id)) 00193 { 00194 ROS_ERROR("Translate is service: query failed"); 00195 response.result = response.DATABASE_ERROR; 00196 return true; 00197 } 00198 if (models.empty()) 00199 { 00200 ROS_ERROR("Translate is service: recognition id %s not found", request.recognition_id.c_str()); 00201 response.result = response.ID_NOT_FOUND; 00202 return true; 00203 } 00204 response.household_objects_id = models[0]->id_.data(); 00205 if (models.size() > 1) ROS_WARN("Multiple matches found for recognition id %s. Returning the first one.", 00206 request.recognition_id.c_str()); 00207 response.result = response.SUCCESS; 00208 return true; 00209 } 00210 00212 bool getModelsCB(GetModelList::Request &request, GetModelList::Response &response) 00213 { 00214 if (!database_) 00215 { 00216 response.return_code.code = response.return_code.DATABASE_NOT_CONNECTED; 00217 return true; 00218 } 00219 std::vector< boost::shared_ptr<DatabaseScaledModel> > models; 00220 if (!database_->getScaledModelsBySet(models, request.model_set)) 00221 { 00222 response.return_code.code = response.return_code.DATABASE_QUERY_ERROR; 00223 return true; 00224 } 00225 for (size_t i=0; i<models.size(); i++) 00226 { 00227 response.model_ids.push_back( models[i]->id_.data() ); 00228 } 00229 response.return_code.code = response.return_code.SUCCESS; 00230 return true; 00231 } 00232 00234 bool getMeshCB(GetModelMesh::Request &request, GetModelMesh::Response &response) 00235 { 00236 if (!database_) 00237 { 00238 response.return_code.code = response.return_code.DATABASE_NOT_CONNECTED; 00239 return true; 00240 } 00241 if ( !database_->getScaledModelMesh(request.model_id, response.mesh) ) 00242 { 00243 response.return_code.code = response.return_code.DATABASE_QUERY_ERROR; 00244 return true; 00245 } 00246 response.return_code.code = response.return_code.SUCCESS; 00247 return true; 00248 } 00249 00251 bool getDescriptionCB(GetModelDescription::Request &request, GetModelDescription::Response &response) 00252 { 00253 if (!database_) 00254 { 00255 response.return_code.code = response.return_code.DATABASE_NOT_CONNECTED; 00256 return true; 00257 } 00258 std::vector< boost::shared_ptr<DatabaseScaledModel> > models; 00259 00260 std::stringstream id; 00261 id << request.model_id; 00262 std::string where_clause("scaled_model_id=" + id.str()); 00263 if (!database_->getList(models, where_clause) || models.size() != 1) 00264 { 00265 response.return_code.code = response.return_code.DATABASE_QUERY_ERROR; 00266 return true; 00267 } 00268 response.tags = models[0]->tags_.data(); 00269 response.name = models[0]->model_.data(); 00270 response.maker = models[0]->maker_.data(); 00271 response.return_code.code = response.return_code.SUCCESS; 00272 return true; 00273 } 00274 00275 bool getScansCB(GetModelScans::Request &request, GetModelScans::Response &response) 00276 { 00277 if (!database_) 00278 { 00279 ROS_ERROR("GetModelScan: database not connected"); 00280 response.return_code.code = DatabaseReturnCode::DATABASE_NOT_CONNECTED; 00281 return true; 00282 } 00283 00284 database_->getModelScans(request.model_id, request.scan_source,response.matching_scans); 00285 response.return_code.code = DatabaseReturnCode::SUCCESS; 00286 return true; 00287 } 00288 00289 bool saveScanCB(SaveScan::Request &request, SaveScan::Response &response) 00290 { 00291 if (!database_) 00292 { 00293 ROS_ERROR("SaveScan: database not connected"); 00294 response.return_code.code = DatabaseReturnCode::DATABASE_NOT_CONNECTED; 00295 return true; 00296 } 00297 household_objects_database::DatabaseScan scan; 00298 scan.frame_id_.get() = request.ground_truth_pose.header.frame_id; 00299 scan.cloud_topic_.get() = request.cloud_topic; 00300 scan.object_pose_.get().pose_ = request.ground_truth_pose.pose; 00301 scan.scaled_model_id_.get() = request.scaled_model_id; 00302 scan.scan_bagfile_location_.get() = request.bagfile_location; 00303 scan.scan_source_.get() = request.scan_source; 00304 database_->insertIntoDatabase(&scan); 00305 response.return_code.code = DatabaseReturnCode::SUCCESS; 00306 return true; 00307 } 00308 00310 00313 virtual void pruneGraspList(std::vector< boost::shared_ptr<DatabaseGrasp> > &grasps, 00314 double gripper_threshold, 00315 double table_clearance_threshold) 00316 { 00317 std::vector< boost::shared_ptr<DatabaseGrasp> >::iterator prune_it = grasps.begin(); 00318 int pruned = 0; 00319 while ( prune_it != grasps.end() ) 00320 { 00321 //by mistake, table clearance in database is currently in mm 00322 if ((*prune_it)->final_grasp_posture_.get().joint_angles_[0] > gripper_threshold || 00323 (table_clearance_threshold >= 0.0 && (*prune_it)->table_clearance_.get() < table_clearance_threshold*1.0e3) ) 00324 { 00325 if (gripper_threshold >= 0.0 && (*prune_it)->final_grasp_posture_.get().joint_angles_[0] > gripper_threshold) 00326 ROS_DEBUG("gripper_threshold: %.2f, joint_angles: %.2f, pruning grasp", 00327 gripper_threshold, (*prune_it)->final_grasp_posture_.get().joint_angles_[0]); 00328 else ROS_DEBUG("table_clearance_threshold: %.2f, table_clearance: %.2f, pruning grasp", 00329 table_clearance_threshold,(*prune_it)->table_clearance_.get()); 00330 prune_it = grasps.erase(prune_it); 00331 pruned++; 00332 } 00333 else 00334 { 00335 prune_it++; 00336 } 00337 } 00338 ROS_INFO("Database grasp planner: pruned %d grasps for table collision or gripper angle above threshold", pruned); 00339 } 00340 00341 geometry_msgs::Pose multiplyPoses(const geometry_msgs::Pose &p1, 00342 const geometry_msgs::Pose &p2) 00343 { 00344 tf::Transform t1; 00345 tf::poseMsgToTF(p1, t1); 00346 tf::Transform t2; 00347 tf::poseMsgToTF(p2, t2); 00348 t2 = t1 * t2; 00349 geometry_msgs::Pose out_pose; 00350 tf::poseTFToMsg(t2, out_pose); 00351 return out_pose; 00352 } 00353 00354 //retrieves all grasps from the database for a given target 00355 bool getGrasps(const GraspableObject &target, const std::string &arm_name, 00356 std::vector<Grasp> &grasps, GraspPlanningErrorCode &error_code) 00357 { 00358 if (!database_) 00359 { 00360 ROS_ERROR("Database grasp planning: database not connected"); 00361 error_code.value = error_code.OTHER_ERROR; 00362 return false; 00363 } 00364 00365 if (target.potential_models.empty()) 00366 { 00367 ROS_ERROR("Database grasp planning: no potential model information in grasp planning target"); 00368 error_code.value = error_code.OTHER_ERROR; 00369 return false; 00370 } 00371 00372 if (target.potential_models.size() > 1) 00373 { 00374 ROS_WARN("Database grasp planning: target has more than one potential models. " 00375 "Returning grasps for first model only"); 00376 } 00377 00378 HandDescription hd; 00379 int model_id = target.potential_models[0].model_id; 00380 std::string hand_id = hd.handDatabaseName(arm_name); 00381 00382 //retrieve the raw grasps from the database 00383 std::vector< boost::shared_ptr<DatabaseGrasp> > db_grasps; 00384 if (!database_->getClusterRepGrasps(model_id, hand_id, db_grasps)) 00385 { 00386 ROS_ERROR("Database grasp planning: database query error"); 00387 error_code.value = error_code.OTHER_ERROR; 00388 return false; 00389 } 00390 ROS_INFO("Database object node: retrieved %u grasps from database", (unsigned int)db_grasps.size()); 00391 00392 //prune the retrieved grasps 00393 pruneGraspList(db_grasps, prune_gripper_opening_, prune_table_clearance_); 00394 00395 //randomize the order of the grasps 00396 std::random_shuffle(db_grasps.begin(), db_grasps.end()); 00397 00398 //convert to the Grasp data type 00399 std::vector< boost::shared_ptr<DatabaseGrasp> >::iterator it; 00400 for (it = db_grasps.begin(); it != db_grasps.end(); it++) 00401 { 00402 ROS_ASSERT( (*it)->final_grasp_posture_.get().joint_angles_.size() == 00403 (*it)->pre_grasp_posture_.get().joint_angles_.size() ); 00404 Grasp grasp; 00405 std::vector<std::string> joint_names = hd.handJointNames(arm_name); 00406 00407 if (hand_id != "WILLOW_GRIPPER_2010") 00408 { 00409 //check that the number of joints in the ROS description of this hand 00410 //matches the number of values we have in the database 00411 if (joint_names.size() != (*it)->final_grasp_posture_.get().joint_angles_.size()) 00412 { 00413 ROS_ERROR("Database grasp specification does not match ROS description of hand. " 00414 "Hand is expected to have %d joints, but database grasp specifies %d values", 00415 (int)joint_names.size(), (int)(*it)->final_grasp_posture_.get().joint_angles_.size()); 00416 continue; 00417 } 00418 //for now we silently assume that the order of the joints in the ROS description of 00419 //the hand is the same as in the database description 00420 grasp.pre_grasp_posture.name = joint_names; 00421 grasp.grasp_posture.name = joint_names; 00422 grasp.pre_grasp_posture.position = (*it)->pre_grasp_posture_.get().joint_angles_; 00423 grasp.grasp_posture.position = (*it)->final_grasp_posture_.get().joint_angles_; 00424 } 00425 else 00426 { 00427 //unfortunately we have to hack this, as the grasp is really defined by a single 00428 //DOF, but the urdf for the PR2 gripper is not well set up to do that 00429 if ( joint_names.size() != 4 || (*it)->final_grasp_posture_.get().joint_angles_.size() != 1) 00430 { 00431 ROS_ERROR("PR2 gripper specs and database grasp specs do not match expected values"); 00432 continue; 00433 } 00434 grasp.pre_grasp_posture.name = joint_names; 00435 grasp.grasp_posture.name = joint_names; 00436 //replicate the single value from the database 4 times 00437 grasp.pre_grasp_posture.position.resize( joint_names.size(), 00438 (*it)->pre_grasp_posture_.get().joint_angles_.at(0)); 00439 grasp.grasp_posture.position.resize( joint_names.size(), 00440 (*it)->final_grasp_posture_.get().joint_angles_.at(0)); 00441 } 00442 //for now the effort is not in the database so we hard-code it in here 00443 //this will change at some point 00444 grasp.grasp_posture.effort.resize(joint_names.size(), 50); 00445 grasp.pre_grasp_posture.effort.resize(joint_names.size(), 100); 00446 //min and desired approach distances are the same for all grasps 00447 grasp.desired_approach_distance = 0.10; 00448 grasp.min_approach_distance = 0.05; 00449 //the pose of the grasp 00450 grasp.grasp_pose = (*it)->final_grasp_pose_.get().pose_; 00451 //convert it to the frame of the detection 00452 grasp.grasp_pose = multiplyPoses(target.potential_models[0].pose.pose, grasp.grasp_pose); 00453 //and then finally to the reference frame of the object 00454 if (target.potential_models[0].pose.header.frame_id != 00455 target.reference_frame_id) 00456 { 00457 tf::StampedTransform ref_trans; 00458 try 00459 { 00460 listener_.lookupTransform(target.reference_frame_id, 00461 target.potential_models[0].pose.header.frame_id, 00462 ros::Time(0), ref_trans); 00463 } 00464 catch (tf::TransformException ex) 00465 { 00466 ROS_ERROR("Grasp planner: failed to get transform from %s to %s; exception: %s", 00467 target.reference_frame_id.c_str(), 00468 target.potential_models[0].pose.header.frame_id.c_str(), ex.what()); 00469 error_code.value = error_code.OTHER_ERROR; 00470 return false; 00471 } 00472 geometry_msgs::Pose ref_pose; 00473 tf::poseTFToMsg(ref_trans, ref_pose); 00474 grasp.grasp_pose = multiplyPoses(ref_pose, grasp.grasp_pose); 00475 } 00476 //stick the scaled quality into the success_probability field 00477 grasp.success_probability = (*it)->scaled_quality_.get(); 00478 00479 //insert the new grasp in the list 00480 grasps.push_back(grasp); 00481 } 00482 00483 ROS_INFO("Database grasp planner: returning %u grasps", (unsigned int)grasps.size()); 00484 error_code.value = error_code.SUCCESS; 00485 return true; 00486 } 00487 00489 bool graspPlanningCB(GraspPlanning::Request &request, GraspPlanning::Response &response) 00490 { 00491 getGrasps(request.target, request.arm_name, response.grasps, response.error_code); 00492 return true; 00493 } 00494 00495 void graspPlanningActionCB(const object_manipulation_msgs::GraspPlanningGoalConstPtr &goal) 00496 { 00497 std::vector<Grasp> grasps; 00498 GraspPlanningErrorCode error_code; 00499 GraspPlanningResult result; 00500 GraspPlanningFeedback feedback; 00501 bool success = getGrasps(goal->target, goal->arm_name, grasps, error_code); 00502 /* 00503 for (size_t i=0; i<grasps.size(); i++) 00504 { 00505 if (grasp_planning_server_->isPreemptRequested()) 00506 { 00507 grasp_planning_server_->setAborted(result); 00508 return; 00509 } 00510 feedback.grasps.push_back(grasps[i]); 00511 if ( (i+1)%10==0) 00512 { 00513 grasp_planning_server_->publishFeedback(feedback); 00514 ros::Duration(10.0).sleep(); 00515 } 00516 } 00517 */ 00518 result.grasps = grasps; 00519 result.error_code = error_code; 00520 if (!success) 00521 { 00522 grasp_planning_server_->setAborted(result); 00523 return; 00524 } 00525 grasp_planning_server_->setSucceeded(result); 00526 } 00527 00528 public: 00529 ObjectsDatabaseNode() : priv_nh_("~"), root_nh_("") 00530 { 00531 //initialize database connection 00532 std::string database_host, database_port, database_user, database_pass, database_name; 00533 root_nh_.param<std::string>("/household_objects_database/database_host", database_host, ""); 00534 int port_int; 00535 root_nh_.param<int>("/household_objects_database/database_port", port_int, -1); 00536 std::stringstream ss; ss << port_int; database_port = ss.str(); 00537 root_nh_.param<std::string>("/household_objects_database/database_user", database_user, ""); 00538 root_nh_.param<std::string>("/household_objects_database/database_pass", database_pass, ""); 00539 root_nh_.param<std::string>("/household_objects_database/database_name", database_name, ""); 00540 database_ = new ObjectsDatabase(database_host, database_port, database_user, database_pass, database_name); 00541 if (!database_->isConnected()) 00542 { 00543 ROS_ERROR("ObjectsDatabaseNode: failed to open model database on host " 00544 "%s, port %s, user %s with password %s, database %s. Unable to do grasp " 00545 "planning on database recognized objects. Exiting.", 00546 database_host.c_str(), database_port.c_str(), 00547 database_user.c_str(), database_pass.c_str(), database_name.c_str()); 00548 delete database_; database_ = NULL; 00549 } 00550 00551 //advertise services 00552 get_models_srv_ = priv_nh_.advertiseService(GET_MODELS_SERVICE_NAME, &ObjectsDatabaseNode::getModelsCB, this); 00553 get_mesh_srv_ = priv_nh_.advertiseService(GET_MESH_SERVICE_NAME, &ObjectsDatabaseNode::getMeshCB, this); 00554 get_description_srv_ = priv_nh_.advertiseService(GET_DESCRIPTION_SERVICE_NAME, 00555 &ObjectsDatabaseNode::getDescriptionCB, this); 00556 grasp_planning_srv_ = priv_nh_.advertiseService(GRASP_PLANNING_SERVICE_NAME, 00557 &ObjectsDatabaseNode::graspPlanningCB, this); 00558 00559 get_scans_srv_ = priv_nh_.advertiseService(GET_SCANS_SERVICE_NAME, 00560 &ObjectsDatabaseNode::getScansCB, this); 00561 save_scan_srv_ = priv_nh_.advertiseService(SAVE_SCAN_SERVICE_NAME, 00562 &ObjectsDatabaseNode::saveScanCB, this); 00563 translate_id_srv_ = priv_nh_.advertiseService(TRANSLATE_ID_SERVICE_NAME, 00564 &ObjectsDatabaseNode::translateIdCB, this); 00565 00566 grasp_planning_server_ = new actionlib::SimpleActionServer<object_manipulation_msgs::GraspPlanningAction> 00567 (root_nh_, GRASP_PLANNING_ACTION_NAME, 00568 boost::bind(&ObjectsDatabaseNode::graspPlanningActionCB, this, _1), false); 00569 grasp_planning_server_->start(); 00570 00571 priv_nh_.param<double>("prune_gripper_opening", prune_gripper_opening_, 0.5); 00572 ROS_DEBUG("prune_gripper_opening value: %.2f", prune_gripper_opening_); 00573 priv_nh_.param<double>("prune_table_clearance", prune_table_clearance_, 0.0); 00574 ROS_DEBUG("prune_table_clearance value: %.2f", prune_table_clearance_); 00575 } 00576 00577 ~ObjectsDatabaseNode() 00578 { 00579 delete database_; 00580 delete grasp_planning_server_; 00581 } 00582 }; 00583 00584 int main(int argc, char **argv) 00585 { 00586 ros::init(argc, argv, "objects_database_node"); 00587 ObjectsDatabaseNode node; 00588 ros::spin(); 00589 return 0; 00590 }