Go to the documentation of this file.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 #ifndef PROBABILISTIC_GRASP_PLANNER_H_
00038 #define PROBABILISTIC_GRASP_PLANNER_H_
00039
00040 #include <object_manipulator/tools/grasp_marker_publisher.h>
00041
00042 #include "probabilistic_grasp_planner/forward_decls.h"
00043
00044 #include "probabilistic_grasp_planner/recognition_probability_computer.h"
00045 #include "probabilistic_grasp_planner/grasp_success_probability_computer.h"
00046 #include "probabilistic_grasp_planner/grasp_retriever.h"
00047
00048 namespace probabilistic_grasp_planner {
00049
00050 class ProbabilisticGraspPlanner
00051 {
00052 private:
00053 ObjectsDatabasePtr database_;
00054
00055 ros::NodeHandle nh_;
00056
00058 object_manipulator::GraspMarkerPublisher *grasp_marker_publisher_;
00059
00061 object_manipulator::GraspMarkerPublisher *debug_grasp_marker_publisher_;
00062
00064 object_manipulator::GraspMarkerPublisher debug_preprune_grasp_marker_publisher_;
00065
00067 object_manipulator::GraspMarkerPublisher debug_precluster_grasp_marker_publisher_;
00068
00070 object_manipulator::GraspMarkerPublisher debug_postprune_grasp_marker_publisher_;
00071
00073 object_manipulator::GraspMarkerPublisher *rank_grasp_marker_publisher_;
00074
00079 void visualizeGrasps(const std::vector<GraspWithMetadata> &grasps,
00080 object_manipulator::GraspMarkerPublisher *grasp_marker_pub, bool color_by_rank);
00081
00087 void populateRepresentationsList(std::vector<ObjectRepresentation> &representations,
00088 std::string arm_name,
00089 const object_manipulation_msgs::GraspableObject &request_object,
00090 const bool enable_cluster);
00091
00096 ObjectRepresentation getObjectRepresentationFromCluster(const object_manipulation_msgs::GraspableObject &request_object,
00097 std::string arm_name);
00098
00099
00104 ObjectRepresentation getObjectRepresentationFromDatabaseObject(
00105 const household_objects_database_msgs::DatabaseModelPose &model_with_score,
00106 std::string arm_name);
00107
00108 void printGrasps(const std::vector<GraspWithMetadata> &grasps);
00109
00110 void appendMetadataToTestGrasps(std::vector<object_manipulation_msgs::Grasp> &input_list,
00111 std::vector<GraspWithMetadata> &output_list,
00112 const object_manipulation_msgs::GraspableObject &graspable_object);
00113
00114 void pruneGraspList(std::vector<GraspWithMetadata> &grasps, const double threshold);
00115
00116 void clusterGrasps(std::vector<GraspWithMetadata> &input_list, std::vector<GraspWithMetadata> &cluster_rep_list);
00117
00118 void printRepresentations(const std::vector<ObjectRepresentation> &representations);
00119
00120 public:
00124 ProbabilisticGraspPlanner(ObjectsDatabasePtr database) :
00125 database_(database),
00126 nh_("~"),
00127 debug_preprune_grasp_marker_publisher_("debug_preprune_grasp_list","",5.0),
00128 debug_precluster_grasp_marker_publisher_("debug_precluster_grasp_list","",5.0),
00129 debug_postprune_grasp_marker_publisher_("debug_postprune_grasp_list","",5.0)
00130 {
00131 }
00132
00140 void plan(const std::string &arm_name, object_manipulation_msgs::GraspableObject &graspable_object,
00141 std::vector<object_manipulation_msgs::Grasp> &grasps, bool visualize_results,
00142 bool prune_grasps);
00147 void setMarkerPublisher(object_manipulator::GraspMarkerPublisher* publisher,
00148 object_manipulator::GraspMarkerPublisher* debug_publisher,
00149 object_manipulator::GraspMarkerPublisher* rank_publisher)
00150 {
00151 grasp_marker_publisher_ = publisher;
00152 debug_grasp_marker_publisher_ = debug_publisher;
00153 rank_grasp_marker_publisher_ = rank_publisher;
00154 }
00155 };
00156 typedef boost::shared_ptr<ProbabilisticGraspPlanner> ProbabilisticGraspPlannerPtr;
00157
00158 }
00159
00160 #endif