$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-cob_environment_perception/doc_stacks/2013-03-01_14-40-06.190572/cob_environment_perception/cob_3d_mapping_msgs/srv/GetPlane.srv */ 00002 #ifndef COB_3D_MAPPING_MSGS_SERVICE_GETPLANE_H 00003 #define COB_3D_MAPPING_MSGS_SERVICE_GETPLANE_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/PointCloud2.h" 00022 #include "sensor_msgs/PointCloud2.h" 00023 #include "std_msgs/Float32.h" 00024 00025 namespace cob_3d_mapping_msgs 00026 { 00027 template <class ContainerAllocator> 00028 struct GetPlaneRequest_ { 00029 typedef GetPlaneRequest_<ContainerAllocator> Type; 00030 00031 GetPlaneRequest_() 00032 { 00033 } 00034 00035 GetPlaneRequest_(const ContainerAllocator& _alloc) 00036 { 00037 } 00038 00039 00040 private: 00041 static const char* __s_getDataType_() { return "cob_3d_mapping_msgs/GetPlaneRequest"; } 00042 public: 00043 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00044 00045 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00046 00047 private: 00048 static const char* __s_getMD5Sum_() { return "d41d8cd98f00b204e9800998ecf8427e"; } 00049 public: 00050 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00051 00052 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00053 00054 private: 00055 static const char* __s_getServerMD5Sum_() { return "e11c006bc7fabf06881bc7d0de7ba820"; } 00056 public: 00057 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00058 00059 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00060 00061 private: 00062 static const char* __s_getMessageDefinition_() { return "\n\ 00063 "; } 00064 public: 00065 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00066 00067 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00068 00069 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00070 { 00071 ros::serialization::OStream stream(write_ptr, 1000000000); 00072 return stream.getData(); 00073 } 00074 00075 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00076 { 00077 ros::serialization::IStream stream(read_ptr, 1000000000); 00078 return stream.getData(); 00079 } 00080 00081 ROS_DEPRECATED virtual uint32_t serializationLength() const 00082 { 00083 uint32_t size = 0; 00084 return size; 00085 } 00086 00087 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> > Ptr; 00088 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> const> ConstPtr; 00089 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00090 }; // struct GetPlaneRequest 00091 typedef ::cob_3d_mapping_msgs::GetPlaneRequest_<std::allocator<void> > GetPlaneRequest; 00092 00093 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::GetPlaneRequest> GetPlaneRequestPtr; 00094 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::GetPlaneRequest const> GetPlaneRequestConstPtr; 00095 00096 00097 template <class ContainerAllocator> 00098 struct GetPlaneResponse_ { 00099 typedef GetPlaneResponse_<ContainerAllocator> Type; 00100 00101 GetPlaneResponse_() 00102 : pc() 00103 , hull() 00104 , plane_coeffs() 00105 { 00106 } 00107 00108 GetPlaneResponse_(const ContainerAllocator& _alloc) 00109 : pc(_alloc) 00110 , hull(_alloc) 00111 , plane_coeffs(_alloc) 00112 { 00113 } 00114 00115 typedef ::sensor_msgs::PointCloud2_<ContainerAllocator> _pc_type; 00116 ::sensor_msgs::PointCloud2_<ContainerAllocator> pc; 00117 00118 typedef ::sensor_msgs::PointCloud2_<ContainerAllocator> _hull_type; 00119 ::sensor_msgs::PointCloud2_<ContainerAllocator> hull; 00120 00121 typedef std::vector< ::std_msgs::Float32_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::Float32_<ContainerAllocator> >::other > _plane_coeffs_type; 00122 std::vector< ::std_msgs::Float32_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::Float32_<ContainerAllocator> >::other > plane_coeffs; 00123 00124 00125 ROS_DEPRECATED uint32_t get_plane_coeffs_size() const { return (uint32_t)plane_coeffs.size(); } 00126 ROS_DEPRECATED void set_plane_coeffs_size(uint32_t size) { plane_coeffs.resize((size_t)size); } 00127 ROS_DEPRECATED void get_plane_coeffs_vec(std::vector< ::std_msgs::Float32_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::Float32_<ContainerAllocator> >::other > & vec) const { vec = this->plane_coeffs; } 00128 ROS_DEPRECATED void set_plane_coeffs_vec(const std::vector< ::std_msgs::Float32_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::Float32_<ContainerAllocator> >::other > & vec) { this->plane_coeffs = vec; } 00129 private: 00130 static const char* __s_getDataType_() { return "cob_3d_mapping_msgs/GetPlaneResponse"; } 00131 public: 00132 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00133 00134 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00135 00136 private: 00137 static const char* __s_getMD5Sum_() { return "e11c006bc7fabf06881bc7d0de7ba820"; } 00138 public: 00139 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00140 00141 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00142 00143 private: 00144 static const char* __s_getServerMD5Sum_() { return "e11c006bc7fabf06881bc7d0de7ba820"; } 00145 public: 00146 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00147 00148 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00149 00150 private: 00151 static const char* __s_getMessageDefinition_() { return "sensor_msgs/PointCloud2 pc\n\ 00152 sensor_msgs/PointCloud2 hull\n\ 00153 std_msgs/Float32[] plane_coeffs\n\ 00154 \n\ 00155 \n\ 00156 ================================================================================\n\ 00157 MSG: sensor_msgs/PointCloud2\n\ 00158 # This message holds a collection of N-dimensional points, which may\n\ 00159 # contain additional information such as normals, intensity, etc. The\n\ 00160 # point data is stored as a binary blob, its layout described by the\n\ 00161 # contents of the \"fields\" array.\n\ 00162 \n\ 00163 # The point cloud data may be organized 2d (image-like) or 1d\n\ 00164 # (unordered). Point clouds organized as 2d images may be produced by\n\ 00165 # camera depth sensors such as stereo or time-of-flight.\n\ 00166 \n\ 00167 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ 00168 # points).\n\ 00169 Header header\n\ 00170 \n\ 00171 # 2D structure of the point cloud. If the cloud is unordered, height is\n\ 00172 # 1 and width is the length of the point cloud.\n\ 00173 uint32 height\n\ 00174 uint32 width\n\ 00175 \n\ 00176 # Describes the channels and their layout in the binary data blob.\n\ 00177 PointField[] fields\n\ 00178 \n\ 00179 bool is_bigendian # Is this data bigendian?\n\ 00180 uint32 point_step # Length of a point in bytes\n\ 00181 uint32 row_step # Length of a row in bytes\n\ 00182 uint8[] data # Actual point data, size is (row_step*height)\n\ 00183 \n\ 00184 bool is_dense # True if there are no invalid points\n\ 00185 \n\ 00186 ================================================================================\n\ 00187 MSG: std_msgs/Header\n\ 00188 # Standard metadata for higher-level stamped data types.\n\ 00189 # This is generally used to communicate timestamped data \n\ 00190 # in a particular coordinate frame.\n\ 00191 # \n\ 00192 # sequence ID: consecutively increasing ID \n\ 00193 uint32 seq\n\ 00194 #Two-integer timestamp that is expressed as:\n\ 00195 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00196 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00197 # time-handling sugar is provided by the client library\n\ 00198 time stamp\n\ 00199 #Frame this data is associated with\n\ 00200 # 0: no frame\n\ 00201 # 1: global frame\n\ 00202 string frame_id\n\ 00203 \n\ 00204 ================================================================================\n\ 00205 MSG: sensor_msgs/PointField\n\ 00206 # This message holds the description of one point entry in the\n\ 00207 # PointCloud2 message format.\n\ 00208 uint8 INT8 = 1\n\ 00209 uint8 UINT8 = 2\n\ 00210 uint8 INT16 = 3\n\ 00211 uint8 UINT16 = 4\n\ 00212 uint8 INT32 = 5\n\ 00213 uint8 UINT32 = 6\n\ 00214 uint8 FLOAT32 = 7\n\ 00215 uint8 FLOAT64 = 8\n\ 00216 \n\ 00217 string name # Name of field\n\ 00218 uint32 offset # Offset from start of point struct\n\ 00219 uint8 datatype # Datatype enumeration, see above\n\ 00220 uint32 count # How many elements in the field\n\ 00221 \n\ 00222 ================================================================================\n\ 00223 MSG: std_msgs/Float32\n\ 00224 float32 data\n\ 00225 "; } 00226 public: 00227 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00228 00229 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00230 00231 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00232 { 00233 ros::serialization::OStream stream(write_ptr, 1000000000); 00234 ros::serialization::serialize(stream, pc); 00235 ros::serialization::serialize(stream, hull); 00236 ros::serialization::serialize(stream, plane_coeffs); 00237 return stream.getData(); 00238 } 00239 00240 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00241 { 00242 ros::serialization::IStream stream(read_ptr, 1000000000); 00243 ros::serialization::deserialize(stream, pc); 00244 ros::serialization::deserialize(stream, hull); 00245 ros::serialization::deserialize(stream, plane_coeffs); 00246 return stream.getData(); 00247 } 00248 00249 ROS_DEPRECATED virtual uint32_t serializationLength() const 00250 { 00251 uint32_t size = 0; 00252 size += ros::serialization::serializationLength(pc); 00253 size += ros::serialization::serializationLength(hull); 00254 size += ros::serialization::serializationLength(plane_coeffs); 00255 return size; 00256 } 00257 00258 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> > Ptr; 00259 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> const> ConstPtr; 00260 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00261 }; // struct GetPlaneResponse 00262 typedef ::cob_3d_mapping_msgs::GetPlaneResponse_<std::allocator<void> > GetPlaneResponse; 00263 00264 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::GetPlaneResponse> GetPlaneResponsePtr; 00265 typedef boost::shared_ptr< ::cob_3d_mapping_msgs::GetPlaneResponse const> GetPlaneResponseConstPtr; 00266 00267 struct GetPlane 00268 { 00269 00270 typedef GetPlaneRequest Request; 00271 typedef GetPlaneResponse Response; 00272 Request request; 00273 Response response; 00274 00275 typedef Request RequestType; 00276 typedef Response ResponseType; 00277 }; // struct GetPlane 00278 } // namespace cob_3d_mapping_msgs 00279 00280 namespace ros 00281 { 00282 namespace message_traits 00283 { 00284 template<class ContainerAllocator> struct IsMessage< ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> > : public TrueType {}; 00285 template<class ContainerAllocator> struct IsMessage< ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> const> : public TrueType {}; 00286 template<class ContainerAllocator> 00287 struct MD5Sum< ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> > { 00288 static const char* value() 00289 { 00290 return "d41d8cd98f00b204e9800998ecf8427e"; 00291 } 00292 00293 static const char* value(const ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> &) { return value(); } 00294 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL; 00295 static const uint64_t static_value2 = 0xe9800998ecf8427eULL; 00296 }; 00297 00298 template<class ContainerAllocator> 00299 struct DataType< ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> > { 00300 static const char* value() 00301 { 00302 return "cob_3d_mapping_msgs/GetPlaneRequest"; 00303 } 00304 00305 static const char* value(const ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> &) { return value(); } 00306 }; 00307 00308 template<class ContainerAllocator> 00309 struct Definition< ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> > { 00310 static const char* value() 00311 { 00312 return "\n\ 00313 "; 00314 } 00315 00316 static const char* value(const ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> &) { return value(); } 00317 }; 00318 00319 template<class ContainerAllocator> struct IsFixedSize< ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> > : public TrueType {}; 00320 } // namespace message_traits 00321 } // namespace ros 00322 00323 00324 namespace ros 00325 { 00326 namespace message_traits 00327 { 00328 template<class ContainerAllocator> struct IsMessage< ::cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> > : public TrueType {}; 00329 template<class ContainerAllocator> struct IsMessage< ::cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> const> : public TrueType {}; 00330 template<class ContainerAllocator> 00331 struct MD5Sum< ::cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> > { 00332 static const char* value() 00333 { 00334 return "e11c006bc7fabf06881bc7d0de7ba820"; 00335 } 00336 00337 static const char* value(const ::cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> &) { return value(); } 00338 static const uint64_t static_value1 = 0xe11c006bc7fabf06ULL; 00339 static const uint64_t static_value2 = 0x881bc7d0de7ba820ULL; 00340 }; 00341 00342 template<class ContainerAllocator> 00343 struct DataType< ::cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> > { 00344 static const char* value() 00345 { 00346 return "cob_3d_mapping_msgs/GetPlaneResponse"; 00347 } 00348 00349 static const char* value(const ::cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> &) { return value(); } 00350 }; 00351 00352 template<class ContainerAllocator> 00353 struct Definition< ::cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> > { 00354 static const char* value() 00355 { 00356 return "sensor_msgs/PointCloud2 pc\n\ 00357 sensor_msgs/PointCloud2 hull\n\ 00358 std_msgs/Float32[] plane_coeffs\n\ 00359 \n\ 00360 \n\ 00361 ================================================================================\n\ 00362 MSG: sensor_msgs/PointCloud2\n\ 00363 # This message holds a collection of N-dimensional points, which may\n\ 00364 # contain additional information such as normals, intensity, etc. The\n\ 00365 # point data is stored as a binary blob, its layout described by the\n\ 00366 # contents of the \"fields\" array.\n\ 00367 \n\ 00368 # The point cloud data may be organized 2d (image-like) or 1d\n\ 00369 # (unordered). Point clouds organized as 2d images may be produced by\n\ 00370 # camera depth sensors such as stereo or time-of-flight.\n\ 00371 \n\ 00372 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ 00373 # points).\n\ 00374 Header header\n\ 00375 \n\ 00376 # 2D structure of the point cloud. If the cloud is unordered, height is\n\ 00377 # 1 and width is the length of the point cloud.\n\ 00378 uint32 height\n\ 00379 uint32 width\n\ 00380 \n\ 00381 # Describes the channels and their layout in the binary data blob.\n\ 00382 PointField[] fields\n\ 00383 \n\ 00384 bool is_bigendian # Is this data bigendian?\n\ 00385 uint32 point_step # Length of a point in bytes\n\ 00386 uint32 row_step # Length of a row in bytes\n\ 00387 uint8[] data # Actual point data, size is (row_step*height)\n\ 00388 \n\ 00389 bool is_dense # True if there are no invalid points\n\ 00390 \n\ 00391 ================================================================================\n\ 00392 MSG: std_msgs/Header\n\ 00393 # Standard metadata for higher-level stamped data types.\n\ 00394 # This is generally used to communicate timestamped data \n\ 00395 # in a particular coordinate frame.\n\ 00396 # \n\ 00397 # sequence ID: consecutively increasing ID \n\ 00398 uint32 seq\n\ 00399 #Two-integer timestamp that is expressed as:\n\ 00400 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00401 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00402 # time-handling sugar is provided by the client library\n\ 00403 time stamp\n\ 00404 #Frame this data is associated with\n\ 00405 # 0: no frame\n\ 00406 # 1: global frame\n\ 00407 string frame_id\n\ 00408 \n\ 00409 ================================================================================\n\ 00410 MSG: sensor_msgs/PointField\n\ 00411 # This message holds the description of one point entry in the\n\ 00412 # PointCloud2 message format.\n\ 00413 uint8 INT8 = 1\n\ 00414 uint8 UINT8 = 2\n\ 00415 uint8 INT16 = 3\n\ 00416 uint8 UINT16 = 4\n\ 00417 uint8 INT32 = 5\n\ 00418 uint8 UINT32 = 6\n\ 00419 uint8 FLOAT32 = 7\n\ 00420 uint8 FLOAT64 = 8\n\ 00421 \n\ 00422 string name # Name of field\n\ 00423 uint32 offset # Offset from start of point struct\n\ 00424 uint8 datatype # Datatype enumeration, see above\n\ 00425 uint32 count # How many elements in the field\n\ 00426 \n\ 00427 ================================================================================\n\ 00428 MSG: std_msgs/Float32\n\ 00429 float32 data\n\ 00430 "; 00431 } 00432 00433 static const char* value(const ::cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> &) { return value(); } 00434 }; 00435 00436 } // namespace message_traits 00437 } // namespace ros 00438 00439 namespace ros 00440 { 00441 namespace serialization 00442 { 00443 00444 template<class ContainerAllocator> struct Serializer< ::cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> > 00445 { 00446 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00447 { 00448 } 00449 00450 ROS_DECLARE_ALLINONE_SERIALIZER; 00451 }; // struct GetPlaneRequest_ 00452 } // namespace serialization 00453 } // namespace ros 00454 00455 00456 namespace ros 00457 { 00458 namespace serialization 00459 { 00460 00461 template<class ContainerAllocator> struct Serializer< ::cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> > 00462 { 00463 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00464 { 00465 stream.next(m.pc); 00466 stream.next(m.hull); 00467 stream.next(m.plane_coeffs); 00468 } 00469 00470 ROS_DECLARE_ALLINONE_SERIALIZER; 00471 }; // struct GetPlaneResponse_ 00472 } // namespace serialization 00473 } // namespace ros 00474 00475 namespace ros 00476 { 00477 namespace service_traits 00478 { 00479 template<> 00480 struct MD5Sum<cob_3d_mapping_msgs::GetPlane> { 00481 static const char* value() 00482 { 00483 return "e11c006bc7fabf06881bc7d0de7ba820"; 00484 } 00485 00486 static const char* value(const cob_3d_mapping_msgs::GetPlane&) { return value(); } 00487 }; 00488 00489 template<> 00490 struct DataType<cob_3d_mapping_msgs::GetPlane> { 00491 static const char* value() 00492 { 00493 return "cob_3d_mapping_msgs/GetPlane"; 00494 } 00495 00496 static const char* value(const cob_3d_mapping_msgs::GetPlane&) { return value(); } 00497 }; 00498 00499 template<class ContainerAllocator> 00500 struct MD5Sum<cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> > { 00501 static const char* value() 00502 { 00503 return "e11c006bc7fabf06881bc7d0de7ba820"; 00504 } 00505 00506 static const char* value(const cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> &) { return value(); } 00507 }; 00508 00509 template<class ContainerAllocator> 00510 struct DataType<cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> > { 00511 static const char* value() 00512 { 00513 return "cob_3d_mapping_msgs/GetPlane"; 00514 } 00515 00516 static const char* value(const cob_3d_mapping_msgs::GetPlaneRequest_<ContainerAllocator> &) { return value(); } 00517 }; 00518 00519 template<class ContainerAllocator> 00520 struct MD5Sum<cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> > { 00521 static const char* value() 00522 { 00523 return "e11c006bc7fabf06881bc7d0de7ba820"; 00524 } 00525 00526 static const char* value(const cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> &) { return value(); } 00527 }; 00528 00529 template<class ContainerAllocator> 00530 struct DataType<cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> > { 00531 static const char* value() 00532 { 00533 return "cob_3d_mapping_msgs/GetPlane"; 00534 } 00535 00536 static const char* value(const cob_3d_mapping_msgs::GetPlaneResponse_<ContainerAllocator> &) { return value(); } 00537 }; 00538 00539 } // namespace service_traits 00540 } // namespace ros 00541 00542 #endif // COB_3D_MAPPING_MSGS_SERVICE_GETPLANE_H 00543