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