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