00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <household_objects_database/objects_database.h>
00038 using household_objects_database::ObjectsDatabasePtr;
00039 #include <household_objects_database/database_grasp.h>
00040 using household_objects_database::DatabaseGraspPtr;
00041 #include <household_objects_database/database_perturbation.h>
00042 using household_objects_database::DatabasePerturbationPtr;
00043
00044 #include <object_manipulator/tools/hand_description.h>
00045 #include <object_manipulation_msgs/GraspPlanning.h>
00046 #include <object_manipulation_msgs/GraspPlanningErrorCode.h>
00047 #include <tf/transform_broadcaster.h>
00048
00049
00050
00051
00052 #include "probabilistic_grasp_planner/grasp_retriever.h"
00053
00054
00055
00056
00057 namespace probabilistic_grasp_planner {
00058
00060
00063 void DatabaseGraspRetriever::pruneGraspList(std::vector<DatabaseGraspPtr> &grasps,
00064 double gripper_threshold,
00065 double table_clearance_threshold)
00066 {
00067 std::vector<DatabaseGraspPtr>::iterator prune_it = grasps.begin();
00068 int pruned = 0;
00069 while ( prune_it != grasps.end() )
00070 {
00071
00072 if ((*prune_it)->final_grasp_posture_.get().joint_angles_[0] > gripper_threshold ||
00073 (table_clearance_threshold >= 0.0 && (*prune_it)->table_clearance_.get() < table_clearance_threshold*1.0e3) )
00074 {
00075 prune_it = grasps.erase(prune_it);
00076 pruned++;
00077 }
00078 else
00079 {
00080 prune_it++;
00081 }
00082 }
00083 ROS_DEBUG("Database grasp planner: pruned %d grasps for table collision or gripper angle above threshold", pruned);
00084 }
00085
00086 void DatabaseGraspRetriever::appendMetadataToGrasps(const std::vector<DatabaseGraspPtr> &db_grasps,
00087 std::vector<GraspWithMetadata> &grasps)
00088 {
00089 grasps.reserve(grasps.size()+db_grasps.size());
00090
00091 BOOST_FOREACH(DatabaseGraspPtr db_grasp, db_grasps) {
00092 GraspWithMetadata grasp;
00093
00094 ROS_ASSERT( db_grasp->final_grasp_posture_.get().joint_angles_.size() ==
00095 db_grasp->pre_grasp_posture_.get().joint_angles_.size() );
00096 ROS_ASSERT(db_grasp->scaled_model_id_.get() == model_.model_id);
00097
00098 std::vector<std::string> joint_names = object_manipulator::handDescription().handJointNames(arm_name_);
00099 if (object_manipulator::handDescription().handDatabaseName(arm_name_) != "WILLOW_GRIPPER_2010")
00100 {
00101
00102
00103 if (joint_names.size() != db_grasp->final_grasp_posture_.get().joint_angles_.size())
00104 {
00105 ROS_ERROR("Database grasp specification does not match ROS description of hand. "
00106 "Hand is expected to have %zd joints, but database grasp specifies %zd values",
00107 joint_names.size(), db_grasp->final_grasp_posture_.get().joint_angles_.size());
00108 continue;
00109 }
00110
00111
00112 grasp.grasp_.pre_grasp_posture.name = joint_names;
00113 grasp.grasp_.grasp_posture.name = joint_names;
00114 grasp.grasp_.pre_grasp_posture.position = db_grasp->pre_grasp_posture_.get().joint_angles_;
00115 grasp.grasp_.grasp_posture.position = db_grasp->final_grasp_posture_.get().joint_angles_;
00116 }
00117 else
00118 {
00119
00120
00121 if ( joint_names.size() != 4 || db_grasp->final_grasp_posture_.get().joint_angles_.size() != 1)
00122 {
00123 ROS_ERROR("PR2 gripper specs and database grasp specs do not match expected values");
00124 continue;
00125 }
00126 grasp.grasp_.pre_grasp_posture.name = joint_names;
00127 grasp.grasp_.grasp_posture.name = joint_names;
00128
00129 grasp.grasp_.pre_grasp_posture.position.resize( joint_names.size(),
00130 db_grasp->pre_grasp_posture_.get().joint_angles_.at(0));
00131 grasp.grasp_.grasp_posture.position.resize( joint_names.size(),
00132 db_grasp->final_grasp_posture_.get().joint_angles_.at(0));
00133 }
00134
00135
00136
00137 grasp.grasp_.grasp_posture.effort.resize(joint_names.size(), 10000);
00138
00139 grasp.grasp_.success_probability = 0.0;
00140
00141
00142
00143
00144 grasp.energy_function_score_ = db_grasp->quality_.get();
00145 grasp.model_id_ = db_grasp->scaled_model_id_.get();
00146 grasp.grasp_id_ = db_grasp->id_.get();
00147
00148 tf::Stamped<tf::Pose> base_to_object;
00149
00150 tf::poseStampedMsgToTF(model_.pose,base_to_object);
00151
00152 tf::Pose object_to_grasp;
00153 tf::poseMsgToTF(db_grasp->final_grasp_pose_.get().pose_, object_to_grasp);
00154
00155
00156
00157 grasp.object_pose_ = base_to_object;
00158
00159
00160
00161 tf::Pose base_to_grasp(base_to_object * object_to_grasp);
00162
00163 tf::poseTFToMsg(base_to_grasp,grasp.grasp_.grasp_pose);
00164
00165
00166 double wrist_to_tool_point_offset_ = 0.13;
00167
00168 tf::Pose offset_tf(btMatrix3x3::getIdentity(),btVector3(wrist_to_tool_point_offset_,0,0));
00169
00171 grasp.tool_point_pose_ = tf::Stamped<tf::Pose>(base_to_grasp * offset_tf,
00172 grasp.object_pose_.stamp_, grasp.object_pose_.frame_id_);
00173
00174
00175 grasps.push_back(grasp);
00176 }
00177
00178 }
00179 DatabaseGraspRetriever::DatabaseGraspRetriever(ObjectsDatabasePtr database,
00180 const household_objects_database_msgs::DatabaseModelPose &model,
00181 const std::string &arm_name,
00182 bool prune_compliant_copies,
00183 bool use_cluster_rep_grasps) :
00184 GraspRetriever(arm_name),
00185 database_(database), model_(model), prune_compliant_copies_(prune_compliant_copies), use_cluster_rep_grasps_(use_cluster_rep_grasps)
00186 {
00187
00188 }
00189
00190 void DatabaseGraspRetriever::fetchFromDB()
00191 {
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203 std::vector<DatabaseGraspPtr> db_grasps;
00204 int model_id=model_.model_id;
00205
00206 if (use_cluster_rep_grasps_)
00207 {
00208 if (!database_->getClusterRepGrasps(model_id, object_manipulator::handDescription().handDatabaseName(arm_name_), db_grasps))
00209 {
00210 ROS_ERROR("Robust Database Grasp Planning Node: grasp retrieval error");
00211 }
00212 }
00213 else
00214 {
00215 if (!database_->getGrasps(model_id, object_manipulator::handDescription().handDatabaseName(arm_name_), db_grasps))
00216 {
00217 ROS_ERROR("Robust Database Grasp Planning Node: grasp retrieval error");
00218 }
00219 }
00220
00221 ROS_DEBUG("Robust Database Grasp Planning Node: retrieved %zd grasps from database", db_grasps.size());
00222
00223
00224 if (prune_compliant_copies_)
00225 {
00226 std::vector<DatabaseGraspPtr>::iterator it = db_grasps.begin();
00227 while (it!=db_grasps.end())
00228 {
00229 if ((*it)->compliant_copy_.get()) it = db_grasps.erase(it);
00230 else it++;
00231 }
00232 }
00233
00234 appendMetadataToGrasps(db_grasps, grasps_);
00235 }
00236
00237 void DatabaseGraspRetriever::getGrasps(std::vector<GraspWithMetadata> &grasps)
00238 {
00239 grasps.insert(grasps.end(), grasps_.begin(), grasps_.end());
00240 }
00241
00242 ClusterRepGraspRetriever::ClusterRepGraspRetriever(ObjectsDatabasePtr database,
00243 const household_objects_database_msgs::DatabaseModelPose &model,
00244 const std::string &arm_name) :
00245 DatabaseGraspRetriever(database, model, arm_name, true, false)
00246 {
00247
00248
00249 }
00250
00251 void ClusterRepGraspRetriever::fetchFromDB()
00252 {
00253
00254
00255
00256
00257
00258
00259
00260
00261
00262
00263
00264
00265 std::vector<DatabaseGraspPtr> db_grasps;
00266 int model_id=model_.model_id;
00267
00268 if (!database_->getClusterRepGrasps(model_id,
00269 object_manipulator::handDescription().handDatabaseName(arm_name_), db_grasps))
00270 {
00271 ROS_ERROR("Robust Database Grasp Planning Node: grasp retrieval error");
00272 }
00273
00274 ROS_WARN("Size from DB: %zd",db_grasps.size());
00275
00276 ROS_DEBUG("Robust Database Grasp Planning Node: retrieved %zd grasps from database", db_grasps.size());
00277
00278
00279 ROS_WARN("Size after pruning: %zd",db_grasps.size());
00280 ROS_WARN("Size before appending: %zd",grasps_.size());
00281 appendMetadataToGrasps(db_grasps, grasps_);
00282
00283 ROS_WARN("Size after appending: %zd",grasps_.size());
00284 }
00285
00286 void ClusterRepGraspRetriever::getGrasps(std::vector<GraspWithMetadata> &grasps)
00287 {
00288 grasps.insert(grasps.end(), grasps_.begin(), grasps_.end());
00289 }
00290
00294 void DebugClusterRepGraspRetriever::getGrasps(std::vector<GraspWithMetadata> &grasps)
00295 {
00296 std::vector<GraspWithMetadata>::iterator begin_plus_five(grasps_.begin());
00297 std::advance(begin_plus_five, 5);
00298 grasps.insert(grasps.end(), grasps_.begin(), begin_plus_five);
00299 }
00300
00301 PerturbationGraspRetriever::PerturbationGraspRetriever(ObjectsDatabasePtr database,
00302 const household_objects_database_msgs::DatabaseModelPose &model,
00303 const std::string &arm_name) :
00304 DatabaseGraspRetriever(database, model, arm_name, false, true), gstar_(NULL)
00305 {
00306 ROS_DEBUG("Created new perturbation grasp retriever for model_id %d",model.model_id);
00307 fetchFromDB();
00308 }
00309
00310 void PerturbationGraspRetriever::fetchFromDB()
00311 {
00312 std::vector<DatabasePerturbationPtr> perturbations;
00313 database_->getAllPerturbationsForModel(model_.model_id, perturbations);
00314
00315 ROS_DEBUG("Retrieved %zd perturbations of grasps for model %d from the DB", perturbations.size(), model_.model_id);
00316
00317 perturbations_.insert(perturbations_.begin(), perturbations.begin(), perturbations.end());
00318 }
00319
00320 void PerturbationGraspRetriever::getGrasps(std::vector<GraspWithMetadata> &grasps)
00321 {
00322 if (gstar_ == NULL)
00323 {
00324 ROS_ERROR("Requested perturbations for a grasp, but grasp is not set.");
00325 return;
00326 }
00327
00329 grasps.reserve(grasps.size()+250);
00330 BOOST_FOREACH(DatabasePerturbationPtr &perturbation, perturbations_)
00331 {
00332 int grasp_id = perturbation->grasp_id_.get();
00333 if (grasp_id == gstar_->grasp_id_)
00334 {
00336 GraspWithMetadata grasp_with_metadata;
00337 grasp_with_metadata.model_id_ = model_.model_id;
00338 grasp_with_metadata.grasp_id_ = grasp_id;
00339 grasp_with_metadata.energy_function_score_ = perturbation->score_.get();
00340 grasp_with_metadata.object_pose_ = gstar_->object_pose_;
00341
00342 object_manipulation_msgs::Grasp grasp;
00343
00344
00346
00347 std::vector<double> deltas = perturbation->deltas_.get();
00348
00349 grasps.push_back(grasp_with_metadata);
00350 }
00351 }
00352 }
00353
00354 ClusterPlannerGraspRetriever::ClusterPlannerGraspRetriever(ros::NodeHandle &nh, const std::string &cluster_planner_name,
00355 const object_manipulation_msgs::GraspableObject &graspable_object,
00356 const std::string &arm_name) :
00357 GraspRetriever(arm_name)
00358 {
00359
00360 cluster_planner_srv_ = register_service<object_manipulation_msgs::GraspPlanning>(nh, cluster_planner_name);
00361 cloud_ = graspable_object.cluster;
00362 fetchFromPlanner(graspable_object);
00363 }
00364
00365 void ClusterPlannerGraspRetriever::fetchFromPlanner(const object_manipulation_msgs::GraspableObject &graspable_object)
00366 {
00367 object_manipulation_msgs::GraspPlanning planner_call;
00370 planner_call.request.target = graspable_object;
00371 planner_call.request.arm_name = arm_name_;
00372 cluster_planner_srv_.call(planner_call);
00373 if (planner_call.response.error_code.value != object_manipulation_msgs::GraspPlanningErrorCode::SUCCESS)
00374 {
00375 ROS_ERROR("Call to cluster planner failed!");
00376 }
00377 grasps_from_cluster_planner_ = planner_call.response.grasps;
00378 ROS_INFO("Got %zd grasps from the cluster planner",grasps_from_cluster_planner_.size());
00379 }
00380
00381 void ClusterPlannerGraspRetriever::getGrasps(std::vector<GraspWithMetadata> &grasps)
00382 {
00383
00385 appendGraspsFromClusterPlanner(grasps);
00386 }
00387
00388 void ClusterPlannerGraspRetriever::appendGraspsFromClusterPlanner(std::vector<GraspWithMetadata> &grasps)
00389 {
00390 grasps.reserve(grasps.size()+grasps_from_cluster_planner_.size());
00391
00392
00393 BOOST_FOREACH(object_manipulation_msgs::Grasp &grasp, grasps_from_cluster_planner_)
00394 {
00395 GraspWithMetadata grasp_with_metadata;
00396 grasp_with_metadata.grasp_ = grasp;
00397
00398 grasp_with_metadata.model_id_ = -1;
00399 grasp_with_metadata.grasp_id_ = -1;
00400
00401 grasp_with_metadata.object_pose_.setIdentity();
00402 grasp_with_metadata.object_pose_.frame_id_ = cloud_.header.frame_id;
00403 grasp_with_metadata.object_pose_.stamp_ = cloud_.header.stamp;
00404
00405 tf::Pose grasp_in_base_frame;
00406 tf::poseMsgToTF(grasp.grasp_pose, grasp_in_base_frame);
00407
00408
00409
00410 tf::poseTFToMsg(grasp_in_base_frame,grasp_with_metadata.grasp_.grasp_pose);
00411
00412 double wrist_to_tool_point_offset_ = 0.13;
00413
00414 tf::Pose grasp_to_tool_point(btMatrix3x3::getIdentity(),btVector3(wrist_to_tool_point_offset_,0,0));
00415
00417 grasp_with_metadata.tool_point_pose_ = tf::Stamped<tf::Pose>(
00418 grasp_in_base_frame * grasp_to_tool_point, cloud_.header.stamp,
00419 cloud_.header.frame_id);
00420
00421
00422 grasps.push_back(grasp_with_metadata);
00423 }
00424 }
00425
00426
00427 }