Go to the documentation of this file.00001
00002 #ifndef KINECT_DEPTH_CALIBRATION_SERVICE_GETCHECKERBOARDPOSE_H
00003 #define KINECT_DEPTH_CALIBRATION_SERVICE_GETCHECKERBOARDPOSE_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 kinect_depth_calibration
00024 {
00025 template <class ContainerAllocator>
00026 struct GetCheckerboardPoseRequest_ {
00027 typedef GetCheckerboardPoseRequest_<ContainerAllocator> Type;
00028
00029 GetCheckerboardPoseRequest_()
00030 : corners_x(0)
00031 , corners_y(0)
00032 , spacing_x(0.0)
00033 , spacing_y(0.0)
00034 {
00035 }
00036
00037 GetCheckerboardPoseRequest_(const ContainerAllocator& _alloc)
00038 : corners_x(0)
00039 , corners_y(0)
00040 , spacing_x(0.0)
00041 , spacing_y(0.0)
00042 {
00043 }
00044
00045 typedef int32_t _corners_x_type;
00046 int32_t corners_x;
00047
00048 typedef int32_t _corners_y_type;
00049 int32_t corners_y;
00050
00051 typedef float _spacing_x_type;
00052 float spacing_x;
00053
00054 typedef float _spacing_y_type;
00055 float spacing_y;
00056
00057
00058 typedef boost::shared_ptr< ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> > Ptr;
00059 typedef boost::shared_ptr< ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> const> ConstPtr;
00060 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00061 };
00062 typedef ::kinect_depth_calibration::GetCheckerboardPoseRequest_<std::allocator<void> > GetCheckerboardPoseRequest;
00063
00064 typedef boost::shared_ptr< ::kinect_depth_calibration::GetCheckerboardPoseRequest> GetCheckerboardPoseRequestPtr;
00065 typedef boost::shared_ptr< ::kinect_depth_calibration::GetCheckerboardPoseRequest const> GetCheckerboardPoseRequestConstPtr;
00066
00067
00068 template <class ContainerAllocator>
00069 struct GetCheckerboardPoseResponse_ {
00070 typedef GetCheckerboardPoseResponse_<ContainerAllocator> Type;
00071
00072 GetCheckerboardPoseResponse_()
00073 : board_pose()
00074 , min_x(0.0)
00075 , max_x(0.0)
00076 , min_y(0.0)
00077 , max_y(0.0)
00078 , noise_vel(0.0)
00079 , noise_rot(0.0)
00080 {
00081 }
00082
00083 GetCheckerboardPoseResponse_(const ContainerAllocator& _alloc)
00084 : board_pose(_alloc)
00085 , min_x(0.0)
00086 , max_x(0.0)
00087 , min_y(0.0)
00088 , max_y(0.0)
00089 , noise_vel(0.0)
00090 , noise_rot(0.0)
00091 {
00092 }
00093
00094 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _board_pose_type;
00095 ::geometry_msgs::PoseStamped_<ContainerAllocator> board_pose;
00096
00097 typedef float _min_x_type;
00098 float min_x;
00099
00100 typedef float _max_x_type;
00101 float max_x;
00102
00103 typedef float _min_y_type;
00104 float min_y;
00105
00106 typedef float _max_y_type;
00107 float max_y;
00108
00109 typedef float _noise_vel_type;
00110 float noise_vel;
00111
00112 typedef float _noise_rot_type;
00113 float noise_rot;
00114
00115
00116 typedef boost::shared_ptr< ::kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> > Ptr;
00117 typedef boost::shared_ptr< ::kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> const> ConstPtr;
00118 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00119 };
00120 typedef ::kinect_depth_calibration::GetCheckerboardPoseResponse_<std::allocator<void> > GetCheckerboardPoseResponse;
00121
00122 typedef boost::shared_ptr< ::kinect_depth_calibration::GetCheckerboardPoseResponse> GetCheckerboardPoseResponsePtr;
00123 typedef boost::shared_ptr< ::kinect_depth_calibration::GetCheckerboardPoseResponse const> GetCheckerboardPoseResponseConstPtr;
00124
00125 struct GetCheckerboardPose
00126 {
00127
00128 typedef GetCheckerboardPoseRequest Request;
00129 typedef GetCheckerboardPoseResponse Response;
00130 Request request;
00131 Response response;
00132
00133 typedef Request RequestType;
00134 typedef Response ResponseType;
00135 };
00136 }
00137
00138 namespace ros
00139 {
00140 namespace message_traits
00141 {
00142 template<class ContainerAllocator> struct IsMessage< ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> > : public TrueType {};
00143 template<class ContainerAllocator> struct IsMessage< ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> const> : public TrueType {};
00144 template<class ContainerAllocator>
00145 struct MD5Sum< ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> > {
00146 static const char* value()
00147 {
00148 return "f9dc7d7f2c73b6a404e26f1d03ad4ec2";
00149 }
00150
00151 static const char* value(const ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> &) { return value(); }
00152 static const uint64_t static_value1 = 0xf9dc7d7f2c73b6a4ULL;
00153 static const uint64_t static_value2 = 0x04e26f1d03ad4ec2ULL;
00154 };
00155
00156 template<class ContainerAllocator>
00157 struct DataType< ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> > {
00158 static const char* value()
00159 {
00160 return "kinect_depth_calibration/GetCheckerboardPoseRequest";
00161 }
00162
00163 static const char* value(const ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> &) { return value(); }
00164 };
00165
00166 template<class ContainerAllocator>
00167 struct Definition< ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> > {
00168 static const char* value()
00169 {
00170 return "int32 corners_x\n\
00171 int32 corners_y\n\
00172 float32 spacing_x\n\
00173 float32 spacing_y\n\
00174 \n\
00175 ";
00176 }
00177
00178 static const char* value(const ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> &) { return value(); }
00179 };
00180
00181 template<class ContainerAllocator> struct IsFixedSize< ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> > : public TrueType {};
00182 }
00183 }
00184
00185
00186 namespace ros
00187 {
00188 namespace message_traits
00189 {
00190 template<class ContainerAllocator> struct IsMessage< ::kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> > : public TrueType {};
00191 template<class ContainerAllocator> struct IsMessage< ::kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> const> : public TrueType {};
00192 template<class ContainerAllocator>
00193 struct MD5Sum< ::kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> > {
00194 static const char* value()
00195 {
00196 return "f2e4d5e733b7a98672707e8a53a68cd4";
00197 }
00198
00199 static const char* value(const ::kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> &) { return value(); }
00200 static const uint64_t static_value1 = 0xf2e4d5e733b7a986ULL;
00201 static const uint64_t static_value2 = 0x72707e8a53a68cd4ULL;
00202 };
00203
00204 template<class ContainerAllocator>
00205 struct DataType< ::kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> > {
00206 static const char* value()
00207 {
00208 return "kinect_depth_calibration/GetCheckerboardPoseResponse";
00209 }
00210
00211 static const char* value(const ::kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> &) { return value(); }
00212 };
00213
00214 template<class ContainerAllocator>
00215 struct Definition< ::kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> > {
00216 static const char* value()
00217 {
00218 return "geometry_msgs/PoseStamped board_pose\n\
00219 float32 min_x\n\
00220 float32 max_x\n\
00221 float32 min_y\n\
00222 float32 max_y\n\
00223 float32 noise_vel\n\
00224 float32 noise_rot\n\
00225 \n\
00226 ================================================================================\n\
00227 MSG: geometry_msgs/PoseStamped\n\
00228 # A Pose with reference coordinate frame and timestamp\n\
00229 Header header\n\
00230 Pose pose\n\
00231 \n\
00232 ================================================================================\n\
00233 MSG: std_msgs/Header\n\
00234 # Standard metadata for higher-level stamped data types.\n\
00235 # This is generally used to communicate timestamped data \n\
00236 # in a particular coordinate frame.\n\
00237 # \n\
00238 # sequence ID: consecutively increasing ID \n\
00239 uint32 seq\n\
00240 #Two-integer timestamp that is expressed as:\n\
00241 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00242 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00243 # time-handling sugar is provided by the client library\n\
00244 time stamp\n\
00245 #Frame this data is associated with\n\
00246 # 0: no frame\n\
00247 # 1: global frame\n\
00248 string frame_id\n\
00249 \n\
00250 ================================================================================\n\
00251 MSG: geometry_msgs/Pose\n\
00252 # A representation of pose in free space, composed of postion and orientation. \n\
00253 Point position\n\
00254 Quaternion orientation\n\
00255 \n\
00256 ================================================================================\n\
00257 MSG: geometry_msgs/Point\n\
00258 # This contains the position of a point in free space\n\
00259 float64 x\n\
00260 float64 y\n\
00261 float64 z\n\
00262 \n\
00263 ================================================================================\n\
00264 MSG: geometry_msgs/Quaternion\n\
00265 # This represents an orientation in free space in quaternion form.\n\
00266 \n\
00267 float64 x\n\
00268 float64 y\n\
00269 float64 z\n\
00270 float64 w\n\
00271 \n\
00272 ";
00273 }
00274
00275 static const char* value(const ::kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> &) { return value(); }
00276 };
00277
00278 }
00279 }
00280
00281 namespace ros
00282 {
00283 namespace serialization
00284 {
00285
00286 template<class ContainerAllocator> struct Serializer< ::kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> >
00287 {
00288 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00289 {
00290 stream.next(m.corners_x);
00291 stream.next(m.corners_y);
00292 stream.next(m.spacing_x);
00293 stream.next(m.spacing_y);
00294 }
00295
00296 ROS_DECLARE_ALLINONE_SERIALIZER;
00297 };
00298 }
00299 }
00300
00301
00302 namespace ros
00303 {
00304 namespace serialization
00305 {
00306
00307 template<class ContainerAllocator> struct Serializer< ::kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> >
00308 {
00309 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00310 {
00311 stream.next(m.board_pose);
00312 stream.next(m.min_x);
00313 stream.next(m.max_x);
00314 stream.next(m.min_y);
00315 stream.next(m.max_y);
00316 stream.next(m.noise_vel);
00317 stream.next(m.noise_rot);
00318 }
00319
00320 ROS_DECLARE_ALLINONE_SERIALIZER;
00321 };
00322 }
00323 }
00324
00325 namespace ros
00326 {
00327 namespace service_traits
00328 {
00329 template<>
00330 struct MD5Sum<kinect_depth_calibration::GetCheckerboardPose> {
00331 static const char* value()
00332 {
00333 return "f515725e9bae2b07fb95aab5c6865589";
00334 }
00335
00336 static const char* value(const kinect_depth_calibration::GetCheckerboardPose&) { return value(); }
00337 };
00338
00339 template<>
00340 struct DataType<kinect_depth_calibration::GetCheckerboardPose> {
00341 static const char* value()
00342 {
00343 return "kinect_depth_calibration/GetCheckerboardPose";
00344 }
00345
00346 static const char* value(const kinect_depth_calibration::GetCheckerboardPose&) { return value(); }
00347 };
00348
00349 template<class ContainerAllocator>
00350 struct MD5Sum<kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> > {
00351 static const char* value()
00352 {
00353 return "f515725e9bae2b07fb95aab5c6865589";
00354 }
00355
00356 static const char* value(const kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> &) { return value(); }
00357 };
00358
00359 template<class ContainerAllocator>
00360 struct DataType<kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> > {
00361 static const char* value()
00362 {
00363 return "kinect_depth_calibration/GetCheckerboardPose";
00364 }
00365
00366 static const char* value(const kinect_depth_calibration::GetCheckerboardPoseRequest_<ContainerAllocator> &) { return value(); }
00367 };
00368
00369 template<class ContainerAllocator>
00370 struct MD5Sum<kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> > {
00371 static const char* value()
00372 {
00373 return "f515725e9bae2b07fb95aab5c6865589";
00374 }
00375
00376 static const char* value(const kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> &) { return value(); }
00377 };
00378
00379 template<class ContainerAllocator>
00380 struct DataType<kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> > {
00381 static const char* value()
00382 {
00383 return "kinect_depth_calibration/GetCheckerboardPose";
00384 }
00385
00386 static const char* value(const kinect_depth_calibration::GetCheckerboardPoseResponse_<ContainerAllocator> &) { return value(); }
00387 };
00388
00389 }
00390 }
00391
00392 #endif // KINECT_DEPTH_CALIBRATION_SERVICE_GETCHECKERBOARDPOSE_H
00393