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