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