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