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