00001
00002 #ifndef ASCTEC_MSGS_MESSAGE_GPSDATAADVANCED_H
00003 #define ASCTEC_MSGS_MESSAGE_GPSDATAADVANCED_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "std_msgs/Header.h"
00014
00015 namespace asctec_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct GPSDataAdvanced_ : public ros::Message
00019 {
00020 typedef GPSDataAdvanced_<ContainerAllocator> Type;
00021
00022 GPSDataAdvanced_()
00023 : header()
00024 , latitude(0)
00025 , longitude(0)
00026 , height(0)
00027 , speed_x(0)
00028 , speed_y(0)
00029 , heading(0)
00030 , horizontal_accuracy(0)
00031 , vertical_accuracy(0)
00032 , speed_accuracy(0)
00033 , numSV(0)
00034 , status(0)
00035 , latitude_best_estimate(0)
00036 , longitude_best_estimate(0)
00037 , speed_x_best_estimate(0)
00038 , speed_y_best_estimate(0)
00039 {
00040 }
00041
00042 GPSDataAdvanced_(const ContainerAllocator& _alloc)
00043 : header(_alloc)
00044 , latitude(0)
00045 , longitude(0)
00046 , height(0)
00047 , speed_x(0)
00048 , speed_y(0)
00049 , heading(0)
00050 , horizontal_accuracy(0)
00051 , vertical_accuracy(0)
00052 , speed_accuracy(0)
00053 , numSV(0)
00054 , status(0)
00055 , latitude_best_estimate(0)
00056 , longitude_best_estimate(0)
00057 , speed_x_best_estimate(0)
00058 , speed_y_best_estimate(0)
00059 {
00060 }
00061
00062 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00063 ::std_msgs::Header_<ContainerAllocator> header;
00064
00065 typedef int32_t _latitude_type;
00066 int32_t latitude;
00067
00068 typedef int32_t _longitude_type;
00069 int32_t longitude;
00070
00071 typedef int32_t _height_type;
00072 int32_t height;
00073
00074 typedef int32_t _speed_x_type;
00075 int32_t speed_x;
00076
00077 typedef int32_t _speed_y_type;
00078 int32_t speed_y;
00079
00080 typedef int32_t _heading_type;
00081 int32_t heading;
00082
00083 typedef int32_t _horizontal_accuracy_type;
00084 int32_t horizontal_accuracy;
00085
00086 typedef int32_t _vertical_accuracy_type;
00087 int32_t vertical_accuracy;
00088
00089 typedef int32_t _speed_accuracy_type;
00090 int32_t speed_accuracy;
00091
00092 typedef int32_t _numSV_type;
00093 int32_t numSV;
00094
00095 typedef int32_t _status_type;
00096 int32_t status;
00097
00098 typedef int32_t _latitude_best_estimate_type;
00099 int32_t latitude_best_estimate;
00100
00101 typedef int32_t _longitude_best_estimate_type;
00102 int32_t longitude_best_estimate;
00103
00104 typedef int32_t _speed_x_best_estimate_type;
00105 int32_t speed_x_best_estimate;
00106
00107 typedef int32_t _speed_y_best_estimate_type;
00108 int32_t speed_y_best_estimate;
00109
00110
00111 private:
00112 static const char* __s_getDataType_() { return "asctec_msgs/GPSDataAdvanced"; }
00113 public:
00114 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00115
00116 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00117
00118 private:
00119 static const char* __s_getMD5Sum_() { return "9ab56d8a7fca6e53fe5619fec119323d"; }
00120 public:
00121 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00122
00123 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00124
00125 private:
00126 static const char* __s_getMessageDefinition_() { return "# Software License Agreement (BSD License)\n\
00127 #\n\
00128 # Copyright (c) 2010\n\
00129 # William Morris <morris@ee.ccny.cuny.edu>\n\
00130 # Ivan Dryanovski <ivan.dryanovski@gmail.com>\n\
00131 # All rights reserved.\n\
00132 #\n\
00133 # Redistribution and use in source and binary forms, with or without\n\
00134 # modification, are permitted provided that the following conditions\n\
00135 # are met:\n\
00136 #\n\
00137 # * Redistributions of source code must retain the above copyright\n\
00138 # notice, this list of conditions and the following disclaimer.\n\
00139 # * Redistributions in binary form must reproduce the above\n\
00140 # copyright notice, this list of conditions and the following\n\
00141 # disclaimer in the documentation and/or other materials provided\n\
00142 # with the distribution.\n\
00143 # * Neither the name of CCNY Robotics Lab nor the names of its\n\
00144 # contributors may be used to endorse or promote products derived\n\
00145 # from this software without specific prior written permission.\n\
00146 #\n\
00147 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n\
00148 # \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n\
00149 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n\
00150 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n\
00151 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n\
00152 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n\
00153 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n\
00154 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n\
00155 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n\
00156 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n\
00157 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n\
00158 # POSSIBILITY OF SUCH DAMAGE.\n\
00159 \n\
00160 Header header\n\
00161 #latitude/longitude in deg * 10^7\n\
00162 int32 latitude\n\
00163 int32 longitude\n\
00164 \n\
00165 #GPS height in mm\n\
00166 int32 height\n\
00167 \n\
00168 #speed in x (E/W) and y(N/S) in mm/s\n\
00169 int32 speed_x\n\
00170 int32 speed_y\n\
00171 \n\
00172 #GPS heading in deg * 100\n\
00173 int32 heading\n\
00174 \n\
00175 #accuracy estimates in mm and mm/s\n\
00176 int32 horizontal_accuracy\n\
00177 int32 vertical_accuracy\n\
00178 int32 speed_accuracy\n\
00179 \n\
00180 #number of satellite vehicles used in NAV solution\n\
00181 int32 numSV\n\
00182 \n\
00183 #GPS status information; 0x03 = valid GPS fix\n\
00184 int32 status\n\
00185 \n\
00186 #coordinates of current origin in deg * 10^7\n\
00187 int32 latitude_best_estimate\n\
00188 int32 longitude_best_estimate\n\
00189 \n\
00190 #velocities in X (E/W) and Y (N/S) after data fusion\n\
00191 int32 speed_x_best_estimate\n\
00192 int32 speed_y_best_estimate\n\
00193 \n\
00194 ================================================================================\n\
00195 MSG: std_msgs/Header\n\
00196 # Standard metadata for higher-level stamped data types.\n\
00197 # This is generally used to communicate timestamped data \n\
00198 # in a particular coordinate frame.\n\
00199 # \n\
00200 # sequence ID: consecutively increasing ID \n\
00201 uint32 seq\n\
00202 #Two-integer timestamp that is expressed as:\n\
00203 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00204 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00205 # time-handling sugar is provided by the client library\n\
00206 time stamp\n\
00207 #Frame this data is associated with\n\
00208 # 0: no frame\n\
00209 # 1: global frame\n\
00210 string frame_id\n\
00211 \n\
00212 "; }
00213 public:
00214 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00215
00216 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00217
00218 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00219 {
00220 ros::serialization::OStream stream(write_ptr, 1000000000);
00221 ros::serialization::serialize(stream, header);
00222 ros::serialization::serialize(stream, latitude);
00223 ros::serialization::serialize(stream, longitude);
00224 ros::serialization::serialize(stream, height);
00225 ros::serialization::serialize(stream, speed_x);
00226 ros::serialization::serialize(stream, speed_y);
00227 ros::serialization::serialize(stream, heading);
00228 ros::serialization::serialize(stream, horizontal_accuracy);
00229 ros::serialization::serialize(stream, vertical_accuracy);
00230 ros::serialization::serialize(stream, speed_accuracy);
00231 ros::serialization::serialize(stream, numSV);
00232 ros::serialization::serialize(stream, status);
00233 ros::serialization::serialize(stream, latitude_best_estimate);
00234 ros::serialization::serialize(stream, longitude_best_estimate);
00235 ros::serialization::serialize(stream, speed_x_best_estimate);
00236 ros::serialization::serialize(stream, speed_y_best_estimate);
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, header);
00244 ros::serialization::deserialize(stream, latitude);
00245 ros::serialization::deserialize(stream, longitude);
00246 ros::serialization::deserialize(stream, height);
00247 ros::serialization::deserialize(stream, speed_x);
00248 ros::serialization::deserialize(stream, speed_y);
00249 ros::serialization::deserialize(stream, heading);
00250 ros::serialization::deserialize(stream, horizontal_accuracy);
00251 ros::serialization::deserialize(stream, vertical_accuracy);
00252 ros::serialization::deserialize(stream, speed_accuracy);
00253 ros::serialization::deserialize(stream, numSV);
00254 ros::serialization::deserialize(stream, status);
00255 ros::serialization::deserialize(stream, latitude_best_estimate);
00256 ros::serialization::deserialize(stream, longitude_best_estimate);
00257 ros::serialization::deserialize(stream, speed_x_best_estimate);
00258 ros::serialization::deserialize(stream, speed_y_best_estimate);
00259 return stream.getData();
00260 }
00261
00262 ROS_DEPRECATED virtual uint32_t serializationLength() const
00263 {
00264 uint32_t size = 0;
00265 size += ros::serialization::serializationLength(header);
00266 size += ros::serialization::serializationLength(latitude);
00267 size += ros::serialization::serializationLength(longitude);
00268 size += ros::serialization::serializationLength(height);
00269 size += ros::serialization::serializationLength(speed_x);
00270 size += ros::serialization::serializationLength(speed_y);
00271 size += ros::serialization::serializationLength(heading);
00272 size += ros::serialization::serializationLength(horizontal_accuracy);
00273 size += ros::serialization::serializationLength(vertical_accuracy);
00274 size += ros::serialization::serializationLength(speed_accuracy);
00275 size += ros::serialization::serializationLength(numSV);
00276 size += ros::serialization::serializationLength(status);
00277 size += ros::serialization::serializationLength(latitude_best_estimate);
00278 size += ros::serialization::serializationLength(longitude_best_estimate);
00279 size += ros::serialization::serializationLength(speed_x_best_estimate);
00280 size += ros::serialization::serializationLength(speed_y_best_estimate);
00281 return size;
00282 }
00283
00284 typedef boost::shared_ptr< ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> > Ptr;
00285 typedef boost::shared_ptr< ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> const> ConstPtr;
00286 };
00287 typedef ::asctec_msgs::GPSDataAdvanced_<std::allocator<void> > GPSDataAdvanced;
00288
00289 typedef boost::shared_ptr< ::asctec_msgs::GPSDataAdvanced> GPSDataAdvancedPtr;
00290 typedef boost::shared_ptr< ::asctec_msgs::GPSDataAdvanced const> GPSDataAdvancedConstPtr;
00291
00292
00293 template<typename ContainerAllocator>
00294 std::ostream& operator<<(std::ostream& s, const ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> & v)
00295 {
00296 ros::message_operations::Printer< ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> >::stream(s, "", v);
00297 return s;}
00298
00299 }
00300
00301 namespace ros
00302 {
00303 namespace message_traits
00304 {
00305 template<class ContainerAllocator>
00306 struct MD5Sum< ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> > {
00307 static const char* value()
00308 {
00309 return "9ab56d8a7fca6e53fe5619fec119323d";
00310 }
00311
00312 static const char* value(const ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> &) { return value(); }
00313 static const uint64_t static_value1 = 0x9ab56d8a7fca6e53ULL;
00314 static const uint64_t static_value2 = 0xfe5619fec119323dULL;
00315 };
00316
00317 template<class ContainerAllocator>
00318 struct DataType< ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> > {
00319 static const char* value()
00320 {
00321 return "asctec_msgs/GPSDataAdvanced";
00322 }
00323
00324 static const char* value(const ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> &) { return value(); }
00325 };
00326
00327 template<class ContainerAllocator>
00328 struct Definition< ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> > {
00329 static const char* value()
00330 {
00331 return "# Software License Agreement (BSD License)\n\
00332 #\n\
00333 # Copyright (c) 2010\n\
00334 # William Morris <morris@ee.ccny.cuny.edu>\n\
00335 # Ivan Dryanovski <ivan.dryanovski@gmail.com>\n\
00336 # All rights reserved.\n\
00337 #\n\
00338 # Redistribution and use in source and binary forms, with or without\n\
00339 # modification, are permitted provided that the following conditions\n\
00340 # are met:\n\
00341 #\n\
00342 # * Redistributions of source code must retain the above copyright\n\
00343 # notice, this list of conditions and the following disclaimer.\n\
00344 # * Redistributions in binary form must reproduce the above\n\
00345 # copyright notice, this list of conditions and the following\n\
00346 # disclaimer in the documentation and/or other materials provided\n\
00347 # with the distribution.\n\
00348 # * Neither the name of CCNY Robotics Lab nor the names of its\n\
00349 # contributors may be used to endorse or promote products derived\n\
00350 # from this software without specific prior written permission.\n\
00351 #\n\
00352 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n\
00353 # \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n\
00354 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n\
00355 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n\
00356 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n\
00357 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n\
00358 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n\
00359 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n\
00360 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n\
00361 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n\
00362 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n\
00363 # POSSIBILITY OF SUCH DAMAGE.\n\
00364 \n\
00365 Header header\n\
00366 #latitude/longitude in deg * 10^7\n\
00367 int32 latitude\n\
00368 int32 longitude\n\
00369 \n\
00370 #GPS height in mm\n\
00371 int32 height\n\
00372 \n\
00373 #speed in x (E/W) and y(N/S) in mm/s\n\
00374 int32 speed_x\n\
00375 int32 speed_y\n\
00376 \n\
00377 #GPS heading in deg * 100\n\
00378 int32 heading\n\
00379 \n\
00380 #accuracy estimates in mm and mm/s\n\
00381 int32 horizontal_accuracy\n\
00382 int32 vertical_accuracy\n\
00383 int32 speed_accuracy\n\
00384 \n\
00385 #number of satellite vehicles used in NAV solution\n\
00386 int32 numSV\n\
00387 \n\
00388 #GPS status information; 0x03 = valid GPS fix\n\
00389 int32 status\n\
00390 \n\
00391 #coordinates of current origin in deg * 10^7\n\
00392 int32 latitude_best_estimate\n\
00393 int32 longitude_best_estimate\n\
00394 \n\
00395 #velocities in X (E/W) and Y (N/S) after data fusion\n\
00396 int32 speed_x_best_estimate\n\
00397 int32 speed_y_best_estimate\n\
00398 \n\
00399 ================================================================================\n\
00400 MSG: std_msgs/Header\n\
00401 # Standard metadata for higher-level stamped data types.\n\
00402 # This is generally used to communicate timestamped data \n\
00403 # in a particular coordinate frame.\n\
00404 # \n\
00405 # sequence ID: consecutively increasing ID \n\
00406 uint32 seq\n\
00407 #Two-integer timestamp that is expressed as:\n\
00408 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00409 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00410 # time-handling sugar is provided by the client library\n\
00411 time stamp\n\
00412 #Frame this data is associated with\n\
00413 # 0: no frame\n\
00414 # 1: global frame\n\
00415 string frame_id\n\
00416 \n\
00417 ";
00418 }
00419
00420 static const char* value(const ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> &) { return value(); }
00421 };
00422
00423 template<class ContainerAllocator> struct HasHeader< ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> > : public TrueType {};
00424 template<class ContainerAllocator> struct HasHeader< const ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> > : public TrueType {};
00425 }
00426 }
00427
00428 namespace ros
00429 {
00430 namespace serialization
00431 {
00432
00433 template<class ContainerAllocator> struct Serializer< ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> >
00434 {
00435 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00436 {
00437 stream.next(m.header);
00438 stream.next(m.latitude);
00439 stream.next(m.longitude);
00440 stream.next(m.height);
00441 stream.next(m.speed_x);
00442 stream.next(m.speed_y);
00443 stream.next(m.heading);
00444 stream.next(m.horizontal_accuracy);
00445 stream.next(m.vertical_accuracy);
00446 stream.next(m.speed_accuracy);
00447 stream.next(m.numSV);
00448 stream.next(m.status);
00449 stream.next(m.latitude_best_estimate);
00450 stream.next(m.longitude_best_estimate);
00451 stream.next(m.speed_x_best_estimate);
00452 stream.next(m.speed_y_best_estimate);
00453 }
00454
00455 ROS_DECLARE_ALLINONE_SERIALIZER;
00456 };
00457 }
00458 }
00459
00460 namespace ros
00461 {
00462 namespace message_operations
00463 {
00464
00465 template<class ContainerAllocator>
00466 struct Printer< ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> >
00467 {
00468 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::asctec_msgs::GPSDataAdvanced_<ContainerAllocator> & v)
00469 {
00470 s << indent << "header: ";
00471 s << std::endl;
00472 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00473 s << indent << "latitude: ";
00474 Printer<int32_t>::stream(s, indent + " ", v.latitude);
00475 s << indent << "longitude: ";
00476 Printer<int32_t>::stream(s, indent + " ", v.longitude);
00477 s << indent << "height: ";
00478 Printer<int32_t>::stream(s, indent + " ", v.height);
00479 s << indent << "speed_x: ";
00480 Printer<int32_t>::stream(s, indent + " ", v.speed_x);
00481 s << indent << "speed_y: ";
00482 Printer<int32_t>::stream(s, indent + " ", v.speed_y);
00483 s << indent << "heading: ";
00484 Printer<int32_t>::stream(s, indent + " ", v.heading);
00485 s << indent << "horizontal_accuracy: ";
00486 Printer<int32_t>::stream(s, indent + " ", v.horizontal_accuracy);
00487 s << indent << "vertical_accuracy: ";
00488 Printer<int32_t>::stream(s, indent + " ", v.vertical_accuracy);
00489 s << indent << "speed_accuracy: ";
00490 Printer<int32_t>::stream(s, indent + " ", v.speed_accuracy);
00491 s << indent << "numSV: ";
00492 Printer<int32_t>::stream(s, indent + " ", v.numSV);
00493 s << indent << "status: ";
00494 Printer<int32_t>::stream(s, indent + " ", v.status);
00495 s << indent << "latitude_best_estimate: ";
00496 Printer<int32_t>::stream(s, indent + " ", v.latitude_best_estimate);
00497 s << indent << "longitude_best_estimate: ";
00498 Printer<int32_t>::stream(s, indent + " ", v.longitude_best_estimate);
00499 s << indent << "speed_x_best_estimate: ";
00500 Printer<int32_t>::stream(s, indent + " ", v.speed_x_best_estimate);
00501 s << indent << "speed_y_best_estimate: ";
00502 Printer<int32_t>::stream(s, indent + " ", v.speed_y_best_estimate);
00503 }
00504 };
00505
00506
00507 }
00508 }
00509
00510 #endif // ASCTEC_MSGS_MESSAGE_GPSDATAADVANCED_H
00511