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