objects_database_node.cpp
Go to the documentation of this file.
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 <manipulation_msgs/GraspPlanning.h>
00051 #include <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 manipulation_msgs;
00075 
00076 geometry_msgs::Vector3 negate(const geometry_msgs::Vector3 &vec)
00077 {
00078   geometry_msgs::Vector3 v;
00079   v.x = - vec.x;
00080   v.y = - vec.y;
00081   v.z = - vec.z;
00082   return v;
00083 }
00084 
00086 
00089 class HandDescription
00090 {
00091  private:
00093   ros::NodeHandle root_nh_;
00094 
00095   inline std::string getStringParam(std::string name)
00096   {
00097     std::string value;
00098     if (!root_nh_.getParamCached(name, value))
00099     {
00100       ROS_ERROR("Hand description: could not find parameter %s", name.c_str());
00101     }
00102     //ROS_INFO_STREAM("Hand description param " << name << " resolved to " << value);
00103     return value;
00104   }
00105 
00106   inline std::vector<std::string> getVectorParam(std::string name)
00107   {
00108     std::vector<std::string> values;
00109     XmlRpc::XmlRpcValue list;
00110     if (!root_nh_.getParamCached(name, list)) 
00111     {
00112       ROS_ERROR("Hand description: could not find parameter %s", name.c_str());
00113     }
00114     if (list.getType() != XmlRpc::XmlRpcValue::TypeArray)
00115     {
00116       ROS_ERROR("Hand description: bad parameter %s", name.c_str());
00117     }
00118     //ROS_INFO_STREAM("Hand description vector param " << name << " resolved to:");
00119     for (int32_t i=0; i<list.size(); i++)
00120     {
00121       if (list[i].getType() != XmlRpc::XmlRpcValue::TypeString)
00122       {
00123         ROS_ERROR("Hand description: bad parameter %s", name.c_str());
00124       }
00125       values.push_back( static_cast<std::string>(list[i]) );
00126       //ROS_INFO_STREAM("  " << values.back());
00127     }
00128     return values;      
00129   }
00130 
00131   inline std::vector<double> getVectorDoubleParam(std::string name)
00132   {
00133     XmlRpc::XmlRpcValue list;
00134     if (!root_nh_.getParamCached(name, list))
00135     {
00136       ROS_ERROR("Hand description: could not find parameter %s", name.c_str());
00137     }
00138     if (list.getType() != XmlRpc::XmlRpcValue::TypeArray)
00139     {
00140       ROS_ERROR("Hand description: bad parameter type %s", name.c_str());
00141     }
00142     std::vector<double> values;
00143     for (int32_t i=0; i<list.size(); i++)
00144     {
00145       if (list[i].getType() != XmlRpc::XmlRpcValue::TypeDouble)
00146       {
00147         ROS_ERROR("Hand description: bad parameter %s", name.c_str());
00148       }
00149       values.push_back( static_cast<double>(list[i]) );
00150     }
00151     return values;
00152   }
00153 
00154   inline tf::Transform getTransformParam(std::string name)
00155   {
00156     std::vector<double> vals = getVectorDoubleParam(name);
00157     if(vals.size() != 7)
00158     {
00159       ROS_ERROR("Hand description: bad parameter %s", name.c_str());
00160       return tf::Transform(tf::Quaternion(0,0,0,0), tf::Vector3(0,0,0));
00161     }
00162     return tf::Transform( tf::Quaternion(vals[3], vals[4], vals[5], vals[6]),
00163                           tf::Vector3(vals[0], vals[1], vals[2]) );
00164   }
00165   
00166  public:
00167  HandDescription() : root_nh_("~") {}
00168   
00169   inline std::string handDatabaseName(std::string arm_name)
00170   {
00171     return getStringParam("/hand_description/" + arm_name + "/hand_database_name");
00172   }
00173   
00174   inline std::vector<std::string> handJointNames(std::string arm_name)
00175   {
00176     return getVectorParam("/hand_description/" + arm_name + "/hand_joints");
00177   }
00178 
00179   inline geometry_msgs::Vector3 approachDirection(std::string arm_name)
00180   {
00181     std::string name = "/hand_description/" + arm_name + "/hand_approach_direction";
00182     std::vector<double> values = getVectorDoubleParam(name);
00183     if ( values.size() != 3 ) 
00184     {
00185       ROS_ERROR("Hand description: bad parameter %s", name.c_str());
00186     }
00187     double length = sqrt( values[0]*values[0] + values[1]*values[1] + values[2]*values[2] );
00188     if ( fabs(length) < 1.0e-5 )
00189     {
00190       ROS_ERROR("Hand description: bad parameter %s", name.c_str());
00191     }
00192     geometry_msgs::Vector3 app;
00193     app.x = values[0] / length;
00194     app.y = values[1] / length;
00195     app.z = values[2] / length;
00196     return app;
00197   }
00198 
00199   inline std::string gripperFrame(std::string arm_name)
00200   {
00201     return getStringParam("/hand_description/" + arm_name + "/hand_frame");
00202   }
00203 
00204   inline tf::Transform armToHandTransform(std::string arm_name)
00205   {
00206     return getTransformParam("/hand_description/" + arm_name + "/arm_to_hand_transform");
00207   }
00208 
00209   inline std::string armAttachmentFrame(std::string arm_name)
00210   {
00211     return getStringParam("/hand_description/" + arm_name + "/arm_attachment_frame");
00212   }
00213 };
00214 
00215 bool greaterScaledQuality(const boost::shared_ptr<DatabaseGrasp> &grasp1, 
00216                           const boost::shared_ptr<DatabaseGrasp> &grasp2)
00217 {
00218   if (grasp1->scaled_quality_.data() > grasp2->scaled_quality_.data()) return true;
00219   return false;
00220 }
00221 
00223 
00225 class ObjectsDatabaseNode
00226 {
00227 private:
00229   ros::NodeHandle priv_nh_;
00230 
00232   ros::NodeHandle root_nh_;
00233 
00235   ros::ServiceServer get_models_srv_;
00236 
00238   ros::ServiceServer get_mesh_srv_;
00239 
00241   ros::ServiceServer get_description_srv_;
00242 
00244   ros::ServiceServer grasp_planning_srv_;
00245 
00247   actionlib::SimpleActionServer<manipulation_msgs::GraspPlanningAction> *grasp_planning_server_;  
00248 
00250   ros::ServiceServer get_scans_srv_;
00251 
00253   ros::ServiceServer save_scan_srv_;
00254 
00256   ros::ServiceServer translate_id_srv_;
00257 
00259   ObjectsDatabase *database_;
00260 
00262   tf::TransformListener listener_;
00263 
00265 
00266   std::string grasp_ordering_method_;
00267 
00269 
00270   bool transform_to_arm_frame_;
00271 
00272   bool translateIdCB(TranslateRecognitionId::Request &request, TranslateRecognitionId::Response &response)
00273   {
00274     std::vector<boost::shared_ptr<DatabaseScaledModel> > models;
00275     if (!database_)
00276     {
00277       ROS_ERROR("Translate is service: database not connected");
00278       response.result = response.DATABASE_ERROR;
00279       return true;
00280     }
00281     if (!database_->getScaledModelsByRecognitionId(models, request.recognition_id))
00282     {
00283       ROS_ERROR("Translate is service: query failed");
00284       response.result = response.DATABASE_ERROR;
00285       return true;
00286     }
00287     if (models.empty())
00288     {
00289       ROS_ERROR("Translate is service: recognition id %s not found", request.recognition_id.c_str());
00290       response.result = response.ID_NOT_FOUND;
00291       return true;
00292     }
00293     response.household_objects_id = models[0]->id_.data();
00294     if (models.size() > 1) ROS_WARN("Multiple matches found for recognition id %s. Returning the first one.",
00295                                     request.recognition_id.c_str());
00296     response.result = response.SUCCESS;
00297     return true;
00298   }
00299 
00301   bool getModelsCB(GetModelList::Request &request, GetModelList::Response &response)
00302   {
00303     if (!database_)
00304     {
00305       response.return_code.code = response.return_code.DATABASE_NOT_CONNECTED;
00306       return true;
00307     }
00308     std::vector< boost::shared_ptr<DatabaseScaledModel> > models;
00309     if (!database_->getScaledModelsBySet(models, request.model_set))
00310     {
00311       response.return_code.code = response.return_code.DATABASE_QUERY_ERROR;
00312       return true;
00313     }
00314     for (size_t i=0; i<models.size(); i++)
00315     {
00316       response.model_ids.push_back( models[i]->id_.data() );
00317     }
00318     response.return_code.code = response.return_code.SUCCESS;
00319     return true;
00320   }
00321 
00323   bool getMeshCB(GetModelMesh::Request &request, GetModelMesh::Response &response)
00324   {
00325     if (!database_)
00326     {
00327       response.return_code.code = response.return_code.DATABASE_NOT_CONNECTED;
00328       return true;
00329     }
00330     if ( !database_->getScaledModelMesh(request.model_id, response.mesh) )
00331     {
00332       response.return_code.code = response.return_code.DATABASE_QUERY_ERROR;
00333       return true;
00334     }
00335     response.return_code.code = response.return_code.SUCCESS;
00336     return true;
00337   }
00338 
00340   bool getDescriptionCB(GetModelDescription::Request &request, GetModelDescription::Response &response)
00341   {
00342     if (!database_)
00343     {
00344       response.return_code.code = response.return_code.DATABASE_NOT_CONNECTED;
00345       return true;
00346     }
00347     std::vector< boost::shared_ptr<DatabaseScaledModel> > models;
00348     
00349     std::stringstream id;
00350     id << request.model_id;
00351     std::string where_clause("scaled_model_id=" + id.str());
00352     if (!database_->getList(models, where_clause) || models.size() != 1)
00353     {
00354       response.return_code.code = response.return_code.DATABASE_QUERY_ERROR;
00355       return true;
00356     }
00357     response.tags = models[0]->tags_.data();
00358     response.name = models[0]->model_.data();
00359     response.maker = models[0]->maker_.data();
00360     response.return_code.code = response.return_code.SUCCESS;
00361     return true;
00362   }
00363 
00364   bool getScansCB(GetModelScans::Request &request, GetModelScans::Response &response)
00365   {
00366     if (!database_)
00367     {
00368       ROS_ERROR("GetModelScan: database not connected");
00369       response.return_code.code = DatabaseReturnCode::DATABASE_NOT_CONNECTED;
00370       return true;
00371     }
00372 
00373     database_->getModelScans(request.model_id, request.scan_source,response.matching_scans);
00374     response.return_code.code = DatabaseReturnCode::SUCCESS;
00375     return true;
00376   }
00377 
00378   bool saveScanCB(SaveScan::Request &request, SaveScan::Response &response)
00379   {
00380     if (!database_)
00381     {
00382       ROS_ERROR("SaveScan: database not connected");
00383       response.return_code.code = DatabaseReturnCode::DATABASE_NOT_CONNECTED;
00384       return true;
00385     }
00386     household_objects_database::DatabaseScan scan;
00387     scan.frame_id_.get() = request.ground_truth_pose.header.frame_id;
00388     scan.cloud_topic_.get() = request.cloud_topic;
00389     scan.object_pose_.get().pose_ = request.ground_truth_pose.pose;
00390     scan.scaled_model_id_.get() = request.scaled_model_id;
00391     scan.scan_bagfile_location_.get() = request.bagfile_location;
00392     scan.scan_source_.get() = request.scan_source;
00393     database_->insertIntoDatabase(&scan);
00394     response.return_code.code = DatabaseReturnCode::SUCCESS;
00395     return true;
00396   }
00397 
00398   geometry_msgs::Pose multiplyPoses(const geometry_msgs::Pose &p1, 
00399                                     const geometry_msgs::Pose &p2)
00400   {
00401     tf::Transform t1;
00402     tf::poseMsgToTF(p1, t1);
00403     tf::Transform t2;
00404     tf::poseMsgToTF(p2, t2);
00405     t2 = t1 * t2;        
00406     geometry_msgs::Pose out_pose;
00407     tf::poseTFToMsg(t2, out_pose);
00408     return out_pose;
00409   }
00410 
00411   //retrieves all grasps from the database for a given target
00412   bool getGrasps(const GraspableObject &target, const std::string &arm_name, 
00413                  std::vector<Grasp> &grasps, GraspPlanningErrorCode &error_code)
00414   {
00415     if (!database_)
00416     {
00417       ROS_ERROR("Database grasp planning: database not connected");
00418       error_code.value = error_code.OTHER_ERROR;
00419       return false;
00420     }
00421 
00422     if (target.potential_models.empty())
00423     {
00424       ROS_ERROR("Database grasp planning: no potential model information in grasp planning target");
00425       error_code.value = error_code.OTHER_ERROR;
00426       return false;      
00427     }
00428 
00429     if (target.potential_models.size() > 1)
00430     {
00431       ROS_WARN("Database grasp planning: target has more than one potential models. "
00432                "Returning grasps for first model only");
00433     }
00434 
00435     // get the object id. If the call has specified a new, ORK-style object type, convert that to a
00436     // household_database model_id.
00437     int model_id = target.potential_models[0].model_id;
00438     ROS_DEBUG_STREAM_NAMED("manipulation","Database grasp planner: getting grasps for model " << model_id);
00439     ROS_DEBUG_STREAM_NAMED("manipulation","Model is in frame " << target.potential_models[0].pose.header.frame_id << 
00440                            " and reference frame is " << target.reference_frame_id);
00441     if (!target.potential_models[0].type.key.empty())
00442     {
00443       if (model_id == 0)
00444       {
00445         TranslateRecognitionId translate;
00446         translate.request.recognition_id = target.potential_models[0].type.key;
00447         translateIdCB(translate.request, translate.response);
00448         if (translate.response.result == translate.response.SUCCESS)
00449         {
00450           model_id = translate.response.household_objects_id;
00451           ROS_DEBUG_STREAM_NAMED("manipulation", "Grasp planning: translated ORK key " << 
00452                                  target.potential_models[0].type.key << " into model_id " << model_id);
00453         }
00454         else
00455         {
00456           ROS_ERROR("Failed to translate ORK key into household model_id");
00457           error_code.value = error_code.OTHER_ERROR;
00458           return false;      
00459         }
00460       }
00461       else
00462       {
00463         ROS_WARN("Grasp planning: both model_id and ORK key specified in GraspableObject; "
00464                  "using model_id and ignoring ORK key");
00465       }
00466     }
00467     HandDescription hd;
00468     std::string hand_id = hd.handDatabaseName(arm_name);
00469     
00470     //retrieve the raw grasps from the database
00471     std::vector< boost::shared_ptr<DatabaseGrasp> > db_grasps;
00472     if (!database_->getClusterRepGrasps(model_id, hand_id, db_grasps))
00473     {
00474       ROS_ERROR("Database grasp planning: database query error");
00475       error_code.value = error_code.OTHER_ERROR;
00476       return false;
00477     }
00478     ROS_INFO("Database object node: retrieved %u grasps from database", (unsigned int)db_grasps.size());
00479 
00480     //order grasps based on request
00481     if (grasp_ordering_method_ == "random") 
00482     {
00483       ROS_DEBUG_NAMED("manipulation", "Randomizing grasps");
00484       std::random_shuffle(db_grasps.begin(), db_grasps.end());
00485     }
00486     else if (grasp_ordering_method_ == "quality")
00487     {
00488       ROS_DEBUG_NAMED("manipulation", "Sorting grasps by scaled quality");
00489       std::sort(db_grasps.begin(), db_grasps.end(), greaterScaledQuality);
00490     }
00491     else
00492     {
00493       ROS_WARN("Unknown grasp ordering method requested -- randomizing grasp order");
00494       std::random_shuffle(db_grasps.begin(), db_grasps.end());
00495     }
00496 
00497     //convert to the Grasp data type
00498     std::vector< boost::shared_ptr<DatabaseGrasp> >::iterator it;
00499     for (it = db_grasps.begin(); it != db_grasps.end(); it++)
00500     {
00501       ROS_ASSERT( (*it)->final_grasp_posture_.get().joint_angles_.size() == 
00502                   (*it)->pre_grasp_posture_.get().joint_angles_.size() );
00503       Grasp grasp;
00504       std::vector<std::string> joint_names = hd.handJointNames(arm_name);
00505 
00506       if (hand_id != "WILLOW_GRIPPER_2010")
00507       {
00508         //check that the number of joints in the ROS description of this hand
00509         //matches the number of values we have in the database
00510         if (joint_names.size() != (*it)->final_grasp_posture_.get().joint_angles_.size())
00511         {
00512           ROS_ERROR("Database grasp specification does not match ROS description of hand. "
00513                     "Hand is expected to have %d joints, but database grasp specifies %d values", 
00514                     (int)joint_names.size(), (int)(*it)->final_grasp_posture_.get().joint_angles_.size());
00515           continue;
00516         }
00517         //for now we silently assume that the order of the joints in the ROS description of
00518         //the hand is the same as in the database description
00519         grasp.pre_grasp_posture.name = joint_names;
00520         grasp.grasp_posture.name = joint_names;
00521         grasp.pre_grasp_posture.position = (*it)->pre_grasp_posture_.get().joint_angles_;
00522         grasp.grasp_posture.position = (*it)->final_grasp_posture_.get().joint_angles_; 
00523       }
00524       else
00525       {
00526         //unfortunately we have to hack this, as the grasp is really defined by a single
00527         //DOF, but the urdf for the PR2 gripper is not well set up to do that
00528         if ( joint_names.size() != 4 || (*it)->final_grasp_posture_.get().joint_angles_.size() != 1)
00529         {
00530           ROS_ERROR("PR2 gripper specs and database grasp specs do not match expected values");
00531           continue;
00532         }
00533         grasp.pre_grasp_posture.name = joint_names;
00534         grasp.grasp_posture.name = joint_names;
00535         //replicate the single value from the database 4 times
00536         grasp.pre_grasp_posture.position.resize( joint_names.size(), 
00537                                                  (*it)->pre_grasp_posture_.get().joint_angles_.at(0));
00538         grasp.grasp_posture.position.resize( joint_names.size(), 
00539                                              (*it)->final_grasp_posture_.get().joint_angles_.at(0));
00540       }
00541       //for now the effort is not in the database so we hard-code it in here
00542       //this will change at some point
00543       grasp.grasp_posture.effort.resize(joint_names.size(), 50);
00544       grasp.pre_grasp_posture.effort.resize(joint_names.size(), 100);
00545       //approach and retreat directions are based on pre-defined hand characteristics
00546       //note that this silently implies that the same convention was used by whatever planner (or human) stored
00547       //this grasps in the database to begin with
00548       grasp.approach.direction.header.stamp = ros::Time::now();
00549       grasp.approach.direction.header.frame_id = hd.gripperFrame(arm_name);
00550       grasp.approach.direction.vector = hd.approachDirection(arm_name);
00551       grasp.retreat.direction.header.stamp = ros::Time::now();
00552       grasp.retreat.direction.header.frame_id = hd.gripperFrame(arm_name);
00553       grasp.retreat.direction.vector = negate( hd.approachDirection(arm_name) );      
00554       //min and desired approach distances are the same for all grasps
00555       grasp.approach.desired_distance = 0.10;
00556       grasp.approach.min_distance = 0.05;
00557       grasp.retreat.desired_distance = 0.10;
00558       grasp.retreat.min_distance = 0.05;
00559       //the pose of the grasp
00560       geometry_msgs::Pose grasp_pose = (*it)->final_grasp_pose_.get().pose_;
00561       //convert it to the frame of the detection
00562       grasp_pose = multiplyPoses(target.potential_models[0].pose.pose, grasp_pose);
00563       //and then finally to the reference frame of the object
00564       if (target.potential_models[0].pose.header.frame_id != target.reference_frame_id)
00565       {
00566         tf::StampedTransform ref_trans;
00567         try
00568         {
00569           listener_.lookupTransform(target.reference_frame_id,
00570                                     target.potential_models[0].pose.header.frame_id,                    
00571                                     ros::Time(0), ref_trans);
00572         }
00573         catch (tf::TransformException ex)
00574         {
00575           ROS_ERROR("Grasp planner: failed to get transform from %s to %s; exception: %s", 
00576                     target.reference_frame_id.c_str(), 
00577                     target.potential_models[0].pose.header.frame_id.c_str(), ex.what());
00578           error_code.value = error_code.OTHER_ERROR;
00579           return false;      
00580         }        
00581         geometry_msgs::Pose ref_pose;
00582         tf::poseTFToMsg(ref_trans, ref_pose);
00583         grasp_pose = multiplyPoses(ref_pose, grasp_pose);
00584       }
00585       //convert to frame of attachment link on arm, if requested
00586       if (transform_to_arm_frame_)
00587       {
00588         std::string arm_frame = hd.armAttachmentFrame(arm_name);
00589         tf::Transform arm_to_hand = hd.armToHandTransform(arm_name);
00590         tf::Transform hand_to_arm = arm_to_hand.inverse();
00591         geometry_msgs::Pose hand_to_arm_pose;
00592         poseTFToMsg(hand_to_arm, hand_to_arm_pose);
00593         grasp_pose = multiplyPoses(grasp_pose, hand_to_arm_pose);
00594       }
00595       //set the grasp pose
00596       grasp.grasp_pose.pose = grasp_pose;
00597       grasp.grasp_pose.header.frame_id = target.reference_frame_id;
00598       grasp.grasp_pose.header.stamp = ros::Time::now();
00599       //store the scaled quality
00600       grasp.grasp_quality = (*it)->scaled_quality_.get();
00601 
00602       //insert the new grasp in the list
00603       grasps.push_back(grasp);
00604     }
00605 
00606     ROS_INFO("Database grasp planner: returning %u grasps", (unsigned int)grasps.size());
00607     error_code.value = error_code.SUCCESS;
00608     return true;
00609   }
00610 
00612   bool graspPlanningCB(GraspPlanning::Request &request, GraspPlanning::Response &response)
00613   {
00614     getGrasps(request.target, request.arm_name, response.grasps, response.error_code);
00615     return true;
00616   }
00617 
00618   void graspPlanningActionCB(const manipulation_msgs::GraspPlanningGoalConstPtr &goal)
00619   {
00620     std::vector<Grasp> grasps;
00621     GraspPlanningErrorCode error_code;
00622     GraspPlanningResult result;
00623     GraspPlanningFeedback feedback;
00624     bool success = getGrasps(goal->target, goal->arm_name, grasps, error_code);
00625     /*
00626     for (size_t i=0; i<grasps.size(); i++)
00627     {
00628       if (grasp_planning_server_->isPreemptRequested()) 
00629       {
00630         grasp_planning_server_->setAborted(result);
00631         return;
00632       }
00633       feedback.grasps.push_back(grasps[i]);
00634       if ( (i+1)%10==0)
00635       {
00636         grasp_planning_server_->publishFeedback(feedback);
00637         ros::Duration(10.0).sleep();
00638       }
00639     }
00640     */
00641     result.grasps = grasps;
00642     result.error_code = error_code;
00643     if (!success) 
00644     {
00645       grasp_planning_server_->setAborted(result);
00646       return;
00647     }
00648     grasp_planning_server_->setSucceeded(result);
00649   }
00650 
00651 public:
00652   ObjectsDatabaseNode() : priv_nh_("~"), root_nh_("")
00653   {
00654     //initialize database connection
00655     std::string database_host, database_port, database_user, database_pass, database_name;
00656     root_nh_.param<std::string>("/household_objects_database/database_host", database_host, "");
00657     int port_int;
00658     root_nh_.param<int>("/household_objects_database/database_port", port_int, -1);
00659     std::stringstream ss; ss << port_int; database_port = ss.str();
00660     root_nh_.param<std::string>("/household_objects_database/database_user", database_user, "");
00661     root_nh_.param<std::string>("/household_objects_database/database_pass", database_pass, "");
00662     root_nh_.param<std::string>("/household_objects_database/database_name", database_name, "");
00663     database_ = new ObjectsDatabase(database_host, database_port, database_user, database_pass, database_name);
00664     if (!database_->isConnected())
00665     {
00666       ROS_ERROR("ObjectsDatabaseNode: failed to open model database on host "
00667                 "%s, port %s, user %s with password %s, database %s. Unable to do grasp "
00668                 "planning on database recognized objects. Exiting.",
00669                 database_host.c_str(), database_port.c_str(), 
00670                 database_user.c_str(), database_pass.c_str(), database_name.c_str());
00671       delete database_; database_ = NULL;
00672     }
00673 
00674     //advertise services
00675     get_models_srv_ = priv_nh_.advertiseService(GET_MODELS_SERVICE_NAME, &ObjectsDatabaseNode::getModelsCB, this);    
00676     get_mesh_srv_ = priv_nh_.advertiseService(GET_MESH_SERVICE_NAME, &ObjectsDatabaseNode::getMeshCB, this);    
00677     get_description_srv_ = priv_nh_.advertiseService(GET_DESCRIPTION_SERVICE_NAME, 
00678                                                      &ObjectsDatabaseNode::getDescriptionCB, this);    
00679     grasp_planning_srv_ = priv_nh_.advertiseService(GRASP_PLANNING_SERVICE_NAME, 
00680                                                     &ObjectsDatabaseNode::graspPlanningCB, this);
00681 
00682     get_scans_srv_ = priv_nh_.advertiseService(GET_SCANS_SERVICE_NAME,
00683                                                &ObjectsDatabaseNode::getScansCB, this);
00684     save_scan_srv_ = priv_nh_.advertiseService(SAVE_SCAN_SERVICE_NAME,
00685                                                &ObjectsDatabaseNode::saveScanCB, this);
00686     translate_id_srv_ = priv_nh_.advertiseService(TRANSLATE_ID_SERVICE_NAME, 
00687                                                   &ObjectsDatabaseNode::translateIdCB, this);
00688 
00689     priv_nh_.param<std::string>("grasp_ordering_method", grasp_ordering_method_, "random");
00690     priv_nh_.param<bool>("transform_to_arm_frame", transform_to_arm_frame_, false);
00691 
00692     grasp_planning_server_ = new actionlib::SimpleActionServer<manipulation_msgs::GraspPlanningAction>
00693       (root_nh_, GRASP_PLANNING_ACTION_NAME, 
00694        boost::bind(&ObjectsDatabaseNode::graspPlanningActionCB, this, _1), false);
00695     grasp_planning_server_->start();
00696     ROS_DEBUG_STREAM_NAMED("manipulation","Database grasp planner ready");
00697   }
00698 
00699   ~ObjectsDatabaseNode()
00700   {
00701     delete database_;
00702     delete grasp_planning_server_;
00703   }
00704 };
00705 
00706 int main(int argc, char **argv)
00707 {
00708   ros::init(argc, argv, "objects_database_node");
00709   ObjectsDatabaseNode node;
00710   ros::spin();
00711   return 0;  
00712 }


household_objects_database
Author(s): Matei Ciocarlie, except for source files individually marked otherwise
autogenerated on Thu Aug 27 2015 13:24:24