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 _ROBUST_PLANNER_TOOLS_H_
00038 #define _ROBUST_PLANNER_TOOLS_H_
00039
00040
00041
00042 #define DISALLOW_COPY_AND_ASSIGN(TypeName) \
00043 TypeName(const TypeName&); \
00044 void operator=(const TypeName&)
00045
00046 #include <map>
00047 #include <cmath>
00048
00049 #include <object_manipulation_msgs/Grasp.h>
00050 #include <object_manipulation_msgs/GraspableObject.h>
00051 #include <tf/transform_datatypes.h>
00052 #include <ros/ros.h>
00053
00054 #include "probabilistic_grasp_planner/forward_decls.h"
00055
00056 namespace probabilistic_grasp_planner {
00057
00058 class GraspWithMetadata
00059 {
00060 private:
00061
00062 public:
00063 int grasp_id_;
00064 int model_id_;
00065 double energy_function_score_;
00066 object_manipulation_msgs::Grasp grasp_;
00067 tf::Stamped<tf::Pose> object_pose_;
00068 tf::Stamped<tf::Pose> tool_point_pose_;
00069 double success_probability;
00070 std::vector<std::pair<int,std::pair<double,double> > >debug_probabilities;
00071
00072 GraspWithMetadata() : success_probability(0.0)
00073 {
00074
00075 }
00076
00077 void getDistance(const GraspWithMetadata &other, double &cartesian_dist, double &rotation_dist, bool debug=false) const
00078 {
00079 tf::Vector3 gstar_position = tool_point_pose_.getOrigin();
00080 tf::Quaternion gstar_orientation = tool_point_pose_.getRotation();
00081
00082 tf::Vector3 grasp_position = other.tool_point_pose_.getOrigin();
00083 tf::Quaternion grasp_orientation = other.tool_point_pose_.getRotation();
00084
00085 if (debug) ROS_INFO("grasp: %f %f %f; other: %f %f %f",
00086 gstar_position.x(),gstar_position.y(),gstar_position.z(),
00087 grasp_position.x(),grasp_position.y(),grasp_position.z());
00088
00089 tf::Vector3 delta_position = gstar_position - grasp_position;
00090 cartesian_dist = delta_position.length();
00091
00092 rotation_dist = gstar_orientation.angleShortestPath(grasp_orientation);
00093 }
00094 };
00095
00096 struct ObjectRepresentation
00097 {
00098 object_manipulation_msgs::GraspableObject object;
00099 boost::shared_ptr<GraspSuccessProbabilityComputer> grasp_success_computer;
00100 boost::shared_ptr<GraspSuccessProbabilityComputer> precise_grasp_success_computer;
00101 boost::shared_ptr<GraspRetriever> grasp_retriever;
00102 double probability;
00103 };
00104
00105
00106 inline bool operator< (const GraspWithMetadata &g1, const GraspWithMetadata &g2)
00107 {
00108 return g1.grasp_.success_probability < g2.grasp_.success_probability;
00109 }
00110
00111 template <class svcType>
00112 inline ros::ServiceClient register_service(ros::NodeHandle &nh, const std::string &service_name)
00113 {
00114 while (!ros::service::waitForService(service_name, ros::Duration(2.0)) && nh.ok())
00115 {
00116 ROS_INFO("Waiting for %s service to come up", service_name.c_str());
00117 }
00118 if (!nh.ok()) exit(0);
00119 return nh.serviceClient<svcType>(service_name, true);
00120 }
00121
00123
00126 template <class ServiceDataType>
00127 class ServiceWrapper
00128 {
00129 private:
00131 bool initialized_;
00133 std::string service_name_;
00135 ros::NodeHandle nh_;
00137 ros::ServiceClient client_;
00138 public:
00139 ServiceWrapper(std::string service_name) : initialized_(false),
00140 service_name_(service_name),
00141 nh_("")
00142 {}
00143
00145 ros::ServiceClient& client()
00146 {
00147 if (!initialized_)
00148 {
00149 while ( !ros::service::waitForService(service_name_, ros::Duration(2.0)) && nh_.ok() )
00150 {
00151 ROS_INFO_STREAM("Waiting for service: " << service_name_);
00152 }
00153 if (!nh_.ok()) exit(0);
00154 client_ = nh_.serviceClient<ServiceDataType>(service_name_);
00155 initialized_ = true;
00156 }
00157 return client_;
00158 }
00159 };
00160
00161
00162 template <typename KeyType, typename ValueType>
00163 static bool retrieve_from_map(std::map<KeyType, ValueType> &map, KeyType &key, ValueType &value)
00164 {
00165 typename std::map<KeyType, ValueType>::iterator it = map.find(key);
00166
00167 if (it != map.end())
00168 {
00169 value = it->second;
00170 return true;
00171 }
00172 return false;
00173 }
00174
00175 }
00176
00177 #endif