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 #include <boost/shared_ptr.hpp>
00036 #include <boost/foreach.hpp>
00037
00038 #include "bayesian_grasp_planner/bayesian_grasp_planner.h"
00039 #include "bayesian_grasp_planner/object_detector.h"
00040 #include "bayesian_grasp_planner/grasp_evaluator.h"
00041 #include "bayesian_grasp_planner/grasp_generator.h"
00042 #include "bayesian_grasp_planner/bayesian_grasp_planner_tools.h"
00043
00044 namespace bayesian_grasp_planner {
00045
00046 void BayesianGraspPlanner::bayesianInference(std::vector<GraspWM> &grasps,
00047 const std::vector<object_manipulation_msgs::GraspableObject> &objects,
00048 const std::vector< boost::shared_ptr<ObjectDetector> > &object_detectors,
00049 const std::vector< boost::shared_ptr<GraspEvaluatorProb> > &prob_evaluators)
00050 {
00051
00052
00053 ROS_INFO("computing grasp conditional probabilities");
00054 BOOST_FOREACH(const boost::shared_ptr<GraspEvaluatorProb> &prob_eval, prob_evaluators)
00055 {
00056 std::vector<double> grasp_success_probs;
00057 std::vector<double> grasp_failure_probs;
00058
00059
00060 BOOST_FOREACH(GraspWM &grasp, grasps)
00061 {
00062 grasp.success_cond_probs.resize(objects.size());
00063 grasp.failure_cond_probs.resize(objects.size());
00064 }
00065
00066
00067 if(prob_eval->is_object_dependent())
00068 {
00069 for(size_t object_ind = 0; object_ind < objects.size(); object_ind++)
00070 {
00071
00072 if(objects[object_ind].potential_models.empty()) continue;
00073
00074
00075 prob_eval->getProbabilitiesForGraspList(grasps, objects[object_ind], grasp_success_probs, grasp_failure_probs);
00076
00077
00078
00079
00080
00081
00082
00083
00084 for (size_t grasp_ind = 0; grasp_ind < grasps.size(); grasp_ind++)
00085 {
00086 grasps[grasp_ind].success_cond_probs[object_ind].push_back(grasp_success_probs[grasp_ind]);
00087 grasps[grasp_ind].failure_cond_probs[object_ind].push_back(grasp_failure_probs[grasp_ind]);
00088 }
00089 }
00090 }
00091
00092
00093 else
00094 {
00095
00096 prob_eval->getProbabilitiesForGraspList(grasps, objects[objects.size()-1], grasp_success_probs, grasp_failure_probs);
00097
00098
00099
00100
00101
00102
00103
00104
00105 for (size_t grasp_ind = 0; grasp_ind < grasps.size(); grasp_ind++)
00106 {
00107 for (size_t object_ind = 0; object_ind < objects.size(); object_ind++)
00108 {
00109 grasps[grasp_ind].success_cond_probs[object_ind].push_back(grasp_success_probs[grasp_ind]);
00110 grasps[grasp_ind].failure_cond_probs[object_ind].push_back(grasp_failure_probs[grasp_ind]);
00111 }
00112 }
00113 }
00114 }
00115
00116 {
00117 for (size_t object_ind = 0; object_ind < objects.size(); object_ind++)
00118 {
00119
00120 double object_prior;
00121 if (objects[object_ind].potential_models.size() > 0)
00122 {
00123 object_prior = 0.5 / (objects.size()-1);
00124 printf("Database object %d:\n", objects[object_ind].potential_models[0].model_id);
00125 }
00126 else
00127 {
00128 printf("Non-database object:\n");
00129 object_prior = 0.5;
00130 }
00131
00132
00133 double detection_prob = 1.0;
00134 BOOST_FOREACH(const boost::shared_ptr<ObjectDetector> &detector, object_detectors)
00135 {
00136 double obj_det_prob = detector->getProbabilityForDetection(objects[object_ind]);
00137
00138 detection_prob *= obj_det_prob;
00139 }
00140 printf(" total detection probability: %f\n", detection_prob);
00141 }
00142 }
00143
00144
00145
00146 ROS_INFO("performing inference");
00147 for (size_t grasp_ind = 0; grasp_ind < grasps.size(); grasp_ind++)
00148 {
00149 double grasp_overall_success_prob = 0.0;
00150 double grasp_overall_failure_prob = 0.0;
00151 for (size_t object_ind = 0; object_ind < objects.size(); object_ind++)
00152 {
00153
00154 double object_prior;
00155 if (objects[object_ind].potential_models.size() > 0) object_prior = 0.5 / (objects.size()-1);
00156 else object_prior = 0.5;
00157
00158
00159 double detection_prob = 1.0;
00160
00161 BOOST_FOREACH(const boost::shared_ptr<ObjectDetector> &detector, object_detectors)
00162 {
00163 double obj_det_prob = detector->getProbabilityForDetection(objects[object_ind]);
00164
00165
00166 detection_prob *= obj_det_prob;
00167 }
00168
00169
00170
00171 double success_prior = 0.5;
00172 double failure_prior = 0.5;
00173
00174
00175 double grasp_success_prob = 1.0;
00176 double grasp_failure_prob = 1.0;
00177
00178
00179
00180
00181
00182
00183
00184
00185
00186 for (size_t eval_ind = 0; eval_ind < grasps[grasp_ind].success_cond_probs[object_ind].size(); eval_ind ++)
00187 {
00188
00189 double succ_prob = grasps[grasp_ind].success_cond_probs[object_ind][eval_ind];
00190
00191 double fail_prob = grasps[grasp_ind].failure_cond_probs[object_ind][eval_ind];
00192
00193 double eval_prob = succ_prob * success_prior + fail_prob * failure_prior;
00194
00195 grasp_success_prob *= succ_prob / eval_prob;
00196 grasp_failure_prob *= fail_prob / eval_prob;
00197
00198 }
00199
00200
00201
00202 grasp_overall_success_prob += object_prior * detection_prob * success_prior * grasp_success_prob;
00203 grasp_overall_failure_prob += object_prior * detection_prob * failure_prior * grasp_failure_prob;
00204
00205
00206
00207
00208
00209
00210 }
00211
00212
00213 if (grasp_overall_success_prob + grasp_overall_failure_prob == 0)
00214 {
00215 ROS_WARN("sum of success and failure conditional probs was 0!");
00216 grasps[grasp_ind].grasp_.success_probability = 0.;
00217 continue;
00218 }
00219 double normalization_factor = 1.0 / (grasp_overall_success_prob + grasp_overall_failure_prob);
00220 grasps[grasp_ind].grasp_.success_probability = normalization_factor * grasp_overall_success_prob;
00221
00222
00223 }
00224 }
00225
00226
00227 void BayesianGraspPlanner::plan(const std::string &arm_name,
00228 const object_manipulation_msgs::GraspableObject &graspable_object,
00229 std::vector<object_manipulation_msgs::Grasp> &final_grasp_list)
00230 {
00231
00232 boost::shared_ptr<ProbabilityDistribution> cluster_success_distribution(
00233
00234 new BimodalGaussianProbabilityDistribution(.611, .285, .806) );
00235
00236 boost::shared_ptr<ProbabilityDistribution> cluster_failure_distribution(
00237
00238 new BimodalGaussianProbabilityDistribution(.563, .272, .935) );
00239
00240 boost::shared_ptr<ProbabilityDistribution> graspit_success_distribution(
00241 new GaussianProbabilityDistribution(.825, .125, 0.0, 1.0, false) );
00242 boost::shared_ptr<ProbabilityDistribution> graspit_failure_distribution(
00243 new GaussianProbabilityDistribution(.627, .376, 0.0, 1.0, false) );
00244
00245
00246 std::vector<object_manipulation_msgs::GraspableObject> objects;
00247 createMutuallyExclusiveObjectRepresentations(graspable_object, objects);
00248
00249
00250 std::vector< boost::shared_ptr<ObjectDetector> > object_detectors;
00251 createDatabaseObjectDetectors(objects, object_detectors);
00252
00253
00254 std::vector< boost::shared_ptr<GraspGenerator> > grasp_generators;
00255
00256
00257 std::vector< boost::shared_ptr<GraspEvaluatorProb> > grasp_evaluators;
00258
00259
00260
00261 {
00262
00263 boost::shared_ptr<MultiplexEvaluator> graspit_multiplexer_regression_eval( new MultiplexEvaluator );
00264
00265
00266 BOOST_FOREACH(const household_objects_database_msgs::DatabaseModelPose &model, graspable_object.potential_models)
00267 {
00268
00269 boost::shared_ptr<GraspGenerator> grasp_gen( new GraspGeneratorDatabaseRetriever(database_, model, arm_name, false) );
00270 grasp_gen->generateGrasps();
00271
00272
00273 boost::shared_ptr<RawGraspEvaluator> regression_eval( new RawGraspEvaluatorWithRegression(grasp_gen, true) );
00274
00275
00276 graspit_multiplexer_regression_eval->addEvaluator(regression_eval, model.model_id);
00277
00278
00279 boost::shared_ptr<GraspGenerator> grasp_gen_reps( new GraspGeneratorDatabaseRetriever(database_, model, arm_name, true) );
00280
00281
00282 grasp_generators.push_back( grasp_gen_reps );
00283 }
00284
00285
00286 boost::shared_ptr<GraspEvaluatorProb> prob_eval( new GraspEvaluatorProb( graspit_success_distribution,
00287 graspit_failure_distribution,
00288 graspit_multiplexer_regression_eval ) );
00289
00290
00291 grasp_evaluators.push_back(prob_eval);
00292 }
00293
00294
00295
00296 {
00297
00298 boost::shared_ptr<GraspGenerator> grasp_gen( new GraspGeneratorServiceCaller(nh_, "/plan_point_cluster_grasp",
00299 graspable_object, arm_name));
00300
00301
00302 grasp_generators.push_back(grasp_gen);
00303
00304 int cluster_computer_type;
00305 nh_.param("cluster_computer_type",cluster_computer_type, 1);
00306 ROS_INFO("cluster_computer_type = %d", cluster_computer_type);
00307
00308 boost::shared_ptr<RawGraspEvaluator> cluster_eval;
00309 switch (cluster_computer_type)
00310 {
00311 case 1:
00312 {
00313 std::string test_cluster_grasp_srv;
00314 nh_.param("test_cluster_grasp_srv", test_cluster_grasp_srv, std::string("/evaluate_point_cluster_grasps"));
00315 cluster_eval.reset( new RawGraspEvaluatorServiceCaller(nh_, test_cluster_grasp_srv, false) );
00316 break;
00317 }
00318 case 2:
00319 {
00320 cluster_eval.reset( new RawGraspEvaluatorWithRegression(grasp_gen, false) );
00321 break;
00322 }
00323 }
00324
00325
00326 boost::shared_ptr<GraspEvaluatorProb> prob_eval( new GraspEvaluatorProb( cluster_success_distribution,
00327 cluster_failure_distribution,
00328 cluster_eval ) );
00329
00330 grasp_evaluators.push_back(prob_eval);
00331 }
00332
00333 ROS_INFO("%d grasp generators created", (int)grasp_generators.size());
00334
00335
00336 std::vector<GraspWM> grasps;
00337 ROS_INFO("evaluating grasps");
00338
00339
00340 if (final_grasp_list.size() > 0)
00341 {
00342
00343 appendMetadataToTestGrasps(final_grasp_list, grasps, graspable_object.reference_frame_id);
00344 }
00345
00346
00347 else
00348 {
00349 BOOST_FOREACH(boost::shared_ptr<GraspGenerator> &gen, grasp_generators)
00350 {
00351 ROS_INFO("getting grasps from grasp generator");
00352 gen->generateGrasps();
00353 gen->getGrasps(grasps);
00354 }
00355 }
00356
00357 ROS_INFO("number of grasps to evaluate: %d", (int)grasps.size());
00358
00359
00360 bayesianInference(grasps, objects, object_detectors, grasp_evaluators);
00361
00362
00363
00364
00365
00366
00367
00368
00369
00370
00371 std::sort(grasps.rbegin(), grasps.rend());
00372
00373 visualizeGrasps(grasps, &debug_preprune_grasp_marker_publisher_, false);
00374
00375
00376
00377
00378
00379
00380
00381
00382
00383 if (final_grasp_list.size() == 0)
00384 {
00385 double grasp_probability_threshold;
00386 nh_.param("initial_probability_threshold", grasp_probability_threshold, 0.01);
00387 pruneGraspList(grasps, grasp_probability_threshold);
00388 }
00389
00390 visualizeGrasps(grasps, &debug_postprune_grasp_marker_publisher_, false);
00391
00392
00393 ROS_INFO("clustering");
00394 std::vector<GraspWM> clustered_grasps;
00395 clusterGrasps(grasps, clustered_grasps);
00396
00397
00398 int grasps_max;
00399 nh_.param("quantity_threshold", grasps_max, 100);
00400 size_t grasps_max_size = grasps_max;
00401 if (clustered_grasps.size() > grasps_max_size)
00402 {
00403 ROS_INFO("Taking top %zd grasps after clustering", grasps_max_size);
00404 clustered_grasps.resize(grasps_max_size);
00405 }
00406
00407
00408 final_grasp_list.clear();
00409 final_grasp_list.reserve(clustered_grasps.size());
00410 BOOST_FOREACH(GraspWM graspwm, clustered_grasps)
00411 {
00412 final_grasp_list.push_back(graspwm.getGrasp());
00413
00414 }
00415 visualizeGrasps(clustered_grasps, &grasp_marker_publisher_, false);
00416
00417 ROS_INFO("done planning");
00418 }
00419
00420 void BayesianGraspPlanner::createMutuallyExclusiveObjectRepresentations(
00421 const object_manipulation_msgs::GraspableObject &original_object,
00422 std::vector<object_manipulation_msgs::GraspableObject> &me_objects )
00423 {
00424
00425 for (size_t i = 0; i < original_object.potential_models.size(); i++)
00426 {
00427 object_manipulation_msgs::GraspableObject new_object;
00428 new_object.potential_models.push_back(original_object.potential_models[i]);
00429 new_object.reference_frame_id = original_object.reference_frame_id;
00430 me_objects.push_back(new_object);
00431 }
00432
00433
00434 object_manipulation_msgs::GraspableObject new_object;
00435 new_object.cluster = original_object.cluster;
00436 new_object.reference_frame_id = original_object.reference_frame_id;
00437 me_objects.push_back(new_object);
00438
00439 ROS_INFO("%d object representations created", (int)me_objects.size());
00440 }
00441
00442 void BayesianGraspPlanner::createDatabaseObjectDetectors(
00443 const std::vector<object_manipulation_msgs::GraspableObject> &objects,
00444 std::vector< boost::shared_ptr<ObjectDetector> >&detectors)
00445 {
00446
00447
00448 boost::shared_ptr<ProbabilityDistribution> correct_distribution(
00449 new GaussianProbabilityDistribution(.531, .125, 0., .005, true));
00450 boost::shared_ptr<ProbabilityDistribution> incorrect_distribution(
00451 new GaussianProbabilityDistribution(.292, .154, 0., .005, true));
00452
00453
00454 for (size_t i = 0; i < objects.size(); i++)
00455 {
00456 if (objects[i].potential_models.size() != 0)
00457 {
00458 boost::shared_ptr<ObjectDetector> detector ( new DatabaseObjectDetector(objects[i], correct_distribution,
00459 incorrect_distribution) );
00460 detectors.push_back(detector);
00461 }
00462 }
00463 ROS_INFO("%d object detectors created", (int)detectors.size());
00464 }
00465
00466 void BayesianGraspPlanner::appendMetadataToTestGrasps(std::vector<object_manipulation_msgs::Grasp> &input_list,
00467 std::vector<GraspWM> &output_list, const std::string frame_id)
00468 {
00469
00470 output_list.reserve(output_list.size()+input_list.size());
00471
00472 ROS_INFO("Got %zd grasps to test",input_list.size());
00473 BOOST_FOREACH(object_manipulation_msgs::Grasp &grasp, input_list)
00474 {
00475 GraspWM grasp_wm;
00476 grasp_wm.grasp_ = grasp;
00477 grasp_wm.grasp_.success_probability = 0.0;
00478 grasp_wm.model_id_ = -1;
00479 grasp_wm.grasp_id_ = -1;
00480
00481 grasp_wm.object_pose_.setIdentity();
00482 grasp_wm.object_pose_.frame_id_ = frame_id;
00483 grasp_wm.object_pose_.stamp_ = ros::Time(0);
00484
00486 tf::Pose grasp_in_base_frame;
00487 tf::poseMsgToTF(grasp.grasp_pose, grasp_in_base_frame);
00488 double wrist_to_tool_point_offset_ = 0.13;
00489 tf::Pose grasp_to_tool_point(btMatrix3x3::getIdentity(),btVector3(wrist_to_tool_point_offset_,0,0));
00490 grasp_wm.tool_point_pose_ = tf::Stamped<tf::Pose>(
00491 grasp_in_base_frame * grasp_to_tool_point, grasp_wm.object_pose_.stamp_, frame_id);
00492
00493 output_list.push_back(grasp_wm);
00494 }
00495 ROS_DEBUG("Created %zd grasps", output_list.size());
00496 }
00497
00498
00499 void BayesianGraspPlanner::clusterGrasps(std::vector<GraspWM> &input_list,
00500 std::vector<GraspWM> &cluster_rep_list)
00501 {
00502 ROS_INFO("Clustering %zd grasps",input_list.size());
00503
00504 double clustering_cart_distance_threshold = 0.01;
00505 double clustering_angle_distance_threshold = 0.266;
00506
00507 int clusters = 0;
00508 while (!input_list.empty())
00509 {
00510 GraspWM *repGrasp = &input_list.front();
00511 repGrasp->grasp_.cluster_rep = true;
00512 cluster_rep_list.push_back(*repGrasp);
00513 input_list.erase(input_list.begin());
00514 ++clusters;
00515
00516 int cloud=0;
00517 std::vector<GraspWM>::iterator it=input_list.begin();
00518 while (it != input_list.end())
00519 {
00520 double cart_distance, angle_distance;
00521 cluster_rep_list.back().getDistance(*it,cart_distance,angle_distance);
00522 if (cart_distance < clustering_cart_distance_threshold &&
00523 angle_distance < clustering_angle_distance_threshold)
00524 {
00525 ++cloud;
00530
00531 it = input_list.erase(it);
00532 }
00533 else {
00534 ++it;
00535 }
00536 }
00537 ROS_DEBUG("Grouped cluster of size %d",cloud);
00538 }
00539 ROS_INFO("Selected %d cluster rep grasps",clusters);
00540 }
00541
00542 void BayesianGraspPlanner::pruneGraspList(std::vector<GraspWM> &grasps, const double threshold)
00543 {
00544 std::vector<GraspWM>::iterator it=grasps.begin();
00545 int erased_count = 0;
00546 while( it != grasps.end())
00547 {
00548 if (it->grasp_.success_probability < threshold)
00549 {
00550 erased_count++;
00551 ROS_DEBUG("Erasing grasp with probability %g",it->grasp_.success_probability);
00552 it=grasps.erase(it);
00553 }
00554 else{
00555 it++;
00556 }
00557 }
00558
00559 ROS_INFO("Removed %d grasps below threshold",erased_count);
00560 }
00561
00562
00563
00564 void BayesianGraspPlanner::visualizeGrasps(const std::vector<GraspWM> &grasps,
00565 object_manipulator::GraspMarkerPublisher *grasp_publisher, bool color_by_rank)
00566 {
00567 grasp_publisher->clearAllMarkers();
00568 size_t sz = grasps.size();
00569 if (sz == 0)
00570 {
00571 return;
00572 }
00573
00574 for (size_t i=0; i < sz; i++) {
00575 const GraspWM *grasp = &grasps[i];
00576 std::string ns_append = boost::lexical_cast<std::string>(grasp->model_id_);
00577 grasp_publisher->setNamespaceSuffix(ns_append);
00578
00579
00580
00581 tf::Pose grasp_pose_tf;
00582 tf::poseMsgToTF(grasp->grasp_.grasp_pose, grasp_pose_tf);
00583
00584 tf::Stamped<tf::Pose> grasp_in_world(grasp_pose_tf, grasp->object_pose_.stamp_, grasp->object_pose_.frame_id_);
00585
00586 geometry_msgs::PoseStamped grasp_in_world_msg;
00587 tf::poseStampedTFToMsg(grasp_in_world, grasp_in_world_msg);
00588
00589 unsigned int id = grasp_publisher->addGraspMarker(grasp_in_world_msg);
00590
00591 float colorval;
00592 if (color_by_rank)
00593 {
00594 colorval = i/(1.0*sz);
00595 }
00596 else {
00597 colorval = 1 - grasp->grasp_.success_probability;
00598 }
00599 grasp_publisher->colorGraspMarker(id, colorval, 1-colorval, 0.0);
00600 }
00601 }
00602
00603
00604 }