_GPSDataAdvanced.py
Go to the documentation of this file.
00001 """autogenerated by genpy from asctec_msgs/GPSDataAdvanced.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006 
00007 import std_msgs.msg
00008 
00009 class GPSDataAdvanced(genpy.Message):
00010   _md5sum = "9ab56d8a7fca6e53fe5619fec119323d"
00011   _type = "asctec_msgs/GPSDataAdvanced"
00012   _has_header = True #flag to mark the presence of a Header object
00013   _full_text = """# Software License Agreement (BSD License)
00014 #
00015 # Copyright (c) 2010
00016 #  William Morris <morris@ee.ccny.cuny.edu>
00017 #  Ivan Dryanovski <ivan.dryanovski@gmail.com>
00018 # All rights reserved.
00019 #
00020 # Redistribution and use in source and binary forms, with or without
00021 # modification, are permitted provided that the following conditions
00022 # are met:
00023 #
00024 #  * Redistributions of source code must retain the above copyright
00025 #    notice, this list of conditions and the following disclaimer.
00026 #  * Redistributions in binary form must reproduce the above
00027 #    copyright notice, this list of conditions and the following
00028 #    disclaimer in the documentation and/or other materials provided
00029 #    with the distribution.
00030 #  * Neither the name of CCNY Robotics Lab nor the names of its
00031 #    contributors may be used to endorse or promote products derived
00032 #    from this software without specific prior written permission.
00033 #
00034 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00035 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00036 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00037 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00038 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00039 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00040 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00041 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00042 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00043 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00044 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00045 # POSSIBILITY OF SUCH DAMAGE.
00046 
00047 Header header
00048 #latitude/longitude in deg * 10^7
00049 int32 latitude
00050 int32 longitude
00051 
00052 #GPS height in mm
00053 int32 height
00054 
00055 #speed in x (E/W) and y(N/S) in mm/s
00056 int32 speed_x
00057 int32 speed_y
00058 
00059 #GPS heading in deg * 100
00060 int32 heading
00061 
00062 #accuracy estimates in mm and mm/s
00063 int32 horizontal_accuracy
00064 int32 vertical_accuracy
00065 int32 speed_accuracy
00066 
00067 #number of satellite vehicles used in NAV solution
00068 int32 numSV
00069 
00070 #GPS status information; 0x03 = valid GPS fix
00071 int32 status
00072 
00073 #coordinates of current origin in deg * 10^7
00074 int32 latitude_best_estimate
00075 int32 longitude_best_estimate
00076 
00077 #velocities in X (E/W) and Y (N/S) after data fusion
00078 int32 speed_x_best_estimate
00079 int32 speed_y_best_estimate
00080 
00081 ================================================================================
00082 MSG: std_msgs/Header
00083 # Standard metadata for higher-level stamped data types.
00084 # This is generally used to communicate timestamped data 
00085 # in a particular coordinate frame.
00086 # 
00087 # sequence ID: consecutively increasing ID 
00088 uint32 seq
00089 #Two-integer timestamp that is expressed as:
00090 # * stamp.secs: seconds (stamp_secs) since epoch
00091 # * stamp.nsecs: nanoseconds since stamp_secs
00092 # time-handling sugar is provided by the client library
00093 time stamp
00094 #Frame this data is associated with
00095 # 0: no frame
00096 # 1: global frame
00097 string frame_id
00098 
00099 """
00100   __slots__ = ['header','latitude','longitude','height','speed_x','speed_y','heading','horizontal_accuracy','vertical_accuracy','speed_accuracy','numSV','status','latitude_best_estimate','longitude_best_estimate','speed_x_best_estimate','speed_y_best_estimate']
00101   _slot_types = ['std_msgs/Header','int32','int32','int32','int32','int32','int32','int32','int32','int32','int32','int32','int32','int32','int32','int32']
00102 
00103   def __init__(self, *args, **kwds):
00104     """
00105     Constructor. Any message fields that are implicitly/explicitly
00106     set to None will be assigned a default value. The recommend
00107     use is keyword arguments as this is more robust to future message
00108     changes.  You cannot mix in-order arguments and keyword arguments.
00109 
00110     The available fields are:
00111        header,latitude,longitude,height,speed_x,speed_y,heading,horizontal_accuracy,vertical_accuracy,speed_accuracy,numSV,status,latitude_best_estimate,longitude_best_estimate,speed_x_best_estimate,speed_y_best_estimate
00112 
00113     :param args: complete set of field values, in .msg order
00114     :param kwds: use keyword arguments corresponding to message field names
00115     to set specific fields.
00116     """
00117     if args or kwds:
00118       super(GPSDataAdvanced, self).__init__(*args, **kwds)
00119       #message fields cannot be None, assign default values for those that are
00120       if self.header is None:
00121         self.header = std_msgs.msg.Header()
00122       if self.latitude is None:
00123         self.latitude = 0
00124       if self.longitude is None:
00125         self.longitude = 0
00126       if self.height is None:
00127         self.height = 0
00128       if self.speed_x is None:
00129         self.speed_x = 0
00130       if self.speed_y is None:
00131         self.speed_y = 0
00132       if self.heading is None:
00133         self.heading = 0
00134       if self.horizontal_accuracy is None:
00135         self.horizontal_accuracy = 0
00136       if self.vertical_accuracy is None:
00137         self.vertical_accuracy = 0
00138       if self.speed_accuracy is None:
00139         self.speed_accuracy = 0
00140       if self.numSV is None:
00141         self.numSV = 0
00142       if self.status is None:
00143         self.status = 0
00144       if self.latitude_best_estimate is None:
00145         self.latitude_best_estimate = 0
00146       if self.longitude_best_estimate is None:
00147         self.longitude_best_estimate = 0
00148       if self.speed_x_best_estimate is None:
00149         self.speed_x_best_estimate = 0
00150       if self.speed_y_best_estimate is None:
00151         self.speed_y_best_estimate = 0
00152     else:
00153       self.header = std_msgs.msg.Header()
00154       self.latitude = 0
00155       self.longitude = 0
00156       self.height = 0
00157       self.speed_x = 0
00158       self.speed_y = 0
00159       self.heading = 0
00160       self.horizontal_accuracy = 0
00161       self.vertical_accuracy = 0
00162       self.speed_accuracy = 0
00163       self.numSV = 0
00164       self.status = 0
00165       self.latitude_best_estimate = 0
00166       self.longitude_best_estimate = 0
00167       self.speed_x_best_estimate = 0
00168       self.speed_y_best_estimate = 0
00169 
00170   def _get_types(self):
00171     """
00172     internal API method
00173     """
00174     return self._slot_types
00175 
00176   def serialize(self, buff):
00177     """
00178     serialize message into buffer
00179     :param buff: buffer, ``StringIO``
00180     """
00181     try:
00182       _x = self
00183       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00184       _x = self.header.frame_id
00185       length = len(_x)
00186       if python3 or type(_x) == unicode:
00187         _x = _x.encode('utf-8')
00188         length = len(_x)
00189       buff.write(struct.pack('<I%ss'%length, length, _x))
00190       _x = self
00191       buff.write(_struct_15i.pack(_x.latitude, _x.longitude, _x.height, _x.speed_x, _x.speed_y, _x.heading, _x.horizontal_accuracy, _x.vertical_accuracy, _x.speed_accuracy, _x.numSV, _x.status, _x.latitude_best_estimate, _x.longitude_best_estimate, _x.speed_x_best_estimate, _x.speed_y_best_estimate))
00192     except struct.error as se: self._check_types(se)
00193     except TypeError as te: self._check_types(te)
00194 
00195   def deserialize(self, str):
00196     """
00197     unpack serialized message in str into this message instance
00198     :param str: byte array of serialized message, ``str``
00199     """
00200     try:
00201       if self.header is None:
00202         self.header = std_msgs.msg.Header()
00203       end = 0
00204       _x = self
00205       start = end
00206       end += 12
00207       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00208       start = end
00209       end += 4
00210       (length,) = _struct_I.unpack(str[start:end])
00211       start = end
00212       end += length
00213       if python3:
00214         self.header.frame_id = str[start:end].decode('utf-8')
00215       else:
00216         self.header.frame_id = str[start:end]
00217       _x = self
00218       start = end
00219       end += 60
00220       (_x.latitude, _x.longitude, _x.height, _x.speed_x, _x.speed_y, _x.heading, _x.horizontal_accuracy, _x.vertical_accuracy, _x.speed_accuracy, _x.numSV, _x.status, _x.latitude_best_estimate, _x.longitude_best_estimate, _x.speed_x_best_estimate, _x.speed_y_best_estimate,) = _struct_15i.unpack(str[start:end])
00221       return self
00222     except struct.error as e:
00223       raise genpy.DeserializationError(e) #most likely buffer underfill
00224 
00225 
00226   def serialize_numpy(self, buff, numpy):
00227     """
00228     serialize message with numpy array types into buffer
00229     :param buff: buffer, ``StringIO``
00230     :param numpy: numpy python module
00231     """
00232     try:
00233       _x = self
00234       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00235       _x = self.header.frame_id
00236       length = len(_x)
00237       if python3 or type(_x) == unicode:
00238         _x = _x.encode('utf-8')
00239         length = len(_x)
00240       buff.write(struct.pack('<I%ss'%length, length, _x))
00241       _x = self
00242       buff.write(_struct_15i.pack(_x.latitude, _x.longitude, _x.height, _x.speed_x, _x.speed_y, _x.heading, _x.horizontal_accuracy, _x.vertical_accuracy, _x.speed_accuracy, _x.numSV, _x.status, _x.latitude_best_estimate, _x.longitude_best_estimate, _x.speed_x_best_estimate, _x.speed_y_best_estimate))
00243     except struct.error as se: self._check_types(se)
00244     except TypeError as te: self._check_types(te)
00245 
00246   def deserialize_numpy(self, str, numpy):
00247     """
00248     unpack serialized message in str into this message instance using numpy for array types
00249     :param str: byte array of serialized message, ``str``
00250     :param numpy: numpy python module
00251     """
00252     try:
00253       if self.header is None:
00254         self.header = std_msgs.msg.Header()
00255       end = 0
00256       _x = self
00257       start = end
00258       end += 12
00259       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00260       start = end
00261       end += 4
00262       (length,) = _struct_I.unpack(str[start:end])
00263       start = end
00264       end += length
00265       if python3:
00266         self.header.frame_id = str[start:end].decode('utf-8')
00267       else:
00268         self.header.frame_id = str[start:end]
00269       _x = self
00270       start = end
00271       end += 60
00272       (_x.latitude, _x.longitude, _x.height, _x.speed_x, _x.speed_y, _x.heading, _x.horizontal_accuracy, _x.vertical_accuracy, _x.speed_accuracy, _x.numSV, _x.status, _x.latitude_best_estimate, _x.longitude_best_estimate, _x.speed_x_best_estimate, _x.speed_y_best_estimate,) = _struct_15i.unpack(str[start:end])
00273       return self
00274     except struct.error as e:
00275       raise genpy.DeserializationError(e) #most likely buffer underfill
00276 
00277 _struct_I = genpy.struct_I
00278 _struct_15i = struct.Struct("<15i")
00279 _struct_3I = struct.Struct("<3I")


asctec_msgs
Author(s): William Morris, Ivan Dryanovski, Steven Bellens, Patrick Bouffard et al.
autogenerated on Tue Jan 7 2014 11:04:07