Go to the documentation of this file.00001 
00002 #ifndef SRS_SYMBOLIC_GROUNDING_SERVICE_SYMBOLGROUNDINGGRASPBASEPOSE_H
00003 #define SRS_SYMBOLIC_GROUNDING_SERVICE_SYMBOLGROUNDINGGRASPBASEPOSE_H
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <ostream>
00008 #include "ros/serialization.h"
00009 #include "ros/builtin_message_traits.h"
00010 #include "ros/message_operations.h"
00011 #include "ros/time.h"
00012 
00013 #include "ros/macros.h"
00014 
00015 #include "ros/assert.h"
00016 
00017 #include "ros/service_traits.h"
00018 
00019 #include "geometry_msgs/Pose.h"
00020 #include "srs_msgs/SRSSpatialInfo.h"
00021 #include "srs_msgs/SRSSpatialInfo.h"
00022 
00023 
00024 #include "geometry_msgs/Pose2D.h"
00025 
00026 namespace srs_symbolic_grounding
00027 {
00028 template <class ContainerAllocator>
00029 struct SymbolGroundingGraspBasePoseRequest_ {
00030   typedef SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> Type;
00031 
00032   SymbolGroundingGraspBasePoseRequest_()
00033   : target_obj_pose()
00034   , parent_obj_geometry()
00035   , furniture_geometry_list()
00036   {
00037   }
00038 
00039   SymbolGroundingGraspBasePoseRequest_(const ContainerAllocator& _alloc)
00040   : target_obj_pose(_alloc)
00041   , parent_obj_geometry(_alloc)
00042   , furniture_geometry_list(_alloc)
00043   {
00044   }
00045 
00046   typedef  ::geometry_msgs::Pose_<ContainerAllocator>  _target_obj_pose_type;
00047    ::geometry_msgs::Pose_<ContainerAllocator>  target_obj_pose;
00048 
00049   typedef  ::srs_msgs::SRSSpatialInfo_<ContainerAllocator>  _parent_obj_geometry_type;
00050    ::srs_msgs::SRSSpatialInfo_<ContainerAllocator>  parent_obj_geometry;
00051 
00052   typedef std::vector< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> >::other >  _furniture_geometry_list_type;
00053   std::vector< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::srs_msgs::SRSSpatialInfo_<ContainerAllocator> >::other >  furniture_geometry_list;
00054 
00055 
00056   typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> > Ptr;
00057   typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator>  const> ConstPtr;
00058   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00059 }; 
00060 typedef  ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<std::allocator<void> > SymbolGroundingGraspBasePoseRequest;
00061 
00062 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest> SymbolGroundingGraspBasePoseRequestPtr;
00063 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest const> SymbolGroundingGraspBasePoseRequestConstPtr;
00064 
00065 
00066 template <class ContainerAllocator>
00067 struct SymbolGroundingGraspBasePoseResponse_ {
00068   typedef SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> Type;
00069 
00070   SymbolGroundingGraspBasePoseResponse_()
00071   : obstacle_check(false)
00072   , reach(0.0)
00073   , grasp_base_pose()
00074   {
00075   }
00076 
00077   SymbolGroundingGraspBasePoseResponse_(const ContainerAllocator& _alloc)
00078   : obstacle_check(false)
00079   , reach(0.0)
00080   , grasp_base_pose(_alloc)
00081   {
00082   }
00083 
00084   typedef uint8_t _obstacle_check_type;
00085   uint8_t obstacle_check;
00086 
00087   typedef float _reach_type;
00088   float reach;
00089 
00090   typedef  ::geometry_msgs::Pose2D_<ContainerAllocator>  _grasp_base_pose_type;
00091    ::geometry_msgs::Pose2D_<ContainerAllocator>  grasp_base_pose;
00092 
00093 
00094   typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> > Ptr;
00095   typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator>  const> ConstPtr;
00096   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00097 }; 
00098 typedef  ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<std::allocator<void> > SymbolGroundingGraspBasePoseResponse;
00099 
00100 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse> SymbolGroundingGraspBasePoseResponsePtr;
00101 typedef boost::shared_ptr< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse const> SymbolGroundingGraspBasePoseResponseConstPtr;
00102 
00103 struct SymbolGroundingGraspBasePose
00104 {
00105 
00106 typedef SymbolGroundingGraspBasePoseRequest Request;
00107 typedef SymbolGroundingGraspBasePoseResponse Response;
00108 Request request;
00109 Response response;
00110 
00111 typedef Request RequestType;
00112 typedef Response ResponseType;
00113 }; 
00114 } 
00115 
00116 namespace ros
00117 {
00118 namespace message_traits
00119 {
00120 template<class ContainerAllocator> struct IsMessage< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> > : public TrueType {};
00121 template<class ContainerAllocator> struct IsMessage< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator>  const> : public TrueType {};
00122 template<class ContainerAllocator>
00123 struct MD5Sum< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> > {
00124   static const char* value() 
00125   {
00126     return "929217c873801a8d83a0ef0a0ff55374";
00127   }
00128 
00129   static const char* value(const  ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> &) { return value(); } 
00130   static const uint64_t static_value1 = 0x929217c873801a8dULL;
00131   static const uint64_t static_value2 = 0x83a0ef0a0ff55374ULL;
00132 };
00133 
00134 template<class ContainerAllocator>
00135 struct DataType< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> > {
00136   static const char* value() 
00137   {
00138     return "srs_symbolic_grounding/SymbolGroundingGraspBasePoseRequest";
00139   }
00140 
00141   static const char* value(const  ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> &) { return value(); } 
00142 };
00143 
00144 template<class ContainerAllocator>
00145 struct Definition< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> > {
00146   static const char* value() 
00147   {
00148     return "geometry_msgs/Pose target_obj_pose\n\
00149 \n\
00150 \n\
00151 srs_msgs/SRSSpatialInfo parent_obj_geometry\n\
00152 srs_msgs/SRSSpatialInfo[] furniture_geometry_list\n\
00153 \n\
00154 ================================================================================\n\
00155 MSG: geometry_msgs/Pose\n\
00156 # A representation of pose in free space, composed of postion and orientation. \n\
00157 Point position\n\
00158 Quaternion orientation\n\
00159 \n\
00160 ================================================================================\n\
00161 MSG: geometry_msgs/Point\n\
00162 # This contains the position of a point in free space\n\
00163 float64 x\n\
00164 float64 y\n\
00165 float64 z\n\
00166 \n\
00167 ================================================================================\n\
00168 MSG: geometry_msgs/Quaternion\n\
00169 # This represents an orientation in free space in quaternion form.\n\
00170 \n\
00171 float64 x\n\
00172 float64 y\n\
00173 float64 z\n\
00174 float64 w\n\
00175 \n\
00176 ================================================================================\n\
00177 MSG: srs_msgs/SRSSpatialInfo\n\
00178 # Point point\n\
00179 # Orientation angles\n\
00180 float32 l\n\
00181 float32 w\n\
00182 float32 h\n\
00183 \n\
00184 geometry_msgs/Pose pose\n\
00185 \n\
00186 ";
00187   }
00188 
00189   static const char* value(const  ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> &) { return value(); } 
00190 };
00191 
00192 } 
00193 } 
00194 
00195 
00196 namespace ros
00197 {
00198 namespace message_traits
00199 {
00200 template<class ContainerAllocator> struct IsMessage< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> > : public TrueType {};
00201 template<class ContainerAllocator> struct IsMessage< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator>  const> : public TrueType {};
00202 template<class ContainerAllocator>
00203 struct MD5Sum< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> > {
00204   static const char* value() 
00205   {
00206     return "1166b4429d4bb491f620326781fed922";
00207   }
00208 
00209   static const char* value(const  ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> &) { return value(); } 
00210   static const uint64_t static_value1 = 0x1166b4429d4bb491ULL;
00211   static const uint64_t static_value2 = 0xf620326781fed922ULL;
00212 };
00213 
00214 template<class ContainerAllocator>
00215 struct DataType< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> > {
00216   static const char* value() 
00217   {
00218     return "srs_symbolic_grounding/SymbolGroundingGraspBasePoseResponse";
00219   }
00220 
00221   static const char* value(const  ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> &) { return value(); } 
00222 };
00223 
00224 template<class ContainerAllocator>
00225 struct Definition< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> > {
00226   static const char* value() 
00227   {
00228     return "bool obstacle_check\n\
00229 float32 reach\n\
00230 geometry_msgs/Pose2D grasp_base_pose\n\
00231 \n\
00232 \n\
00233 ================================================================================\n\
00234 MSG: geometry_msgs/Pose2D\n\
00235 # This expresses a position and orientation on a 2D manifold.\n\
00236 \n\
00237 float64 x\n\
00238 float64 y\n\
00239 float64 theta\n\
00240 ";
00241   }
00242 
00243   static const char* value(const  ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> &) { return value(); } 
00244 };
00245 
00246 template<class ContainerAllocator> struct IsFixedSize< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> > : public TrueType {};
00247 } 
00248 } 
00249 
00250 namespace ros
00251 {
00252 namespace serialization
00253 {
00254 
00255 template<class ContainerAllocator> struct Serializer< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> >
00256 {
00257   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00258   {
00259     stream.next(m.target_obj_pose);
00260     stream.next(m.parent_obj_geometry);
00261     stream.next(m.furniture_geometry_list);
00262   }
00263 
00264   ROS_DECLARE_ALLINONE_SERIALIZER;
00265 }; 
00266 } 
00267 } 
00268 
00269 
00270 namespace ros
00271 {
00272 namespace serialization
00273 {
00274 
00275 template<class ContainerAllocator> struct Serializer< ::srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> >
00276 {
00277   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00278   {
00279     stream.next(m.obstacle_check);
00280     stream.next(m.reach);
00281     stream.next(m.grasp_base_pose);
00282   }
00283 
00284   ROS_DECLARE_ALLINONE_SERIALIZER;
00285 }; 
00286 } 
00287 } 
00288 
00289 namespace ros
00290 {
00291 namespace service_traits
00292 {
00293 template<>
00294 struct MD5Sum<srs_symbolic_grounding::SymbolGroundingGraspBasePose> {
00295   static const char* value() 
00296   {
00297     return "80365e2dd1e4f246fb4542bfaa7f0518";
00298   }
00299 
00300   static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePose&) { return value(); } 
00301 };
00302 
00303 template<>
00304 struct DataType<srs_symbolic_grounding::SymbolGroundingGraspBasePose> {
00305   static const char* value() 
00306   {
00307     return "srs_symbolic_grounding/SymbolGroundingGraspBasePose";
00308   }
00309 
00310   static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePose&) { return value(); } 
00311 };
00312 
00313 template<class ContainerAllocator>
00314 struct MD5Sum<srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> > {
00315   static const char* value() 
00316   {
00317     return "80365e2dd1e4f246fb4542bfaa7f0518";
00318   }
00319 
00320   static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> &) { return value(); } 
00321 };
00322 
00323 template<class ContainerAllocator>
00324 struct DataType<srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> > {
00325   static const char* value() 
00326   {
00327     return "srs_symbolic_grounding/SymbolGroundingGraspBasePose";
00328   }
00329 
00330   static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePoseRequest_<ContainerAllocator> &) { return value(); } 
00331 };
00332 
00333 template<class ContainerAllocator>
00334 struct MD5Sum<srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> > {
00335   static const char* value() 
00336   {
00337     return "80365e2dd1e4f246fb4542bfaa7f0518";
00338   }
00339 
00340   static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> &) { return value(); } 
00341 };
00342 
00343 template<class ContainerAllocator>
00344 struct DataType<srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> > {
00345   static const char* value() 
00346   {
00347     return "srs_symbolic_grounding/SymbolGroundingGraspBasePose";
00348   }
00349 
00350   static const char* value(const srs_symbolic_grounding::SymbolGroundingGraspBasePoseResponse_<ContainerAllocator> &) { return value(); } 
00351 };
00352 
00353 } 
00354 } 
00355 
00356 #endif // SRS_SYMBOLIC_GROUNDING_SERVICE_SYMBOLGROUNDINGGRASPBASEPOSE_H
00357