_GPSFix.py
Go to the documentation of this file.
00001 """autogenerated by genpy from corobot_msgs/GPSFix.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 corobot_msgs.msg
00008 import std_msgs.msg
00009 
00010 class GPSFix(genpy.Message):
00011   _md5sum = "3db3d0a7bc53054c67c528af84710b70"
00012   _type = "corobot_msgs/GPSFix"
00013   _has_header = True #flag to mark the presence of a Header object
00014   _full_text = """# A more complete GPS fix to supplement sensor_msgs/NavSatFix.
00015 Header header
00016 
00017 GPSStatus status
00018 
00019 # Latitude (degrees). Positive is north of equator; negative is south.
00020 float64 latitude
00021 
00022 # Longitude (degrees). Positive is east of prime meridian, negative west.
00023 float64 longitude
00024 
00025 # Altitude (meters). Positive is above reference (e.g., sea level).
00026 float64 altitude
00027 
00028 # Direction (degrees from north)
00029 float64 track
00030 
00031 # Ground speed (meters/second)
00032 float64 speed
00033 
00034 # Vertical speed (meters/second)
00035 float64 climb
00036 
00037 # Device orientation (units in degrees)
00038 float64 pitch
00039 float64 roll
00040 float64 dip
00041 
00042 # GPS time
00043 float64 time
00044 
00045 ## Dilution of precision; Xdop<=0 means the value is unknown
00046 
00047 # Total (positional-temporal) dilution of precision
00048 float64 gdop
00049 
00050 # Positional (3D) dilution of precision
00051 float64 pdop
00052 
00053 # Horizontal dilution of precision
00054 float64 hdop
00055 
00056 # Vertical dilution of precision
00057 float64 vdop
00058 
00059 # Temporal dilution of precision
00060 float64 tdop
00061 
00062 ## Uncertainty of measurement, 95% confidence
00063 
00064 # Spherical position uncertainty (meters) [epe]
00065 float64 err
00066 
00067 # Horizontal position uncertainty (meters) [eph]
00068 float64 err_horz
00069 
00070 # Vertical position uncertainty (meters) [epv]
00071 float64 err_vert
00072 
00073 # Track uncertainty (degrees) [epd]
00074 float64 err_track
00075 
00076 # Ground speed uncertainty (meters/second) [eps]
00077 float64 err_speed
00078 
00079 # Vertical speed uncertainty (meters/second) [epc]
00080 float64 err_climb
00081 
00082 # Temporal uncertainty [ept]
00083 float64 err_time
00084 
00085 # Orientation uncertainty (degrees)
00086 float64 err_pitch
00087 float64 err_roll
00088 float64 err_dip
00089 
00090 # Position covariance [m^2] defined relative to a tangential plane
00091 # through the reported position. The components are East, North, and
00092 # Up (ENU), in row-major order.
00093 
00094 float64[9] position_covariance
00095 
00096 uint8 COVARIANCE_TYPE_UNKNOWN = 0
00097 uint8 COVARIANCE_TYPE_APPROXIMATED = 1
00098 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2
00099 uint8 COVARIANCE_TYPE_KNOWN = 3
00100 
00101 uint8 position_covariance_type
00102 
00103 
00104 ================================================================================
00105 MSG: std_msgs/Header
00106 # Standard metadata for higher-level stamped data types.
00107 # This is generally used to communicate timestamped data 
00108 # in a particular coordinate frame.
00109 # 
00110 # sequence ID: consecutively increasing ID 
00111 uint32 seq
00112 #Two-integer timestamp that is expressed as:
00113 # * stamp.secs: seconds (stamp_secs) since epoch
00114 # * stamp.nsecs: nanoseconds since stamp_secs
00115 # time-handling sugar is provided by the client library
00116 time stamp
00117 #Frame this data is associated with
00118 # 0: no frame
00119 # 1: global frame
00120 string frame_id
00121 
00122 ================================================================================
00123 MSG: corobot_msgs/GPSStatus
00124 Header header
00125 
00126 # Satellites used in solution
00127 uint16 satellites_used # Number of satellites
00128 int32[] satellite_used_prn # PRN identifiers
00129 
00130 # Satellites visible
00131 uint16 satellites_visible
00132 int32[] satellite_visible_prn # PRN identifiers
00133 int32[] satellite_visible_z # Elevation of satellites
00134 int32[] satellite_visible_azimuth # Azimuth of satellites
00135 int32[] satellite_visible_snr # Signal-to-noise ratios (dB)
00136 
00137 # Measurement status
00138 int16 STATUS_NO_FIX=-1   # Unable to fix position
00139 int16 STATUS_FIX=0       # Normal fix
00140 int16 STATUS_SBAS_FIX=1  # Fixed using a satellite-based augmentation system
00141 int16 STATUS_GBAS_FIX=2  #          or a ground-based augmentation system
00142 int16 STATUS_DGPS_FIX=18 # Fixed with DGPS
00143 int16 STATUS_WAAS_FIX=33 # Fixed with WAAS
00144 int16 status
00145 
00146 uint16 SOURCE_NONE=0 # No information is available
00147 uint16 SOURCE_GPS=1 # Using standard GPS location [only valid for position_source]
00148 uint16 SOURCE_POINTS=2 # Motion/orientation fix is derived from successive points
00149 uint16 SOURCE_DOPPLER=4 # Motion is derived using the Doppler effect
00150 uint16 SOURCE_ALTIMETER=8 # Using an altimeter
00151 uint16 SOURCE_MAGNETIC=16 # Using magnetic sensors
00152 uint16 SOURCE_GYRO=32 # Using gyroscopes
00153 uint16 SOURCE_ACCEL=64 # Using accelerometers
00154 
00155 uint16 motion_source # Source for speed, climb and track
00156 uint16 orientation_source # Source for device orientation
00157 uint16 position_source # Source for position
00158 
00159 
00160 """
00161   # Pseudo-constants
00162   COVARIANCE_TYPE_UNKNOWN = 0
00163   COVARIANCE_TYPE_APPROXIMATED = 1
00164   COVARIANCE_TYPE_DIAGONAL_KNOWN = 2
00165   COVARIANCE_TYPE_KNOWN = 3
00166 
00167   __slots__ = ['header','status','latitude','longitude','altitude','track','speed','climb','pitch','roll','dip','time','gdop','pdop','hdop','vdop','tdop','err','err_horz','err_vert','err_track','err_speed','err_climb','err_time','err_pitch','err_roll','err_dip','position_covariance','position_covariance_type']
00168   _slot_types = ['std_msgs/Header','corobot_msgs/GPSStatus','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64','float64[9]','uint8']
00169 
00170   def __init__(self, *args, **kwds):
00171     """
00172     Constructor. Any message fields that are implicitly/explicitly
00173     set to None will be assigned a default value. The recommend
00174     use is keyword arguments as this is more robust to future message
00175     changes.  You cannot mix in-order arguments and keyword arguments.
00176 
00177     The available fields are:
00178        header,status,latitude,longitude,altitude,track,speed,climb,pitch,roll,dip,time,gdop,pdop,hdop,vdop,tdop,err,err_horz,err_vert,err_track,err_speed,err_climb,err_time,err_pitch,err_roll,err_dip,position_covariance,position_covariance_type
00179 
00180     :param args: complete set of field values, in .msg order
00181     :param kwds: use keyword arguments corresponding to message field names
00182     to set specific fields.
00183     """
00184     if args or kwds:
00185       super(GPSFix, self).__init__(*args, **kwds)
00186       #message fields cannot be None, assign default values for those that are
00187       if self.header is None:
00188         self.header = std_msgs.msg.Header()
00189       if self.status is None:
00190         self.status = corobot_msgs.msg.GPSStatus()
00191       if self.latitude is None:
00192         self.latitude = 0.
00193       if self.longitude is None:
00194         self.longitude = 0.
00195       if self.altitude is None:
00196         self.altitude = 0.
00197       if self.track is None:
00198         self.track = 0.
00199       if self.speed is None:
00200         self.speed = 0.
00201       if self.climb is None:
00202         self.climb = 0.
00203       if self.pitch is None:
00204         self.pitch = 0.
00205       if self.roll is None:
00206         self.roll = 0.
00207       if self.dip is None:
00208         self.dip = 0.
00209       if self.time is None:
00210         self.time = 0.
00211       if self.gdop is None:
00212         self.gdop = 0.
00213       if self.pdop is None:
00214         self.pdop = 0.
00215       if self.hdop is None:
00216         self.hdop = 0.
00217       if self.vdop is None:
00218         self.vdop = 0.
00219       if self.tdop is None:
00220         self.tdop = 0.
00221       if self.err is None:
00222         self.err = 0.
00223       if self.err_horz is None:
00224         self.err_horz = 0.
00225       if self.err_vert is None:
00226         self.err_vert = 0.
00227       if self.err_track is None:
00228         self.err_track = 0.
00229       if self.err_speed is None:
00230         self.err_speed = 0.
00231       if self.err_climb is None:
00232         self.err_climb = 0.
00233       if self.err_time is None:
00234         self.err_time = 0.
00235       if self.err_pitch is None:
00236         self.err_pitch = 0.
00237       if self.err_roll is None:
00238         self.err_roll = 0.
00239       if self.err_dip is None:
00240         self.err_dip = 0.
00241       if self.position_covariance is None:
00242         self.position_covariance = [0.,0.,0.,0.,0.,0.,0.,0.,0.]
00243       if self.position_covariance_type is None:
00244         self.position_covariance_type = 0
00245     else:
00246       self.header = std_msgs.msg.Header()
00247       self.status = corobot_msgs.msg.GPSStatus()
00248       self.latitude = 0.
00249       self.longitude = 0.
00250       self.altitude = 0.
00251       self.track = 0.
00252       self.speed = 0.
00253       self.climb = 0.
00254       self.pitch = 0.
00255       self.roll = 0.
00256       self.dip = 0.
00257       self.time = 0.
00258       self.gdop = 0.
00259       self.pdop = 0.
00260       self.hdop = 0.
00261       self.vdop = 0.
00262       self.tdop = 0.
00263       self.err = 0.
00264       self.err_horz = 0.
00265       self.err_vert = 0.
00266       self.err_track = 0.
00267       self.err_speed = 0.
00268       self.err_climb = 0.
00269       self.err_time = 0.
00270       self.err_pitch = 0.
00271       self.err_roll = 0.
00272       self.err_dip = 0.
00273       self.position_covariance = [0.,0.,0.,0.,0.,0.,0.,0.,0.]
00274       self.position_covariance_type = 0
00275 
00276   def _get_types(self):
00277     """
00278     internal API method
00279     """
00280     return self._slot_types
00281 
00282   def serialize(self, buff):
00283     """
00284     serialize message into buffer
00285     :param buff: buffer, ``StringIO``
00286     """
00287     try:
00288       _x = self
00289       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00290       _x = self.header.frame_id
00291       length = len(_x)
00292       if python3 or type(_x) == unicode:
00293         _x = _x.encode('utf-8')
00294         length = len(_x)
00295       buff.write(struct.pack('<I%ss'%length, length, _x))
00296       _x = self
00297       buff.write(_struct_3I.pack(_x.status.header.seq, _x.status.header.stamp.secs, _x.status.header.stamp.nsecs))
00298       _x = self.status.header.frame_id
00299       length = len(_x)
00300       if python3 or type(_x) == unicode:
00301         _x = _x.encode('utf-8')
00302         length = len(_x)
00303       buff.write(struct.pack('<I%ss'%length, length, _x))
00304       buff.write(_struct_H.pack(self.status.satellites_used))
00305       length = len(self.status.satellite_used_prn)
00306       buff.write(_struct_I.pack(length))
00307       pattern = '<%si'%length
00308       buff.write(struct.pack(pattern, *self.status.satellite_used_prn))
00309       buff.write(_struct_H.pack(self.status.satellites_visible))
00310       length = len(self.status.satellite_visible_prn)
00311       buff.write(_struct_I.pack(length))
00312       pattern = '<%si'%length
00313       buff.write(struct.pack(pattern, *self.status.satellite_visible_prn))
00314       length = len(self.status.satellite_visible_z)
00315       buff.write(_struct_I.pack(length))
00316       pattern = '<%si'%length
00317       buff.write(struct.pack(pattern, *self.status.satellite_visible_z))
00318       length = len(self.status.satellite_visible_azimuth)
00319       buff.write(_struct_I.pack(length))
00320       pattern = '<%si'%length
00321       buff.write(struct.pack(pattern, *self.status.satellite_visible_azimuth))
00322       length = len(self.status.satellite_visible_snr)
00323       buff.write(_struct_I.pack(length))
00324       pattern = '<%si'%length
00325       buff.write(struct.pack(pattern, *self.status.satellite_visible_snr))
00326       _x = self
00327       buff.write(_struct_h3H25d.pack(_x.status.status, _x.status.motion_source, _x.status.orientation_source, _x.status.position_source, _x.latitude, _x.longitude, _x.altitude, _x.track, _x.speed, _x.climb, _x.pitch, _x.roll, _x.dip, _x.time, _x.gdop, _x.pdop, _x.hdop, _x.vdop, _x.tdop, _x.err, _x.err_horz, _x.err_vert, _x.err_track, _x.err_speed, _x.err_climb, _x.err_time, _x.err_pitch, _x.err_roll, _x.err_dip))
00328       buff.write(_struct_9d.pack(*self.position_covariance))
00329       buff.write(_struct_B.pack(self.position_covariance_type))
00330     except struct.error as se: self._check_types(se)
00331     except TypeError as te: self._check_types(te)
00332 
00333   def deserialize(self, str):
00334     """
00335     unpack serialized message in str into this message instance
00336     :param str: byte array of serialized message, ``str``
00337     """
00338     try:
00339       if self.header is None:
00340         self.header = std_msgs.msg.Header()
00341       if self.status is None:
00342         self.status = corobot_msgs.msg.GPSStatus()
00343       end = 0
00344       _x = self
00345       start = end
00346       end += 12
00347       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00348       start = end
00349       end += 4
00350       (length,) = _struct_I.unpack(str[start:end])
00351       start = end
00352       end += length
00353       if python3:
00354         self.header.frame_id = str[start:end].decode('utf-8')
00355       else:
00356         self.header.frame_id = str[start:end]
00357       _x = self
00358       start = end
00359       end += 12
00360       (_x.status.header.seq, _x.status.header.stamp.secs, _x.status.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00361       start = end
00362       end += 4
00363       (length,) = _struct_I.unpack(str[start:end])
00364       start = end
00365       end += length
00366       if python3:
00367         self.status.header.frame_id = str[start:end].decode('utf-8')
00368       else:
00369         self.status.header.frame_id = str[start:end]
00370       start = end
00371       end += 2
00372       (self.status.satellites_used,) = _struct_H.unpack(str[start:end])
00373       start = end
00374       end += 4
00375       (length,) = _struct_I.unpack(str[start:end])
00376       pattern = '<%si'%length
00377       start = end
00378       end += struct.calcsize(pattern)
00379       self.status.satellite_used_prn = struct.unpack(pattern, str[start:end])
00380       start = end
00381       end += 2
00382       (self.status.satellites_visible,) = _struct_H.unpack(str[start:end])
00383       start = end
00384       end += 4
00385       (length,) = _struct_I.unpack(str[start:end])
00386       pattern = '<%si'%length
00387       start = end
00388       end += struct.calcsize(pattern)
00389       self.status.satellite_visible_prn = struct.unpack(pattern, str[start:end])
00390       start = end
00391       end += 4
00392       (length,) = _struct_I.unpack(str[start:end])
00393       pattern = '<%si'%length
00394       start = end
00395       end += struct.calcsize(pattern)
00396       self.status.satellite_visible_z = struct.unpack(pattern, str[start:end])
00397       start = end
00398       end += 4
00399       (length,) = _struct_I.unpack(str[start:end])
00400       pattern = '<%si'%length
00401       start = end
00402       end += struct.calcsize(pattern)
00403       self.status.satellite_visible_azimuth = struct.unpack(pattern, str[start:end])
00404       start = end
00405       end += 4
00406       (length,) = _struct_I.unpack(str[start:end])
00407       pattern = '<%si'%length
00408       start = end
00409       end += struct.calcsize(pattern)
00410       self.status.satellite_visible_snr = struct.unpack(pattern, str[start:end])
00411       _x = self
00412       start = end
00413       end += 208
00414       (_x.status.status, _x.status.motion_source, _x.status.orientation_source, _x.status.position_source, _x.latitude, _x.longitude, _x.altitude, _x.track, _x.speed, _x.climb, _x.pitch, _x.roll, _x.dip, _x.time, _x.gdop, _x.pdop, _x.hdop, _x.vdop, _x.tdop, _x.err, _x.err_horz, _x.err_vert, _x.err_track, _x.err_speed, _x.err_climb, _x.err_time, _x.err_pitch, _x.err_roll, _x.err_dip,) = _struct_h3H25d.unpack(str[start:end])
00415       start = end
00416       end += 72
00417       self.position_covariance = _struct_9d.unpack(str[start:end])
00418       start = end
00419       end += 1
00420       (self.position_covariance_type,) = _struct_B.unpack(str[start:end])
00421       return self
00422     except struct.error as e:
00423       raise genpy.DeserializationError(e) #most likely buffer underfill
00424 
00425 
00426   def serialize_numpy(self, buff, numpy):
00427     """
00428     serialize message with numpy array types into buffer
00429     :param buff: buffer, ``StringIO``
00430     :param numpy: numpy python module
00431     """
00432     try:
00433       _x = self
00434       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00435       _x = self.header.frame_id
00436       length = len(_x)
00437       if python3 or type(_x) == unicode:
00438         _x = _x.encode('utf-8')
00439         length = len(_x)
00440       buff.write(struct.pack('<I%ss'%length, length, _x))
00441       _x = self
00442       buff.write(_struct_3I.pack(_x.status.header.seq, _x.status.header.stamp.secs, _x.status.header.stamp.nsecs))
00443       _x = self.status.header.frame_id
00444       length = len(_x)
00445       if python3 or type(_x) == unicode:
00446         _x = _x.encode('utf-8')
00447         length = len(_x)
00448       buff.write(struct.pack('<I%ss'%length, length, _x))
00449       buff.write(_struct_H.pack(self.status.satellites_used))
00450       length = len(self.status.satellite_used_prn)
00451       buff.write(_struct_I.pack(length))
00452       pattern = '<%si'%length
00453       buff.write(self.status.satellite_used_prn.tostring())
00454       buff.write(_struct_H.pack(self.status.satellites_visible))
00455       length = len(self.status.satellite_visible_prn)
00456       buff.write(_struct_I.pack(length))
00457       pattern = '<%si'%length
00458       buff.write(self.status.satellite_visible_prn.tostring())
00459       length = len(self.status.satellite_visible_z)
00460       buff.write(_struct_I.pack(length))
00461       pattern = '<%si'%length
00462       buff.write(self.status.satellite_visible_z.tostring())
00463       length = len(self.status.satellite_visible_azimuth)
00464       buff.write(_struct_I.pack(length))
00465       pattern = '<%si'%length
00466       buff.write(self.status.satellite_visible_azimuth.tostring())
00467       length = len(self.status.satellite_visible_snr)
00468       buff.write(_struct_I.pack(length))
00469       pattern = '<%si'%length
00470       buff.write(self.status.satellite_visible_snr.tostring())
00471       _x = self
00472       buff.write(_struct_h3H25d.pack(_x.status.status, _x.status.motion_source, _x.status.orientation_source, _x.status.position_source, _x.latitude, _x.longitude, _x.altitude, _x.track, _x.speed, _x.climb, _x.pitch, _x.roll, _x.dip, _x.time, _x.gdop, _x.pdop, _x.hdop, _x.vdop, _x.tdop, _x.err, _x.err_horz, _x.err_vert, _x.err_track, _x.err_speed, _x.err_climb, _x.err_time, _x.err_pitch, _x.err_roll, _x.err_dip))
00473       buff.write(self.position_covariance.tostring())
00474       buff.write(_struct_B.pack(self.position_covariance_type))
00475     except struct.error as se: self._check_types(se)
00476     except TypeError as te: self._check_types(te)
00477 
00478   def deserialize_numpy(self, str, numpy):
00479     """
00480     unpack serialized message in str into this message instance using numpy for array types
00481     :param str: byte array of serialized message, ``str``
00482     :param numpy: numpy python module
00483     """
00484     try:
00485       if self.header is None:
00486         self.header = std_msgs.msg.Header()
00487       if self.status is None:
00488         self.status = corobot_msgs.msg.GPSStatus()
00489       end = 0
00490       _x = self
00491       start = end
00492       end += 12
00493       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00494       start = end
00495       end += 4
00496       (length,) = _struct_I.unpack(str[start:end])
00497       start = end
00498       end += length
00499       if python3:
00500         self.header.frame_id = str[start:end].decode('utf-8')
00501       else:
00502         self.header.frame_id = str[start:end]
00503       _x = self
00504       start = end
00505       end += 12
00506       (_x.status.header.seq, _x.status.header.stamp.secs, _x.status.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00507       start = end
00508       end += 4
00509       (length,) = _struct_I.unpack(str[start:end])
00510       start = end
00511       end += length
00512       if python3:
00513         self.status.header.frame_id = str[start:end].decode('utf-8')
00514       else:
00515         self.status.header.frame_id = str[start:end]
00516       start = end
00517       end += 2
00518       (self.status.satellites_used,) = _struct_H.unpack(str[start:end])
00519       start = end
00520       end += 4
00521       (length,) = _struct_I.unpack(str[start:end])
00522       pattern = '<%si'%length
00523       start = end
00524       end += struct.calcsize(pattern)
00525       self.status.satellite_used_prn = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00526       start = end
00527       end += 2
00528       (self.status.satellites_visible,) = _struct_H.unpack(str[start:end])
00529       start = end
00530       end += 4
00531       (length,) = _struct_I.unpack(str[start:end])
00532       pattern = '<%si'%length
00533       start = end
00534       end += struct.calcsize(pattern)
00535       self.status.satellite_visible_prn = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00536       start = end
00537       end += 4
00538       (length,) = _struct_I.unpack(str[start:end])
00539       pattern = '<%si'%length
00540       start = end
00541       end += struct.calcsize(pattern)
00542       self.status.satellite_visible_z = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00543       start = end
00544       end += 4
00545       (length,) = _struct_I.unpack(str[start:end])
00546       pattern = '<%si'%length
00547       start = end
00548       end += struct.calcsize(pattern)
00549       self.status.satellite_visible_azimuth = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00550       start = end
00551       end += 4
00552       (length,) = _struct_I.unpack(str[start:end])
00553       pattern = '<%si'%length
00554       start = end
00555       end += struct.calcsize(pattern)
00556       self.status.satellite_visible_snr = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00557       _x = self
00558       start = end
00559       end += 208
00560       (_x.status.status, _x.status.motion_source, _x.status.orientation_source, _x.status.position_source, _x.latitude, _x.longitude, _x.altitude, _x.track, _x.speed, _x.climb, _x.pitch, _x.roll, _x.dip, _x.time, _x.gdop, _x.pdop, _x.hdop, _x.vdop, _x.tdop, _x.err, _x.err_horz, _x.err_vert, _x.err_track, _x.err_speed, _x.err_climb, _x.err_time, _x.err_pitch, _x.err_roll, _x.err_dip,) = _struct_h3H25d.unpack(str[start:end])
00561       start = end
00562       end += 72
00563       self.position_covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9)
00564       start = end
00565       end += 1
00566       (self.position_covariance_type,) = _struct_B.unpack(str[start:end])
00567       return self
00568     except struct.error as e:
00569       raise genpy.DeserializationError(e) #most likely buffer underfill
00570 
00571 _struct_I = genpy.struct_I
00572 _struct_h3H25d = struct.Struct("<h3H25d")
00573 _struct_H = struct.Struct("<H")
00574 _struct_3I = struct.Struct("<3I")
00575 _struct_B = struct.Struct("<B")
00576 _struct_9d = struct.Struct("<9d")


corobot_msgs
Author(s): Morgan Cormier/mcormier@coroware.com
autogenerated on Tue Jan 7 2014 11:38:41