$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-laser_pipeline/doc_stacks/2013-03-01_15-57-12.978425/laser_pipeline/laser_assembler/srv/AssembleScans.srv */ 00002 #ifndef LASER_ASSEMBLER_SERVICE_ASSEMBLESCANS_H 00003 #define LASER_ASSEMBLER_SERVICE_ASSEMBLESCANS_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 "sensor_msgs/PointCloud.h" 00022 00023 namespace laser_assembler 00024 { 00025 template <class ContainerAllocator> 00026 struct AssembleScansRequest_ { 00027 typedef AssembleScansRequest_<ContainerAllocator> Type; 00028 00029 AssembleScansRequest_() 00030 : begin() 00031 , end() 00032 { 00033 } 00034 00035 AssembleScansRequest_(const ContainerAllocator& _alloc) 00036 : begin() 00037 , end() 00038 { 00039 } 00040 00041 typedef ros::Time _begin_type; 00042 ros::Time begin; 00043 00044 typedef ros::Time _end_type; 00045 ros::Time end; 00046 00047 00048 private: 00049 static const char* __s_getDataType_() { return "laser_assembler/AssembleScansRequest"; } 00050 public: 00051 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00052 00053 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00054 00055 private: 00056 static const char* __s_getMD5Sum_() { return "b341004f74e15bf5e1b2053a9183bdc7"; } 00057 public: 00058 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00059 00060 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00061 00062 private: 00063 static const char* __s_getServerMD5Sum_() { return "6d5cec00dca23821eae6bd7449078aa7"; } 00064 public: 00065 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00066 00067 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00068 00069 private: 00070 static const char* __s_getMessageDefinition_() { return "\n\ 00071 time begin\n\ 00072 \n\ 00073 time end\n\ 00074 \n\ 00075 "; } 00076 public: 00077 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00078 00079 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00080 00081 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00082 { 00083 ros::serialization::OStream stream(write_ptr, 1000000000); 00084 ros::serialization::serialize(stream, begin); 00085 ros::serialization::serialize(stream, end); 00086 return stream.getData(); 00087 } 00088 00089 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00090 { 00091 ros::serialization::IStream stream(read_ptr, 1000000000); 00092 ros::serialization::deserialize(stream, begin); 00093 ros::serialization::deserialize(stream, end); 00094 return stream.getData(); 00095 } 00096 00097 ROS_DEPRECATED virtual uint32_t serializationLength() const 00098 { 00099 uint32_t size = 0; 00100 size += ros::serialization::serializationLength(begin); 00101 size += ros::serialization::serializationLength(end); 00102 return size; 00103 } 00104 00105 typedef boost::shared_ptr< ::laser_assembler::AssembleScansRequest_<ContainerAllocator> > Ptr; 00106 typedef boost::shared_ptr< ::laser_assembler::AssembleScansRequest_<ContainerAllocator> const> ConstPtr; 00107 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00108 }; // struct AssembleScansRequest 00109 typedef ::laser_assembler::AssembleScansRequest_<std::allocator<void> > AssembleScansRequest; 00110 00111 typedef boost::shared_ptr< ::laser_assembler::AssembleScansRequest> AssembleScansRequestPtr; 00112 typedef boost::shared_ptr< ::laser_assembler::AssembleScansRequest const> AssembleScansRequestConstPtr; 00113 00114 00115 template <class ContainerAllocator> 00116 struct AssembleScansResponse_ { 00117 typedef AssembleScansResponse_<ContainerAllocator> Type; 00118 00119 AssembleScansResponse_() 00120 : cloud() 00121 { 00122 } 00123 00124 AssembleScansResponse_(const ContainerAllocator& _alloc) 00125 : cloud(_alloc) 00126 { 00127 } 00128 00129 typedef ::sensor_msgs::PointCloud_<ContainerAllocator> _cloud_type; 00130 ::sensor_msgs::PointCloud_<ContainerAllocator> cloud; 00131 00132 00133 private: 00134 static const char* __s_getDataType_() { return "laser_assembler/AssembleScansResponse"; } 00135 public: 00136 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00137 00138 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00139 00140 private: 00141 static const char* __s_getMD5Sum_() { return "4217b28a903e4ad7869a83b3653110ff"; } 00142 public: 00143 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00144 00145 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00146 00147 private: 00148 static const char* __s_getServerMD5Sum_() { return "6d5cec00dca23821eae6bd7449078aa7"; } 00149 public: 00150 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00151 00152 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00153 00154 private: 00155 static const char* __s_getMessageDefinition_() { return "\n\ 00156 \n\ 00157 \n\ 00158 sensor_msgs/PointCloud cloud\n\ 00159 \n\ 00160 \n\ 00161 ================================================================================\n\ 00162 MSG: sensor_msgs/PointCloud\n\ 00163 # This message holds a collection of 3d points, plus optional additional\n\ 00164 # information about each point.\n\ 00165 \n\ 00166 # Time of sensor data acquisition, coordinate frame ID.\n\ 00167 Header header\n\ 00168 \n\ 00169 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\ 00170 # in the frame given in the header.\n\ 00171 geometry_msgs/Point32[] points\n\ 00172 \n\ 00173 # Each channel should have the same number of elements as points array,\n\ 00174 # and the data in each channel should correspond 1:1 with each point.\n\ 00175 # Channel names in common practice are listed in ChannelFloat32.msg.\n\ 00176 ChannelFloat32[] channels\n\ 00177 \n\ 00178 ================================================================================\n\ 00179 MSG: std_msgs/Header\n\ 00180 # Standard metadata for higher-level stamped data types.\n\ 00181 # This is generally used to communicate timestamped data \n\ 00182 # in a particular coordinate frame.\n\ 00183 # \n\ 00184 # sequence ID: consecutively increasing ID \n\ 00185 uint32 seq\n\ 00186 #Two-integer timestamp that is expressed as:\n\ 00187 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00188 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00189 # time-handling sugar is provided by the client library\n\ 00190 time stamp\n\ 00191 #Frame this data is associated with\n\ 00192 # 0: no frame\n\ 00193 # 1: global frame\n\ 00194 string frame_id\n\ 00195 \n\ 00196 ================================================================================\n\ 00197 MSG: geometry_msgs/Point32\n\ 00198 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00199 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00200 # \n\ 00201 # This recommendation is to promote interoperability. \n\ 00202 #\n\ 00203 # This message is designed to take up less space when sending\n\ 00204 # lots of points at once, as in the case of a PointCloud. \n\ 00205 \n\ 00206 float32 x\n\ 00207 float32 y\n\ 00208 float32 z\n\ 00209 ================================================================================\n\ 00210 MSG: sensor_msgs/ChannelFloat32\n\ 00211 # This message is used by the PointCloud message to hold optional data\n\ 00212 # associated with each point in the cloud. The length of the values\n\ 00213 # array should be the same as the length of the points array in the\n\ 00214 # PointCloud, and each value should be associated with the corresponding\n\ 00215 # point.\n\ 00216 \n\ 00217 # Channel names in existing practice include:\n\ 00218 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\ 00219 # This is opposite to usual conventions but remains for\n\ 00220 # historical reasons. The newer PointCloud2 message has no\n\ 00221 # such problem.\n\ 00222 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\ 00223 # (R,G,B) values packed into the least significant 24 bits,\n\ 00224 # in order.\n\ 00225 # \"intensity\" - laser or pixel intensity.\n\ 00226 # \"distance\"\n\ 00227 \n\ 00228 # The channel name should give semantics of the channel (e.g.\n\ 00229 # \"intensity\" instead of \"value\").\n\ 00230 string name\n\ 00231 \n\ 00232 # The values array should be 1-1 with the elements of the associated\n\ 00233 # PointCloud.\n\ 00234 float32[] values\n\ 00235 \n\ 00236 "; } 00237 public: 00238 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00239 00240 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00241 00242 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00243 { 00244 ros::serialization::OStream stream(write_ptr, 1000000000); 00245 ros::serialization::serialize(stream, cloud); 00246 return stream.getData(); 00247 } 00248 00249 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00250 { 00251 ros::serialization::IStream stream(read_ptr, 1000000000); 00252 ros::serialization::deserialize(stream, cloud); 00253 return stream.getData(); 00254 } 00255 00256 ROS_DEPRECATED virtual uint32_t serializationLength() const 00257 { 00258 uint32_t size = 0; 00259 size += ros::serialization::serializationLength(cloud); 00260 return size; 00261 } 00262 00263 typedef boost::shared_ptr< ::laser_assembler::AssembleScansResponse_<ContainerAllocator> > Ptr; 00264 typedef boost::shared_ptr< ::laser_assembler::AssembleScansResponse_<ContainerAllocator> const> ConstPtr; 00265 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00266 }; // struct AssembleScansResponse 00267 typedef ::laser_assembler::AssembleScansResponse_<std::allocator<void> > AssembleScansResponse; 00268 00269 typedef boost::shared_ptr< ::laser_assembler::AssembleScansResponse> AssembleScansResponsePtr; 00270 typedef boost::shared_ptr< ::laser_assembler::AssembleScansResponse const> AssembleScansResponseConstPtr; 00271 00272 struct AssembleScans 00273 { 00274 00275 typedef AssembleScansRequest Request; 00276 typedef AssembleScansResponse Response; 00277 Request request; 00278 Response response; 00279 00280 typedef Request RequestType; 00281 typedef Response ResponseType; 00282 }; // struct AssembleScans 00283 } // namespace laser_assembler 00284 00285 namespace ros 00286 { 00287 namespace message_traits 00288 { 00289 template<class ContainerAllocator> struct IsMessage< ::laser_assembler::AssembleScansRequest_<ContainerAllocator> > : public TrueType {}; 00290 template<class ContainerAllocator> struct IsMessage< ::laser_assembler::AssembleScansRequest_<ContainerAllocator> const> : public TrueType {}; 00291 template<class ContainerAllocator> 00292 struct MD5Sum< ::laser_assembler::AssembleScansRequest_<ContainerAllocator> > { 00293 static const char* value() 00294 { 00295 return "b341004f74e15bf5e1b2053a9183bdc7"; 00296 } 00297 00298 static const char* value(const ::laser_assembler::AssembleScansRequest_<ContainerAllocator> &) { return value(); } 00299 static const uint64_t static_value1 = 0xb341004f74e15bf5ULL; 00300 static const uint64_t static_value2 = 0xe1b2053a9183bdc7ULL; 00301 }; 00302 00303 template<class ContainerAllocator> 00304 struct DataType< ::laser_assembler::AssembleScansRequest_<ContainerAllocator> > { 00305 static const char* value() 00306 { 00307 return "laser_assembler/AssembleScansRequest"; 00308 } 00309 00310 static const char* value(const ::laser_assembler::AssembleScansRequest_<ContainerAllocator> &) { return value(); } 00311 }; 00312 00313 template<class ContainerAllocator> 00314 struct Definition< ::laser_assembler::AssembleScansRequest_<ContainerAllocator> > { 00315 static const char* value() 00316 { 00317 return "\n\ 00318 time begin\n\ 00319 \n\ 00320 time end\n\ 00321 \n\ 00322 "; 00323 } 00324 00325 static const char* value(const ::laser_assembler::AssembleScansRequest_<ContainerAllocator> &) { return value(); } 00326 }; 00327 00328 template<class ContainerAllocator> struct IsFixedSize< ::laser_assembler::AssembleScansRequest_<ContainerAllocator> > : public TrueType {}; 00329 } // namespace message_traits 00330 } // namespace ros 00331 00332 00333 namespace ros 00334 { 00335 namespace message_traits 00336 { 00337 template<class ContainerAllocator> struct IsMessage< ::laser_assembler::AssembleScansResponse_<ContainerAllocator> > : public TrueType {}; 00338 template<class ContainerAllocator> struct IsMessage< ::laser_assembler::AssembleScansResponse_<ContainerAllocator> const> : public TrueType {}; 00339 template<class ContainerAllocator> 00340 struct MD5Sum< ::laser_assembler::AssembleScansResponse_<ContainerAllocator> > { 00341 static const char* value() 00342 { 00343 return "4217b28a903e4ad7869a83b3653110ff"; 00344 } 00345 00346 static const char* value(const ::laser_assembler::AssembleScansResponse_<ContainerAllocator> &) { return value(); } 00347 static const uint64_t static_value1 = 0x4217b28a903e4ad7ULL; 00348 static const uint64_t static_value2 = 0x869a83b3653110ffULL; 00349 }; 00350 00351 template<class ContainerAllocator> 00352 struct DataType< ::laser_assembler::AssembleScansResponse_<ContainerAllocator> > { 00353 static const char* value() 00354 { 00355 return "laser_assembler/AssembleScansResponse"; 00356 } 00357 00358 static const char* value(const ::laser_assembler::AssembleScansResponse_<ContainerAllocator> &) { return value(); } 00359 }; 00360 00361 template<class ContainerAllocator> 00362 struct Definition< ::laser_assembler::AssembleScansResponse_<ContainerAllocator> > { 00363 static const char* value() 00364 { 00365 return "\n\ 00366 \n\ 00367 \n\ 00368 sensor_msgs/PointCloud cloud\n\ 00369 \n\ 00370 \n\ 00371 ================================================================================\n\ 00372 MSG: sensor_msgs/PointCloud\n\ 00373 # This message holds a collection of 3d points, plus optional additional\n\ 00374 # information about each point.\n\ 00375 \n\ 00376 # Time of sensor data acquisition, coordinate frame ID.\n\ 00377 Header header\n\ 00378 \n\ 00379 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\ 00380 # in the frame given in the header.\n\ 00381 geometry_msgs/Point32[] points\n\ 00382 \n\ 00383 # Each channel should have the same number of elements as points array,\n\ 00384 # and the data in each channel should correspond 1:1 with each point.\n\ 00385 # Channel names in common practice are listed in ChannelFloat32.msg.\n\ 00386 ChannelFloat32[] channels\n\ 00387 \n\ 00388 ================================================================================\n\ 00389 MSG: std_msgs/Header\n\ 00390 # Standard metadata for higher-level stamped data types.\n\ 00391 # This is generally used to communicate timestamped data \n\ 00392 # in a particular coordinate frame.\n\ 00393 # \n\ 00394 # sequence ID: consecutively increasing ID \n\ 00395 uint32 seq\n\ 00396 #Two-integer timestamp that is expressed as:\n\ 00397 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00398 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00399 # time-handling sugar is provided by the client library\n\ 00400 time stamp\n\ 00401 #Frame this data is associated with\n\ 00402 # 0: no frame\n\ 00403 # 1: global frame\n\ 00404 string frame_id\n\ 00405 \n\ 00406 ================================================================================\n\ 00407 MSG: geometry_msgs/Point32\n\ 00408 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00409 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00410 # \n\ 00411 # This recommendation is to promote interoperability. \n\ 00412 #\n\ 00413 # This message is designed to take up less space when sending\n\ 00414 # lots of points at once, as in the case of a PointCloud. \n\ 00415 \n\ 00416 float32 x\n\ 00417 float32 y\n\ 00418 float32 z\n\ 00419 ================================================================================\n\ 00420 MSG: sensor_msgs/ChannelFloat32\n\ 00421 # This message is used by the PointCloud message to hold optional data\n\ 00422 # associated with each point in the cloud. The length of the values\n\ 00423 # array should be the same as the length of the points array in the\n\ 00424 # PointCloud, and each value should be associated with the corresponding\n\ 00425 # point.\n\ 00426 \n\ 00427 # Channel names in existing practice include:\n\ 00428 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\ 00429 # This is opposite to usual conventions but remains for\n\ 00430 # historical reasons. The newer PointCloud2 message has no\n\ 00431 # such problem.\n\ 00432 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\ 00433 # (R,G,B) values packed into the least significant 24 bits,\n\ 00434 # in order.\n\ 00435 # \"intensity\" - laser or pixel intensity.\n\ 00436 # \"distance\"\n\ 00437 \n\ 00438 # The channel name should give semantics of the channel (e.g.\n\ 00439 # \"intensity\" instead of \"value\").\n\ 00440 string name\n\ 00441 \n\ 00442 # The values array should be 1-1 with the elements of the associated\n\ 00443 # PointCloud.\n\ 00444 float32[] values\n\ 00445 \n\ 00446 "; 00447 } 00448 00449 static const char* value(const ::laser_assembler::AssembleScansResponse_<ContainerAllocator> &) { return value(); } 00450 }; 00451 00452 } // namespace message_traits 00453 } // namespace ros 00454 00455 namespace ros 00456 { 00457 namespace serialization 00458 { 00459 00460 template<class ContainerAllocator> struct Serializer< ::laser_assembler::AssembleScansRequest_<ContainerAllocator> > 00461 { 00462 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00463 { 00464 stream.next(m.begin); 00465 stream.next(m.end); 00466 } 00467 00468 ROS_DECLARE_ALLINONE_SERIALIZER; 00469 }; // struct AssembleScansRequest_ 00470 } // namespace serialization 00471 } // namespace ros 00472 00473 00474 namespace ros 00475 { 00476 namespace serialization 00477 { 00478 00479 template<class ContainerAllocator> struct Serializer< ::laser_assembler::AssembleScansResponse_<ContainerAllocator> > 00480 { 00481 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00482 { 00483 stream.next(m.cloud); 00484 } 00485 00486 ROS_DECLARE_ALLINONE_SERIALIZER; 00487 }; // struct AssembleScansResponse_ 00488 } // namespace serialization 00489 } // namespace ros 00490 00491 namespace ros 00492 { 00493 namespace service_traits 00494 { 00495 template<> 00496 struct MD5Sum<laser_assembler::AssembleScans> { 00497 static const char* value() 00498 { 00499 return "6d5cec00dca23821eae6bd7449078aa7"; 00500 } 00501 00502 static const char* value(const laser_assembler::AssembleScans&) { return value(); } 00503 }; 00504 00505 template<> 00506 struct DataType<laser_assembler::AssembleScans> { 00507 static const char* value() 00508 { 00509 return "laser_assembler/AssembleScans"; 00510 } 00511 00512 static const char* value(const laser_assembler::AssembleScans&) { return value(); } 00513 }; 00514 00515 template<class ContainerAllocator> 00516 struct MD5Sum<laser_assembler::AssembleScansRequest_<ContainerAllocator> > { 00517 static const char* value() 00518 { 00519 return "6d5cec00dca23821eae6bd7449078aa7"; 00520 } 00521 00522 static const char* value(const laser_assembler::AssembleScansRequest_<ContainerAllocator> &) { return value(); } 00523 }; 00524 00525 template<class ContainerAllocator> 00526 struct DataType<laser_assembler::AssembleScansRequest_<ContainerAllocator> > { 00527 static const char* value() 00528 { 00529 return "laser_assembler/AssembleScans"; 00530 } 00531 00532 static const char* value(const laser_assembler::AssembleScansRequest_<ContainerAllocator> &) { return value(); } 00533 }; 00534 00535 template<class ContainerAllocator> 00536 struct MD5Sum<laser_assembler::AssembleScansResponse_<ContainerAllocator> > { 00537 static const char* value() 00538 { 00539 return "6d5cec00dca23821eae6bd7449078aa7"; 00540 } 00541 00542 static const char* value(const laser_assembler::AssembleScansResponse_<ContainerAllocator> &) { return value(); } 00543 }; 00544 00545 template<class ContainerAllocator> 00546 struct DataType<laser_assembler::AssembleScansResponse_<ContainerAllocator> > { 00547 static const char* value() 00548 { 00549 return "laser_assembler/AssembleScans"; 00550 } 00551 00552 static const char* value(const laser_assembler::AssembleScansResponse_<ContainerAllocator> &) { return value(); } 00553 }; 00554 00555 } // namespace service_traits 00556 } // namespace ros 00557 00558 #endif // LASER_ASSEMBLER_SERVICE_ASSEMBLESCANS_H 00559