Go to the documentation of this file.00001
00002 #ifndef JSK_PERCEPTION_SERVICE_WHITEBALANCEPOINTS_H
00003 #define JSK_PERCEPTION_SERVICE_WHITEBALANCEPOINTS_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 "sensor_msgs/PointCloud2.h"
00020
00021
00022 #include "sensor_msgs/PointCloud2.h"
00023
00024 namespace jsk_perception
00025 {
00026 template <class ContainerAllocator>
00027 struct WhiteBalancePointsRequest_ {
00028 typedef WhiteBalancePointsRequest_<ContainerAllocator> Type;
00029
00030 WhiteBalancePointsRequest_()
00031 : reference_color()
00032 , input()
00033 {
00034 reference_color.assign(0.0);
00035 }
00036
00037 WhiteBalancePointsRequest_(const ContainerAllocator& _alloc)
00038 : reference_color()
00039 , input(_alloc)
00040 {
00041 reference_color.assign(0.0);
00042 }
00043
00044 typedef boost::array<float, 3> _reference_color_type;
00045 boost::array<float, 3> reference_color;
00046
00047 typedef ::sensor_msgs::PointCloud2_<ContainerAllocator> _input_type;
00048 ::sensor_msgs::PointCloud2_<ContainerAllocator> input;
00049
00050
00051 typedef boost::shared_ptr< ::jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> > Ptr;
00052 typedef boost::shared_ptr< ::jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> const> ConstPtr;
00053 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00054 };
00055 typedef ::jsk_perception::WhiteBalancePointsRequest_<std::allocator<void> > WhiteBalancePointsRequest;
00056
00057 typedef boost::shared_ptr< ::jsk_perception::WhiteBalancePointsRequest> WhiteBalancePointsRequestPtr;
00058 typedef boost::shared_ptr< ::jsk_perception::WhiteBalancePointsRequest const> WhiteBalancePointsRequestConstPtr;
00059
00060
00061 template <class ContainerAllocator>
00062 struct WhiteBalancePointsResponse_ {
00063 typedef WhiteBalancePointsResponse_<ContainerAllocator> Type;
00064
00065 WhiteBalancePointsResponse_()
00066 : output()
00067 {
00068 }
00069
00070 WhiteBalancePointsResponse_(const ContainerAllocator& _alloc)
00071 : output(_alloc)
00072 {
00073 }
00074
00075 typedef ::sensor_msgs::PointCloud2_<ContainerAllocator> _output_type;
00076 ::sensor_msgs::PointCloud2_<ContainerAllocator> output;
00077
00078
00079 typedef boost::shared_ptr< ::jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> > Ptr;
00080 typedef boost::shared_ptr< ::jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> const> ConstPtr;
00081 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00082 };
00083 typedef ::jsk_perception::WhiteBalancePointsResponse_<std::allocator<void> > WhiteBalancePointsResponse;
00084
00085 typedef boost::shared_ptr< ::jsk_perception::WhiteBalancePointsResponse> WhiteBalancePointsResponsePtr;
00086 typedef boost::shared_ptr< ::jsk_perception::WhiteBalancePointsResponse const> WhiteBalancePointsResponseConstPtr;
00087
00088 struct WhiteBalancePoints
00089 {
00090
00091 typedef WhiteBalancePointsRequest Request;
00092 typedef WhiteBalancePointsResponse Response;
00093 Request request;
00094 Response response;
00095
00096 typedef Request RequestType;
00097 typedef Response ResponseType;
00098 };
00099 }
00100
00101 namespace ros
00102 {
00103 namespace message_traits
00104 {
00105 template<class ContainerAllocator> struct IsMessage< ::jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> > : public TrueType {};
00106 template<class ContainerAllocator> struct IsMessage< ::jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> const> : public TrueType {};
00107 template<class ContainerAllocator>
00108 struct MD5Sum< ::jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> > {
00109 static const char* value()
00110 {
00111 return "c114e8c81fa040c23390d86cd0cb8e3a";
00112 }
00113
00114 static const char* value(const ::jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> &) { return value(); }
00115 static const uint64_t static_value1 = 0xc114e8c81fa040c2ULL;
00116 static const uint64_t static_value2 = 0x3390d86cd0cb8e3aULL;
00117 };
00118
00119 template<class ContainerAllocator>
00120 struct DataType< ::jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> > {
00121 static const char* value()
00122 {
00123 return "jsk_perception/WhiteBalancePointsRequest";
00124 }
00125
00126 static const char* value(const ::jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> &) { return value(); }
00127 };
00128
00129 template<class ContainerAllocator>
00130 struct Definition< ::jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> > {
00131 static const char* value()
00132 {
00133 return "float32[3] reference_color\n\
00134 sensor_msgs/PointCloud2 input\n\
00135 \n\
00136 ================================================================================\n\
00137 MSG: sensor_msgs/PointCloud2\n\
00138 # This message holds a collection of N-dimensional points, which may\n\
00139 # contain additional information such as normals, intensity, etc. The\n\
00140 # point data is stored as a binary blob, its layout described by the\n\
00141 # contents of the \"fields\" array.\n\
00142 \n\
00143 # The point cloud data may be organized 2d (image-like) or 1d\n\
00144 # (unordered). Point clouds organized as 2d images may be produced by\n\
00145 # camera depth sensors such as stereo or time-of-flight.\n\
00146 \n\
00147 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\
00148 # points).\n\
00149 Header header\n\
00150 \n\
00151 # 2D structure of the point cloud. If the cloud is unordered, height is\n\
00152 # 1 and width is the length of the point cloud.\n\
00153 uint32 height\n\
00154 uint32 width\n\
00155 \n\
00156 # Describes the channels and their layout in the binary data blob.\n\
00157 PointField[] fields\n\
00158 \n\
00159 bool is_bigendian # Is this data bigendian?\n\
00160 uint32 point_step # Length of a point in bytes\n\
00161 uint32 row_step # Length of a row in bytes\n\
00162 uint8[] data # Actual point data, size is (row_step*height)\n\
00163 \n\
00164 bool is_dense # True if there are no invalid points\n\
00165 \n\
00166 ================================================================================\n\
00167 MSG: std_msgs/Header\n\
00168 # Standard metadata for higher-level stamped data types.\n\
00169 # This is generally used to communicate timestamped data \n\
00170 # in a particular coordinate frame.\n\
00171 # \n\
00172 # sequence ID: consecutively increasing ID \n\
00173 uint32 seq\n\
00174 #Two-integer timestamp that is expressed as:\n\
00175 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00176 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00177 # time-handling sugar is provided by the client library\n\
00178 time stamp\n\
00179 #Frame this data is associated with\n\
00180 # 0: no frame\n\
00181 # 1: global frame\n\
00182 string frame_id\n\
00183 \n\
00184 ================================================================================\n\
00185 MSG: sensor_msgs/PointField\n\
00186 # This message holds the description of one point entry in the\n\
00187 # PointCloud2 message format.\n\
00188 uint8 INT8 = 1\n\
00189 uint8 UINT8 = 2\n\
00190 uint8 INT16 = 3\n\
00191 uint8 UINT16 = 4\n\
00192 uint8 INT32 = 5\n\
00193 uint8 UINT32 = 6\n\
00194 uint8 FLOAT32 = 7\n\
00195 uint8 FLOAT64 = 8\n\
00196 \n\
00197 string name # Name of field\n\
00198 uint32 offset # Offset from start of point struct\n\
00199 uint8 datatype # Datatype enumeration, see above\n\
00200 uint32 count # How many elements in the field\n\
00201 \n\
00202 ";
00203 }
00204
00205 static const char* value(const ::jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> &) { return value(); }
00206 };
00207
00208 }
00209 }
00210
00211
00212 namespace ros
00213 {
00214 namespace message_traits
00215 {
00216 template<class ContainerAllocator> struct IsMessage< ::jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> > : public TrueType {};
00217 template<class ContainerAllocator> struct IsMessage< ::jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> const> : public TrueType {};
00218 template<class ContainerAllocator>
00219 struct MD5Sum< ::jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> > {
00220 static const char* value()
00221 {
00222 return "6db5ac8d8316fdb3e0c62197115f87cd";
00223 }
00224
00225 static const char* value(const ::jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> &) { return value(); }
00226 static const uint64_t static_value1 = 0x6db5ac8d8316fdb3ULL;
00227 static const uint64_t static_value2 = 0xe0c62197115f87cdULL;
00228 };
00229
00230 template<class ContainerAllocator>
00231 struct DataType< ::jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> > {
00232 static const char* value()
00233 {
00234 return "jsk_perception/WhiteBalancePointsResponse";
00235 }
00236
00237 static const char* value(const ::jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> &) { return value(); }
00238 };
00239
00240 template<class ContainerAllocator>
00241 struct Definition< ::jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> > {
00242 static const char* value()
00243 {
00244 return "sensor_msgs/PointCloud2 output\n\
00245 \n\
00246 \n\
00247 ================================================================================\n\
00248 MSG: sensor_msgs/PointCloud2\n\
00249 # This message holds a collection of N-dimensional points, which may\n\
00250 # contain additional information such as normals, intensity, etc. The\n\
00251 # point data is stored as a binary blob, its layout described by the\n\
00252 # contents of the \"fields\" array.\n\
00253 \n\
00254 # The point cloud data may be organized 2d (image-like) or 1d\n\
00255 # (unordered). Point clouds organized as 2d images may be produced by\n\
00256 # camera depth sensors such as stereo or time-of-flight.\n\
00257 \n\
00258 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\
00259 # points).\n\
00260 Header header\n\
00261 \n\
00262 # 2D structure of the point cloud. If the cloud is unordered, height is\n\
00263 # 1 and width is the length of the point cloud.\n\
00264 uint32 height\n\
00265 uint32 width\n\
00266 \n\
00267 # Describes the channels and their layout in the binary data blob.\n\
00268 PointField[] fields\n\
00269 \n\
00270 bool is_bigendian # Is this data bigendian?\n\
00271 uint32 point_step # Length of a point in bytes\n\
00272 uint32 row_step # Length of a row in bytes\n\
00273 uint8[] data # Actual point data, size is (row_step*height)\n\
00274 \n\
00275 bool is_dense # True if there are no invalid points\n\
00276 \n\
00277 ================================================================================\n\
00278 MSG: std_msgs/Header\n\
00279 # Standard metadata for higher-level stamped data types.\n\
00280 # This is generally used to communicate timestamped data \n\
00281 # in a particular coordinate frame.\n\
00282 # \n\
00283 # sequence ID: consecutively increasing ID \n\
00284 uint32 seq\n\
00285 #Two-integer timestamp that is expressed as:\n\
00286 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00287 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00288 # time-handling sugar is provided by the client library\n\
00289 time stamp\n\
00290 #Frame this data is associated with\n\
00291 # 0: no frame\n\
00292 # 1: global frame\n\
00293 string frame_id\n\
00294 \n\
00295 ================================================================================\n\
00296 MSG: sensor_msgs/PointField\n\
00297 # This message holds the description of one point entry in the\n\
00298 # PointCloud2 message format.\n\
00299 uint8 INT8 = 1\n\
00300 uint8 UINT8 = 2\n\
00301 uint8 INT16 = 3\n\
00302 uint8 UINT16 = 4\n\
00303 uint8 INT32 = 5\n\
00304 uint8 UINT32 = 6\n\
00305 uint8 FLOAT32 = 7\n\
00306 uint8 FLOAT64 = 8\n\
00307 \n\
00308 string name # Name of field\n\
00309 uint32 offset # Offset from start of point struct\n\
00310 uint8 datatype # Datatype enumeration, see above\n\
00311 uint32 count # How many elements in the field\n\
00312 \n\
00313 ";
00314 }
00315
00316 static const char* value(const ::jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> &) { return value(); }
00317 };
00318
00319 }
00320 }
00321
00322 namespace ros
00323 {
00324 namespace serialization
00325 {
00326
00327 template<class ContainerAllocator> struct Serializer< ::jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> >
00328 {
00329 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00330 {
00331 stream.next(m.reference_color);
00332 stream.next(m.input);
00333 }
00334
00335 ROS_DECLARE_ALLINONE_SERIALIZER;
00336 };
00337 }
00338 }
00339
00340
00341 namespace ros
00342 {
00343 namespace serialization
00344 {
00345
00346 template<class ContainerAllocator> struct Serializer< ::jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> >
00347 {
00348 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00349 {
00350 stream.next(m.output);
00351 }
00352
00353 ROS_DECLARE_ALLINONE_SERIALIZER;
00354 };
00355 }
00356 }
00357
00358 namespace ros
00359 {
00360 namespace service_traits
00361 {
00362 template<>
00363 struct MD5Sum<jsk_perception::WhiteBalancePoints> {
00364 static const char* value()
00365 {
00366 return "6f5674d9dbb4051d4ed08afdf5be7566";
00367 }
00368
00369 static const char* value(const jsk_perception::WhiteBalancePoints&) { return value(); }
00370 };
00371
00372 template<>
00373 struct DataType<jsk_perception::WhiteBalancePoints> {
00374 static const char* value()
00375 {
00376 return "jsk_perception/WhiteBalancePoints";
00377 }
00378
00379 static const char* value(const jsk_perception::WhiteBalancePoints&) { return value(); }
00380 };
00381
00382 template<class ContainerAllocator>
00383 struct MD5Sum<jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> > {
00384 static const char* value()
00385 {
00386 return "6f5674d9dbb4051d4ed08afdf5be7566";
00387 }
00388
00389 static const char* value(const jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> &) { return value(); }
00390 };
00391
00392 template<class ContainerAllocator>
00393 struct DataType<jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> > {
00394 static const char* value()
00395 {
00396 return "jsk_perception/WhiteBalancePoints";
00397 }
00398
00399 static const char* value(const jsk_perception::WhiteBalancePointsRequest_<ContainerAllocator> &) { return value(); }
00400 };
00401
00402 template<class ContainerAllocator>
00403 struct MD5Sum<jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> > {
00404 static const char* value()
00405 {
00406 return "6f5674d9dbb4051d4ed08afdf5be7566";
00407 }
00408
00409 static const char* value(const jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> &) { return value(); }
00410 };
00411
00412 template<class ContainerAllocator>
00413 struct DataType<jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> > {
00414 static const char* value()
00415 {
00416 return "jsk_perception/WhiteBalancePoints";
00417 }
00418
00419 static const char* value(const jsk_perception::WhiteBalancePointsResponse_<ContainerAllocator> &) { return value(); }
00420 };
00421
00422 }
00423 }
00424
00425 #endif // JSK_PERCEPTION_SERVICE_WHITEBALANCEPOINTS_H
00426