_GeographicMapChanges.py
Go to the documentation of this file.
00001 """autogenerated by genpy from geographic_msgs/GeographicMapChanges.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 uuid_msgs.msg
00008 import geographic_msgs.msg
00009 import std_msgs.msg
00010 
00011 class GeographicMapChanges(genpy.Message):
00012   _md5sum = "4fd027f54298203ec12aa1c4b20e6cb8"
00013   _type = "geographic_msgs/GeographicMapChanges"
00014   _has_header = True #flag to mark the presence of a Header object
00015   _full_text = """# A list of geographic map changes.
00016 
00017 Header header                   # stamp specifies time of change
00018                                 # frame_id (normally /map)
00019 
00020 GeographicMap diffs             # new and changed points and features
00021 uuid_msgs/UniqueID[] deletes    # deleted map components
00022 
00023 ================================================================================
00024 MSG: std_msgs/Header
00025 # Standard metadata for higher-level stamped data types.
00026 # This is generally used to communicate timestamped data 
00027 # in a particular coordinate frame.
00028 # 
00029 # sequence ID: consecutively increasing ID 
00030 uint32 seq
00031 #Two-integer timestamp that is expressed as:
00032 # * stamp.secs: seconds (stamp_secs) since epoch
00033 # * stamp.nsecs: nanoseconds since stamp_secs
00034 # time-handling sugar is provided by the client library
00035 time stamp
00036 #Frame this data is associated with
00037 # 0: no frame
00038 # 1: global frame
00039 string frame_id
00040 
00041 ================================================================================
00042 MSG: geographic_msgs/GeographicMap
00043 # Geographic map for a specified region.
00044 
00045 Header header            # stamp specifies time
00046                          # frame_id (normally /map)
00047 
00048 uuid_msgs/UniqueID id    # identifier for this map
00049 BoundingBox  bounds      # 2D bounding box containing map
00050 
00051 WayPoint[]   points      # way-points
00052 MapFeature[] features    # map features
00053 KeyValue[]   props       # map properties
00054 
00055 ================================================================================
00056 MSG: uuid_msgs/UniqueID
00057 # A universally unique identifier (UUID).
00058 #
00059 #  http://en.wikipedia.org/wiki/Universally_unique_identifier
00060 #  http://tools.ietf.org/html/rfc4122.html
00061 
00062 uint8[16] uuid
00063 
00064 ================================================================================
00065 MSG: geographic_msgs/BoundingBox
00066 # Geographic map bounding box. 
00067 #
00068 # The two GeoPoints denote diagonally opposite corners of the box.
00069 #
00070 # If min_pt.latitude is NaN, the bounding box is "global", matching
00071 # any valid latitude, longitude and altitude.
00072 #
00073 # If min_pt.altitude is NaN, the bounding box is two-dimensional and
00074 # matches any altitude within the specified latitude and longitude
00075 # range.
00076 
00077 GeoPoint min_pt         # lowest and most Southwestern corner
00078 GeoPoint max_pt         # highest and most Northeastern corner
00079 
00080 ================================================================================
00081 MSG: geographic_msgs/GeoPoint
00082 # Geographic point, using the WGS 84 reference ellipsoid.
00083 
00084 # Latitude [degrees]. Positive is north of equator; negative is south
00085 # (-90 <= latitude <= +90).
00086 float64 latitude
00087 
00088 # Longitude [degrees]. Positive is east of prime meridian; negative is
00089 # west (-180 <= longitude <= +180). At the poles, latitude is -90 or
00090 # +90, and longitude is irrelevant, but must be in range.
00091 float64 longitude
00092 
00093 # Altitude [m]. Positive is above the WGS 84 ellipsoid (NaN if unspecified).
00094 float64 altitude
00095 
00096 ================================================================================
00097 MSG: geographic_msgs/WayPoint
00098 # Way-point element for a geographic map.
00099 
00100 uuid_msgs/UniqueID id   # Unique way-point identifier
00101 GeoPoint   position     # Position relative to WGS 84 ellipsoid
00102 KeyValue[] props        # Key/value properties for this point
00103 
00104 ================================================================================
00105 MSG: geographic_msgs/KeyValue
00106 # Geographic map tag (key, value) pair
00107 #
00108 # This is equivalent to diagnostic_msgs/KeyValue, repeated here to
00109 # avoid introducing a trivial stack dependency.
00110 
00111 string key                     # tag label
00112 string value                   # corresponding value
00113 
00114 ================================================================================
00115 MSG: geographic_msgs/MapFeature
00116 # Geographic map feature.
00117 #
00118 # A list of WayPoint IDs for features like streets, highways, hiking
00119 # trails, the outlines of buildings and parking lots in sequential
00120 # order.
00121 #
00122 # Feature lists may also contain other feature lists as members.
00123 
00124 uuid_msgs/UniqueID   id         # Unique feature identifier
00125 uuid_msgs/UniqueID[] components # Sequence of feature components
00126 KeyValue[] props                # Key/value properties for this feature
00127 
00128 """
00129   __slots__ = ['header','diffs','deletes']
00130   _slot_types = ['std_msgs/Header','geographic_msgs/GeographicMap','uuid_msgs/UniqueID[]']
00131 
00132   def __init__(self, *args, **kwds):
00133     """
00134     Constructor. Any message fields that are implicitly/explicitly
00135     set to None will be assigned a default value. The recommend
00136     use is keyword arguments as this is more robust to future message
00137     changes.  You cannot mix in-order arguments and keyword arguments.
00138 
00139     The available fields are:
00140        header,diffs,deletes
00141 
00142     :param args: complete set of field values, in .msg order
00143     :param kwds: use keyword arguments corresponding to message field names
00144     to set specific fields.
00145     """
00146     if args or kwds:
00147       super(GeographicMapChanges, self).__init__(*args, **kwds)
00148       #message fields cannot be None, assign default values for those that are
00149       if self.header is None:
00150         self.header = std_msgs.msg.Header()
00151       if self.diffs is None:
00152         self.diffs = geographic_msgs.msg.GeographicMap()
00153       if self.deletes is None:
00154         self.deletes = []
00155     else:
00156       self.header = std_msgs.msg.Header()
00157       self.diffs = geographic_msgs.msg.GeographicMap()
00158       self.deletes = []
00159 
00160   def _get_types(self):
00161     """
00162     internal API method
00163     """
00164     return self._slot_types
00165 
00166   def serialize(self, buff):
00167     """
00168     serialize message into buffer
00169     :param buff: buffer, ``StringIO``
00170     """
00171     try:
00172       _x = self
00173       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00174       _x = self.header.frame_id
00175       length = len(_x)
00176       if python3 or type(_x) == unicode:
00177         _x = _x.encode('utf-8')
00178         length = len(_x)
00179       buff.write(struct.pack('<I%ss'%length, length, _x))
00180       _x = self
00181       buff.write(_struct_3I.pack(_x.diffs.header.seq, _x.diffs.header.stamp.secs, _x.diffs.header.stamp.nsecs))
00182       _x = self.diffs.header.frame_id
00183       length = len(_x)
00184       if python3 or type(_x) == unicode:
00185         _x = _x.encode('utf-8')
00186         length = len(_x)
00187       buff.write(struct.pack('<I%ss'%length, length, _x))
00188       _x = self.diffs.id.uuid
00189       # - if encoded as a list instead, serialize as bytes instead of string
00190       if type(_x) in [list, tuple]:
00191         buff.write(_struct_16B.pack(*_x))
00192       else:
00193         buff.write(_struct_16s.pack(_x))
00194       _x = self
00195       buff.write(_struct_6d.pack(_x.diffs.bounds.min_pt.latitude, _x.diffs.bounds.min_pt.longitude, _x.diffs.bounds.min_pt.altitude, _x.diffs.bounds.max_pt.latitude, _x.diffs.bounds.max_pt.longitude, _x.diffs.bounds.max_pt.altitude))
00196       length = len(self.diffs.points)
00197       buff.write(_struct_I.pack(length))
00198       for val1 in self.diffs.points:
00199         _v1 = val1.id
00200         _x = _v1.uuid
00201         # - if encoded as a list instead, serialize as bytes instead of string
00202         if type(_x) in [list, tuple]:
00203           buff.write(_struct_16B.pack(*_x))
00204         else:
00205           buff.write(_struct_16s.pack(_x))
00206         _v2 = val1.position
00207         _x = _v2
00208         buff.write(_struct_3d.pack(_x.latitude, _x.longitude, _x.altitude))
00209         length = len(val1.props)
00210         buff.write(_struct_I.pack(length))
00211         for val2 in val1.props:
00212           _x = val2.key
00213           length = len(_x)
00214           if python3 or type(_x) == unicode:
00215             _x = _x.encode('utf-8')
00216             length = len(_x)
00217           buff.write(struct.pack('<I%ss'%length, length, _x))
00218           _x = val2.value
00219           length = len(_x)
00220           if python3 or type(_x) == unicode:
00221             _x = _x.encode('utf-8')
00222             length = len(_x)
00223           buff.write(struct.pack('<I%ss'%length, length, _x))
00224       length = len(self.diffs.features)
00225       buff.write(_struct_I.pack(length))
00226       for val1 in self.diffs.features:
00227         _v3 = val1.id
00228         _x = _v3.uuid
00229         # - if encoded as a list instead, serialize as bytes instead of string
00230         if type(_x) in [list, tuple]:
00231           buff.write(_struct_16B.pack(*_x))
00232         else:
00233           buff.write(_struct_16s.pack(_x))
00234         length = len(val1.components)
00235         buff.write(_struct_I.pack(length))
00236         for val2 in val1.components:
00237           _x = val2.uuid
00238           # - if encoded as a list instead, serialize as bytes instead of string
00239           if type(_x) in [list, tuple]:
00240             buff.write(_struct_16B.pack(*_x))
00241           else:
00242             buff.write(_struct_16s.pack(_x))
00243         length = len(val1.props)
00244         buff.write(_struct_I.pack(length))
00245         for val2 in val1.props:
00246           _x = val2.key
00247           length = len(_x)
00248           if python3 or type(_x) == unicode:
00249             _x = _x.encode('utf-8')
00250             length = len(_x)
00251           buff.write(struct.pack('<I%ss'%length, length, _x))
00252           _x = val2.value
00253           length = len(_x)
00254           if python3 or type(_x) == unicode:
00255             _x = _x.encode('utf-8')
00256             length = len(_x)
00257           buff.write(struct.pack('<I%ss'%length, length, _x))
00258       length = len(self.diffs.props)
00259       buff.write(_struct_I.pack(length))
00260       for val1 in self.diffs.props:
00261         _x = val1.key
00262         length = len(_x)
00263         if python3 or type(_x) == unicode:
00264           _x = _x.encode('utf-8')
00265           length = len(_x)
00266         buff.write(struct.pack('<I%ss'%length, length, _x))
00267         _x = val1.value
00268         length = len(_x)
00269         if python3 or type(_x) == unicode:
00270           _x = _x.encode('utf-8')
00271           length = len(_x)
00272         buff.write(struct.pack('<I%ss'%length, length, _x))
00273       length = len(self.deletes)
00274       buff.write(_struct_I.pack(length))
00275       for val1 in self.deletes:
00276         _x = val1.uuid
00277         # - if encoded as a list instead, serialize as bytes instead of string
00278         if type(_x) in [list, tuple]:
00279           buff.write(_struct_16B.pack(*_x))
00280         else:
00281           buff.write(_struct_16s.pack(_x))
00282     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00283     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00284 
00285   def deserialize(self, str):
00286     """
00287     unpack serialized message in str into this message instance
00288     :param str: byte array of serialized message, ``str``
00289     """
00290     try:
00291       if self.header is None:
00292         self.header = std_msgs.msg.Header()
00293       if self.diffs is None:
00294         self.diffs = geographic_msgs.msg.GeographicMap()
00295       if self.deletes is None:
00296         self.deletes = None
00297       end = 0
00298       _x = self
00299       start = end
00300       end += 12
00301       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00302       start = end
00303       end += 4
00304       (length,) = _struct_I.unpack(str[start:end])
00305       start = end
00306       end += length
00307       if python3:
00308         self.header.frame_id = str[start:end].decode('utf-8')
00309       else:
00310         self.header.frame_id = str[start:end]
00311       _x = self
00312       start = end
00313       end += 12
00314       (_x.diffs.header.seq, _x.diffs.header.stamp.secs, _x.diffs.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00315       start = end
00316       end += 4
00317       (length,) = _struct_I.unpack(str[start:end])
00318       start = end
00319       end += length
00320       if python3:
00321         self.diffs.header.frame_id = str[start:end].decode('utf-8')
00322       else:
00323         self.diffs.header.frame_id = str[start:end]
00324       start = end
00325       end += 16
00326       self.diffs.id.uuid = str[start:end]
00327       _x = self
00328       start = end
00329       end += 48
00330       (_x.diffs.bounds.min_pt.latitude, _x.diffs.bounds.min_pt.longitude, _x.diffs.bounds.min_pt.altitude, _x.diffs.bounds.max_pt.latitude, _x.diffs.bounds.max_pt.longitude, _x.diffs.bounds.max_pt.altitude,) = _struct_6d.unpack(str[start:end])
00331       start = end
00332       end += 4
00333       (length,) = _struct_I.unpack(str[start:end])
00334       self.diffs.points = []
00335       for i in range(0, length):
00336         val1 = geographic_msgs.msg.WayPoint()
00337         _v4 = val1.id
00338         start = end
00339         end += 16
00340         _v4.uuid = str[start:end]
00341         _v5 = val1.position
00342         _x = _v5
00343         start = end
00344         end += 24
00345         (_x.latitude, _x.longitude, _x.altitude,) = _struct_3d.unpack(str[start:end])
00346         start = end
00347         end += 4
00348         (length,) = _struct_I.unpack(str[start:end])
00349         val1.props = []
00350         for i in range(0, length):
00351           val2 = geographic_msgs.msg.KeyValue()
00352           start = end
00353           end += 4
00354           (length,) = _struct_I.unpack(str[start:end])
00355           start = end
00356           end += length
00357           if python3:
00358             val2.key = str[start:end].decode('utf-8')
00359           else:
00360             val2.key = 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             val2.value = str[start:end].decode('utf-8')
00368           else:
00369             val2.value = str[start:end]
00370           val1.props.append(val2)
00371         self.diffs.points.append(val1)
00372       start = end
00373       end += 4
00374       (length,) = _struct_I.unpack(str[start:end])
00375       self.diffs.features = []
00376       for i in range(0, length):
00377         val1 = geographic_msgs.msg.MapFeature()
00378         _v6 = val1.id
00379         start = end
00380         end += 16
00381         _v6.uuid = str[start:end]
00382         start = end
00383         end += 4
00384         (length,) = _struct_I.unpack(str[start:end])
00385         val1.components = []
00386         for i in range(0, length):
00387           val2 = uuid_msgs.msg.UniqueID()
00388           start = end
00389           end += 16
00390           val2.uuid = str[start:end]
00391           val1.components.append(val2)
00392         start = end
00393         end += 4
00394         (length,) = _struct_I.unpack(str[start:end])
00395         val1.props = []
00396         for i in range(0, length):
00397           val2 = geographic_msgs.msg.KeyValue()
00398           start = end
00399           end += 4
00400           (length,) = _struct_I.unpack(str[start:end])
00401           start = end
00402           end += length
00403           if python3:
00404             val2.key = str[start:end].decode('utf-8')
00405           else:
00406             val2.key = str[start:end]
00407           start = end
00408           end += 4
00409           (length,) = _struct_I.unpack(str[start:end])
00410           start = end
00411           end += length
00412           if python3:
00413             val2.value = str[start:end].decode('utf-8')
00414           else:
00415             val2.value = str[start:end]
00416           val1.props.append(val2)
00417         self.diffs.features.append(val1)
00418       start = end
00419       end += 4
00420       (length,) = _struct_I.unpack(str[start:end])
00421       self.diffs.props = []
00422       for i in range(0, length):
00423         val1 = geographic_msgs.msg.KeyValue()
00424         start = end
00425         end += 4
00426         (length,) = _struct_I.unpack(str[start:end])
00427         start = end
00428         end += length
00429         if python3:
00430           val1.key = str[start:end].decode('utf-8')
00431         else:
00432           val1.key = str[start:end]
00433         start = end
00434         end += 4
00435         (length,) = _struct_I.unpack(str[start:end])
00436         start = end
00437         end += length
00438         if python3:
00439           val1.value = str[start:end].decode('utf-8')
00440         else:
00441           val1.value = str[start:end]
00442         self.diffs.props.append(val1)
00443       start = end
00444       end += 4
00445       (length,) = _struct_I.unpack(str[start:end])
00446       self.deletes = []
00447       for i in range(0, length):
00448         val1 = uuid_msgs.msg.UniqueID()
00449         start = end
00450         end += 16
00451         val1.uuid = str[start:end]
00452         self.deletes.append(val1)
00453       return self
00454     except struct.error as e:
00455       raise genpy.DeserializationError(e) #most likely buffer underfill
00456 
00457 
00458   def serialize_numpy(self, buff, numpy):
00459     """
00460     serialize message with numpy array types into buffer
00461     :param buff: buffer, ``StringIO``
00462     :param numpy: numpy python module
00463     """
00464     try:
00465       _x = self
00466       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00467       _x = self.header.frame_id
00468       length = len(_x)
00469       if python3 or type(_x) == unicode:
00470         _x = _x.encode('utf-8')
00471         length = len(_x)
00472       buff.write(struct.pack('<I%ss'%length, length, _x))
00473       _x = self
00474       buff.write(_struct_3I.pack(_x.diffs.header.seq, _x.diffs.header.stamp.secs, _x.diffs.header.stamp.nsecs))
00475       _x = self.diffs.header.frame_id
00476       length = len(_x)
00477       if python3 or type(_x) == unicode:
00478         _x = _x.encode('utf-8')
00479         length = len(_x)
00480       buff.write(struct.pack('<I%ss'%length, length, _x))
00481       _x = self.diffs.id.uuid
00482       # - if encoded as a list instead, serialize as bytes instead of string
00483       if type(_x) in [list, tuple]:
00484         buff.write(_struct_16B.pack(*_x))
00485       else:
00486         buff.write(_struct_16s.pack(_x))
00487       _x = self
00488       buff.write(_struct_6d.pack(_x.diffs.bounds.min_pt.latitude, _x.diffs.bounds.min_pt.longitude, _x.diffs.bounds.min_pt.altitude, _x.diffs.bounds.max_pt.latitude, _x.diffs.bounds.max_pt.longitude, _x.diffs.bounds.max_pt.altitude))
00489       length = len(self.diffs.points)
00490       buff.write(_struct_I.pack(length))
00491       for val1 in self.diffs.points:
00492         _v7 = val1.id
00493         _x = _v7.uuid
00494         # - if encoded as a list instead, serialize as bytes instead of string
00495         if type(_x) in [list, tuple]:
00496           buff.write(_struct_16B.pack(*_x))
00497         else:
00498           buff.write(_struct_16s.pack(_x))
00499         _v8 = val1.position
00500         _x = _v8
00501         buff.write(_struct_3d.pack(_x.latitude, _x.longitude, _x.altitude))
00502         length = len(val1.props)
00503         buff.write(_struct_I.pack(length))
00504         for val2 in val1.props:
00505           _x = val2.key
00506           length = len(_x)
00507           if python3 or type(_x) == unicode:
00508             _x = _x.encode('utf-8')
00509             length = len(_x)
00510           buff.write(struct.pack('<I%ss'%length, length, _x))
00511           _x = val2.value
00512           length = len(_x)
00513           if python3 or type(_x) == unicode:
00514             _x = _x.encode('utf-8')
00515             length = len(_x)
00516           buff.write(struct.pack('<I%ss'%length, length, _x))
00517       length = len(self.diffs.features)
00518       buff.write(_struct_I.pack(length))
00519       for val1 in self.diffs.features:
00520         _v9 = val1.id
00521         _x = _v9.uuid
00522         # - if encoded as a list instead, serialize as bytes instead of string
00523         if type(_x) in [list, tuple]:
00524           buff.write(_struct_16B.pack(*_x))
00525         else:
00526           buff.write(_struct_16s.pack(_x))
00527         length = len(val1.components)
00528         buff.write(_struct_I.pack(length))
00529         for val2 in val1.components:
00530           _x = val2.uuid
00531           # - if encoded as a list instead, serialize as bytes instead of string
00532           if type(_x) in [list, tuple]:
00533             buff.write(_struct_16B.pack(*_x))
00534           else:
00535             buff.write(_struct_16s.pack(_x))
00536         length = len(val1.props)
00537         buff.write(_struct_I.pack(length))
00538         for val2 in val1.props:
00539           _x = val2.key
00540           length = len(_x)
00541           if python3 or type(_x) == unicode:
00542             _x = _x.encode('utf-8')
00543             length = len(_x)
00544           buff.write(struct.pack('<I%ss'%length, length, _x))
00545           _x = val2.value
00546           length = len(_x)
00547           if python3 or type(_x) == unicode:
00548             _x = _x.encode('utf-8')
00549             length = len(_x)
00550           buff.write(struct.pack('<I%ss'%length, length, _x))
00551       length = len(self.diffs.props)
00552       buff.write(_struct_I.pack(length))
00553       for val1 in self.diffs.props:
00554         _x = val1.key
00555         length = len(_x)
00556         if python3 or type(_x) == unicode:
00557           _x = _x.encode('utf-8')
00558           length = len(_x)
00559         buff.write(struct.pack('<I%ss'%length, length, _x))
00560         _x = val1.value
00561         length = len(_x)
00562         if python3 or type(_x) == unicode:
00563           _x = _x.encode('utf-8')
00564           length = len(_x)
00565         buff.write(struct.pack('<I%ss'%length, length, _x))
00566       length = len(self.deletes)
00567       buff.write(_struct_I.pack(length))
00568       for val1 in self.deletes:
00569         _x = val1.uuid
00570         # - if encoded as a list instead, serialize as bytes instead of string
00571         if type(_x) in [list, tuple]:
00572           buff.write(_struct_16B.pack(*_x))
00573         else:
00574           buff.write(_struct_16s.pack(_x))
00575     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00576     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00577 
00578   def deserialize_numpy(self, str, numpy):
00579     """
00580     unpack serialized message in str into this message instance using numpy for array types
00581     :param str: byte array of serialized message, ``str``
00582     :param numpy: numpy python module
00583     """
00584     try:
00585       if self.header is None:
00586         self.header = std_msgs.msg.Header()
00587       if self.diffs is None:
00588         self.diffs = geographic_msgs.msg.GeographicMap()
00589       if self.deletes is None:
00590         self.deletes = None
00591       end = 0
00592       _x = self
00593       start = end
00594       end += 12
00595       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00596       start = end
00597       end += 4
00598       (length,) = _struct_I.unpack(str[start:end])
00599       start = end
00600       end += length
00601       if python3:
00602         self.header.frame_id = str[start:end].decode('utf-8')
00603       else:
00604         self.header.frame_id = str[start:end]
00605       _x = self
00606       start = end
00607       end += 12
00608       (_x.diffs.header.seq, _x.diffs.header.stamp.secs, _x.diffs.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00609       start = end
00610       end += 4
00611       (length,) = _struct_I.unpack(str[start:end])
00612       start = end
00613       end += length
00614       if python3:
00615         self.diffs.header.frame_id = str[start:end].decode('utf-8')
00616       else:
00617         self.diffs.header.frame_id = str[start:end]
00618       start = end
00619       end += 16
00620       self.diffs.id.uuid = str[start:end]
00621       _x = self
00622       start = end
00623       end += 48
00624       (_x.diffs.bounds.min_pt.latitude, _x.diffs.bounds.min_pt.longitude, _x.diffs.bounds.min_pt.altitude, _x.diffs.bounds.max_pt.latitude, _x.diffs.bounds.max_pt.longitude, _x.diffs.bounds.max_pt.altitude,) = _struct_6d.unpack(str[start:end])
00625       start = end
00626       end += 4
00627       (length,) = _struct_I.unpack(str[start:end])
00628       self.diffs.points = []
00629       for i in range(0, length):
00630         val1 = geographic_msgs.msg.WayPoint()
00631         _v10 = val1.id
00632         start = end
00633         end += 16
00634         _v10.uuid = str[start:end]
00635         _v11 = val1.position
00636         _x = _v11
00637         start = end
00638         end += 24
00639         (_x.latitude, _x.longitude, _x.altitude,) = _struct_3d.unpack(str[start:end])
00640         start = end
00641         end += 4
00642         (length,) = _struct_I.unpack(str[start:end])
00643         val1.props = []
00644         for i in range(0, length):
00645           val2 = geographic_msgs.msg.KeyValue()
00646           start = end
00647           end += 4
00648           (length,) = _struct_I.unpack(str[start:end])
00649           start = end
00650           end += length
00651           if python3:
00652             val2.key = str[start:end].decode('utf-8')
00653           else:
00654             val2.key = str[start:end]
00655           start = end
00656           end += 4
00657           (length,) = _struct_I.unpack(str[start:end])
00658           start = end
00659           end += length
00660           if python3:
00661             val2.value = str[start:end].decode('utf-8')
00662           else:
00663             val2.value = str[start:end]
00664           val1.props.append(val2)
00665         self.diffs.points.append(val1)
00666       start = end
00667       end += 4
00668       (length,) = _struct_I.unpack(str[start:end])
00669       self.diffs.features = []
00670       for i in range(0, length):
00671         val1 = geographic_msgs.msg.MapFeature()
00672         _v12 = val1.id
00673         start = end
00674         end += 16
00675         _v12.uuid = str[start:end]
00676         start = end
00677         end += 4
00678         (length,) = _struct_I.unpack(str[start:end])
00679         val1.components = []
00680         for i in range(0, length):
00681           val2 = uuid_msgs.msg.UniqueID()
00682           start = end
00683           end += 16
00684           val2.uuid = str[start:end]
00685           val1.components.append(val2)
00686         start = end
00687         end += 4
00688         (length,) = _struct_I.unpack(str[start:end])
00689         val1.props = []
00690         for i in range(0, length):
00691           val2 = geographic_msgs.msg.KeyValue()
00692           start = end
00693           end += 4
00694           (length,) = _struct_I.unpack(str[start:end])
00695           start = end
00696           end += length
00697           if python3:
00698             val2.key = str[start:end].decode('utf-8')
00699           else:
00700             val2.key = str[start:end]
00701           start = end
00702           end += 4
00703           (length,) = _struct_I.unpack(str[start:end])
00704           start = end
00705           end += length
00706           if python3:
00707             val2.value = str[start:end].decode('utf-8')
00708           else:
00709             val2.value = str[start:end]
00710           val1.props.append(val2)
00711         self.diffs.features.append(val1)
00712       start = end
00713       end += 4
00714       (length,) = _struct_I.unpack(str[start:end])
00715       self.diffs.props = []
00716       for i in range(0, length):
00717         val1 = geographic_msgs.msg.KeyValue()
00718         start = end
00719         end += 4
00720         (length,) = _struct_I.unpack(str[start:end])
00721         start = end
00722         end += length
00723         if python3:
00724           val1.key = str[start:end].decode('utf-8')
00725         else:
00726           val1.key = str[start:end]
00727         start = end
00728         end += 4
00729         (length,) = _struct_I.unpack(str[start:end])
00730         start = end
00731         end += length
00732         if python3:
00733           val1.value = str[start:end].decode('utf-8')
00734         else:
00735           val1.value = str[start:end]
00736         self.diffs.props.append(val1)
00737       start = end
00738       end += 4
00739       (length,) = _struct_I.unpack(str[start:end])
00740       self.deletes = []
00741       for i in range(0, length):
00742         val1 = uuid_msgs.msg.UniqueID()
00743         start = end
00744         end += 16
00745         val1.uuid = str[start:end]
00746         self.deletes.append(val1)
00747       return self
00748     except struct.error as e:
00749       raise genpy.DeserializationError(e) #most likely buffer underfill
00750 
00751 _struct_I = genpy.struct_I
00752 _struct_3I = struct.Struct("<3I")
00753 _struct_3d = struct.Struct("<3d")
00754 _struct_6d = struct.Struct("<6d")
00755 _struct_16B = struct.Struct("<16B")
00756 _struct_16s = struct.Struct("<16s")


geographic_msgs
Author(s): Jack O'Quin
autogenerated on Mon Oct 6 2014 00:09:26