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


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