Go to the documentation of this file.00001
00002 #ifndef PIXEL_2_3D_SERVICE_PIXEL23D_H
00003 #define PIXEL_2_3D_SERVICE_PIXEL23D_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
00020
00021 #include "geometry_msgs/PoseStamped.h"
00022
00023 namespace pixel_2_3d
00024 {
00025 template <class ContainerAllocator>
00026 struct Pixel23dRequest_ {
00027 typedef Pixel23dRequest_<ContainerAllocator> Type;
00028
00029 Pixel23dRequest_()
00030 : pixel_u(0)
00031 , pixel_v(0)
00032 {
00033 }
00034
00035 Pixel23dRequest_(const ContainerAllocator& _alloc)
00036 : pixel_u(0)
00037 , pixel_v(0)
00038 {
00039 }
00040
00041 typedef int32_t _pixel_u_type;
00042 int32_t pixel_u;
00043
00044 typedef int32_t _pixel_v_type;
00045 int32_t pixel_v;
00046
00047
00048 typedef boost::shared_ptr< ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> > Ptr;
00049 typedef boost::shared_ptr< ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> const> ConstPtr;
00050 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00051 };
00052 typedef ::pixel_2_3d::Pixel23dRequest_<std::allocator<void> > Pixel23dRequest;
00053
00054 typedef boost::shared_ptr< ::pixel_2_3d::Pixel23dRequest> Pixel23dRequestPtr;
00055 typedef boost::shared_ptr< ::pixel_2_3d::Pixel23dRequest const> Pixel23dRequestConstPtr;
00056
00057
00058 template <class ContainerAllocator>
00059 struct Pixel23dResponse_ {
00060 typedef Pixel23dResponse_<ContainerAllocator> Type;
00061
00062 Pixel23dResponse_()
00063 : pixel3d()
00064 , error_flag(0)
00065 {
00066 }
00067
00068 Pixel23dResponse_(const ContainerAllocator& _alloc)
00069 : pixel3d(_alloc)
00070 , error_flag(0)
00071 {
00072 }
00073
00074 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _pixel3d_type;
00075 ::geometry_msgs::PoseStamped_<ContainerAllocator> pixel3d;
00076
00077 typedef uint8_t _error_flag_type;
00078 uint8_t error_flag;
00079
00080 enum { SUCCESS = 0 };
00081 enum { NO_CAMERA_INFO = 1 };
00082 enum { NO_POINT_CLOUD = 2 };
00083 enum { OUTSIDE_IMAGE = 3 };
00084 enum { OUTSIDE_POINT_CLOUD = 4 };
00085
00086 typedef boost::shared_ptr< ::pixel_2_3d::Pixel23dResponse_<ContainerAllocator> > Ptr;
00087 typedef boost::shared_ptr< ::pixel_2_3d::Pixel23dResponse_<ContainerAllocator> const> ConstPtr;
00088 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00089 };
00090 typedef ::pixel_2_3d::Pixel23dResponse_<std::allocator<void> > Pixel23dResponse;
00091
00092 typedef boost::shared_ptr< ::pixel_2_3d::Pixel23dResponse> Pixel23dResponsePtr;
00093 typedef boost::shared_ptr< ::pixel_2_3d::Pixel23dResponse const> Pixel23dResponseConstPtr;
00094
00095 struct Pixel23d
00096 {
00097
00098 typedef Pixel23dRequest Request;
00099 typedef Pixel23dResponse Response;
00100 Request request;
00101 Response response;
00102
00103 typedef Request RequestType;
00104 typedef Response ResponseType;
00105 };
00106 }
00107
00108 namespace ros
00109 {
00110 namespace message_traits
00111 {
00112 template<class ContainerAllocator> struct IsMessage< ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> > : public TrueType {};
00113 template<class ContainerAllocator> struct IsMessage< ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> const> : public TrueType {};
00114 template<class ContainerAllocator>
00115 struct MD5Sum< ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> > {
00116 static const char* value()
00117 {
00118 return "2044eb57c15e4dce3c879a1a1b124b3b";
00119 }
00120
00121 static const char* value(const ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> &) { return value(); }
00122 static const uint64_t static_value1 = 0x2044eb57c15e4dceULL;
00123 static const uint64_t static_value2 = 0x3c879a1a1b124b3bULL;
00124 };
00125
00126 template<class ContainerAllocator>
00127 struct DataType< ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> > {
00128 static const char* value()
00129 {
00130 return "pixel_2_3d/Pixel23dRequest";
00131 }
00132
00133 static const char* value(const ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> &) { return value(); }
00134 };
00135
00136 template<class ContainerAllocator>
00137 struct Definition< ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> > {
00138 static const char* value()
00139 {
00140 return "int32 pixel_u\n\
00141 int32 pixel_v\n\
00142 \n\
00143 ";
00144 }
00145
00146 static const char* value(const ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> &) { return value(); }
00147 };
00148
00149 template<class ContainerAllocator> struct IsFixedSize< ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> > : public TrueType {};
00150 }
00151 }
00152
00153
00154 namespace ros
00155 {
00156 namespace message_traits
00157 {
00158 template<class ContainerAllocator> struct IsMessage< ::pixel_2_3d::Pixel23dResponse_<ContainerAllocator> > : public TrueType {};
00159 template<class ContainerAllocator> struct IsMessage< ::pixel_2_3d::Pixel23dResponse_<ContainerAllocator> const> : public TrueType {};
00160 template<class ContainerAllocator>
00161 struct MD5Sum< ::pixel_2_3d::Pixel23dResponse_<ContainerAllocator> > {
00162 static const char* value()
00163 {
00164 return "bac764537310ba8703643eb02ade4505";
00165 }
00166
00167 static const char* value(const ::pixel_2_3d::Pixel23dResponse_<ContainerAllocator> &) { return value(); }
00168 static const uint64_t static_value1 = 0xbac764537310ba87ULL;
00169 static const uint64_t static_value2 = 0x03643eb02ade4505ULL;
00170 };
00171
00172 template<class ContainerAllocator>
00173 struct DataType< ::pixel_2_3d::Pixel23dResponse_<ContainerAllocator> > {
00174 static const char* value()
00175 {
00176 return "pixel_2_3d/Pixel23dResponse";
00177 }
00178
00179 static const char* value(const ::pixel_2_3d::Pixel23dResponse_<ContainerAllocator> &) { return value(); }
00180 };
00181
00182 template<class ContainerAllocator>
00183 struct Definition< ::pixel_2_3d::Pixel23dResponse_<ContainerAllocator> > {
00184 static const char* value()
00185 {
00186 return "geometry_msgs/PoseStamped pixel3d\n\
00187 uint8 error_flag\n\
00188 uint8 SUCCESS=0\n\
00189 uint8 NO_CAMERA_INFO=1\n\
00190 uint8 NO_POINT_CLOUD=2\n\
00191 uint8 OUTSIDE_IMAGE=3\n\
00192 uint8 OUTSIDE_POINT_CLOUD=4\n\
00193 \n\
00194 \n\
00195 ================================================================================\n\
00196 MSG: geometry_msgs/PoseStamped\n\
00197 # A Pose with reference coordinate frame and timestamp\n\
00198 Header header\n\
00199 Pose pose\n\
00200 \n\
00201 ================================================================================\n\
00202 MSG: std_msgs/Header\n\
00203 # Standard metadata for higher-level stamped data types.\n\
00204 # This is generally used to communicate timestamped data \n\
00205 # in a particular coordinate frame.\n\
00206 # \n\
00207 # sequence ID: consecutively increasing ID \n\
00208 uint32 seq\n\
00209 #Two-integer timestamp that is expressed as:\n\
00210 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00211 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00212 # time-handling sugar is provided by the client library\n\
00213 time stamp\n\
00214 #Frame this data is associated with\n\
00215 # 0: no frame\n\
00216 # 1: global frame\n\
00217 string frame_id\n\
00218 \n\
00219 ================================================================================\n\
00220 MSG: geometry_msgs/Pose\n\
00221 # A representation of pose in free space, composed of postion and orientation. \n\
00222 Point position\n\
00223 Quaternion orientation\n\
00224 \n\
00225 ================================================================================\n\
00226 MSG: geometry_msgs/Point\n\
00227 # This contains the position of a point in free space\n\
00228 float64 x\n\
00229 float64 y\n\
00230 float64 z\n\
00231 \n\
00232 ================================================================================\n\
00233 MSG: geometry_msgs/Quaternion\n\
00234 # This represents an orientation in free space in quaternion form.\n\
00235 \n\
00236 float64 x\n\
00237 float64 y\n\
00238 float64 z\n\
00239 float64 w\n\
00240 \n\
00241 ";
00242 }
00243
00244 static const char* value(const ::pixel_2_3d::Pixel23dResponse_<ContainerAllocator> &) { return value(); }
00245 };
00246
00247 }
00248 }
00249
00250 namespace ros
00251 {
00252 namespace serialization
00253 {
00254
00255 template<class ContainerAllocator> struct Serializer< ::pixel_2_3d::Pixel23dRequest_<ContainerAllocator> >
00256 {
00257 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00258 {
00259 stream.next(m.pixel_u);
00260 stream.next(m.pixel_v);
00261 }
00262
00263 ROS_DECLARE_ALLINONE_SERIALIZER;
00264 };
00265 }
00266 }
00267
00268
00269 namespace ros
00270 {
00271 namespace serialization
00272 {
00273
00274 template<class ContainerAllocator> struct Serializer< ::pixel_2_3d::Pixel23dResponse_<ContainerAllocator> >
00275 {
00276 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00277 {
00278 stream.next(m.pixel3d);
00279 stream.next(m.error_flag);
00280 }
00281
00282 ROS_DECLARE_ALLINONE_SERIALIZER;
00283 };
00284 }
00285 }
00286
00287 namespace ros
00288 {
00289 namespace service_traits
00290 {
00291 template<>
00292 struct MD5Sum<pixel_2_3d::Pixel23d> {
00293 static const char* value()
00294 {
00295 return "77d375efc96312100499b2b8d5091377";
00296 }
00297
00298 static const char* value(const pixel_2_3d::Pixel23d&) { return value(); }
00299 };
00300
00301 template<>
00302 struct DataType<pixel_2_3d::Pixel23d> {
00303 static const char* value()
00304 {
00305 return "pixel_2_3d/Pixel23d";
00306 }
00307
00308 static const char* value(const pixel_2_3d::Pixel23d&) { return value(); }
00309 };
00310
00311 template<class ContainerAllocator>
00312 struct MD5Sum<pixel_2_3d::Pixel23dRequest_<ContainerAllocator> > {
00313 static const char* value()
00314 {
00315 return "77d375efc96312100499b2b8d5091377";
00316 }
00317
00318 static const char* value(const pixel_2_3d::Pixel23dRequest_<ContainerAllocator> &) { return value(); }
00319 };
00320
00321 template<class ContainerAllocator>
00322 struct DataType<pixel_2_3d::Pixel23dRequest_<ContainerAllocator> > {
00323 static const char* value()
00324 {
00325 return "pixel_2_3d/Pixel23d";
00326 }
00327
00328 static const char* value(const pixel_2_3d::Pixel23dRequest_<ContainerAllocator> &) { return value(); }
00329 };
00330
00331 template<class ContainerAllocator>
00332 struct MD5Sum<pixel_2_3d::Pixel23dResponse_<ContainerAllocator> > {
00333 static const char* value()
00334 {
00335 return "77d375efc96312100499b2b8d5091377";
00336 }
00337
00338 static const char* value(const pixel_2_3d::Pixel23dResponse_<ContainerAllocator> &) { return value(); }
00339 };
00340
00341 template<class ContainerAllocator>
00342 struct DataType<pixel_2_3d::Pixel23dResponse_<ContainerAllocator> > {
00343 static const char* value()
00344 {
00345 return "pixel_2_3d/Pixel23d";
00346 }
00347
00348 static const char* value(const pixel_2_3d::Pixel23dResponse_<ContainerAllocator> &) { return value(); }
00349 };
00350
00351 }
00352 }
00353
00354 #endif // PIXEL_2_3D_SERVICE_PIXEL23D_H
00355