00001 """autogenerated by genpy from image_view2/ImageMarker2.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 image_view2.msg
00008 import geometry_msgs.msg
00009 import genpy
00010 import std_msgs.msg
00011
00012 class ImageMarker2(genpy.Message):
00013 _md5sum = "0f15d5468243177cf34fcb59d10d1b18"
00014 _type = "image_view2/ImageMarker2"
00015 _has_header = True
00016 _full_text = """byte CIRCLE=0
00017 byte LINE_STRIP=1
00018 byte LINE_LIST=2
00019 byte POLYGON=3
00020 byte POINTS=4
00021 byte FRAMES=5
00022 byte TEXT=6
00023
00024 byte LINE_STRIP3D=7
00025 byte LINE_LIST3D=8
00026 byte POLYGON3D=9
00027 byte POINTS3D=10
00028 byte TEXT3D=11
00029
00030 byte ADD=0
00031 byte REMOVE=1
00032
00033 Header header
00034 string ns # namespace, used with id to form a unique id
00035 int32 id # unique id within the namespace
00036 int32 type # CIRCLE/LINE_STRIP/etc.
00037 int32 action # ADD/REMOVE
00038 geometry_msgs/Point position # used for CIRCLE/TEXT, 2D in pixel-coords
00039 geometry_msgs/PointStamped position3D # used for 3DTEXT
00040 float32 scale # the diameter for a circle, etc.
00041 std_msgs/ColorRGBA outline_color
00042 byte filled # whether to fill in the shape with color
00043 std_msgs/ColorRGBA fill_color # color [0.0-1.0]
00044 duration lifetime # How long the object should last before being automatically deleted. 0 means forever
00045
00046
00047 geometry_msgs/Point[] points # used for LINE_STRIP/LINE_LIST/POLYGON/POINTS., 2D in pixel coords
00048 PointArrayStamped points3D # used for 3DLINE_STRIP/3DLINE_LIST/3DPOLYGON/3DPOINTS
00049 std_msgs/ColorRGBA[] outline_colors # a color for each line, point, etc.
00050
00051 string[] frames # used for FRAMES, tf names
00052 string text # used for TEXT, draw size of text is scale
00053
00054 ================================================================================
00055 MSG: std_msgs/Header
00056 # Standard metadata for higher-level stamped data types.
00057 # This is generally used to communicate timestamped data
00058 # in a particular coordinate frame.
00059 #
00060 # sequence ID: consecutively increasing ID
00061 uint32 seq
00062 #Two-integer timestamp that is expressed as:
00063 # * stamp.secs: seconds (stamp_secs) since epoch
00064 # * stamp.nsecs: nanoseconds since stamp_secs
00065 # time-handling sugar is provided by the client library
00066 time stamp
00067 #Frame this data is associated with
00068 # 0: no frame
00069 # 1: global frame
00070 string frame_id
00071
00072 ================================================================================
00073 MSG: geometry_msgs/Point
00074 # This contains the position of a point in free space
00075 float64 x
00076 float64 y
00077 float64 z
00078
00079 ================================================================================
00080 MSG: geometry_msgs/PointStamped
00081 # This represents a Point with reference coordinate frame and timestamp
00082 Header header
00083 Point point
00084
00085 ================================================================================
00086 MSG: std_msgs/ColorRGBA
00087 float32 r
00088 float32 g
00089 float32 b
00090 float32 a
00091
00092 ================================================================================
00093 MSG: image_view2/PointArrayStamped
00094 Header header
00095
00096 geometry_msgs/Point[] points
00097
00098
00099 """
00100
00101 CIRCLE = 0
00102 LINE_STRIP = 1
00103 LINE_LIST = 2
00104 POLYGON = 3
00105 POINTS = 4
00106 FRAMES = 5
00107 TEXT = 6
00108 LINE_STRIP3D = 7
00109 LINE_LIST3D = 8
00110 POLYGON3D = 9
00111 POINTS3D = 10
00112 TEXT3D = 11
00113 ADD = 0
00114 REMOVE = 1
00115
00116 __slots__ = ['header','ns','id','type','action','position','position3D','scale','outline_color','filled','fill_color','lifetime','points','points3D','outline_colors','frames','text']
00117 _slot_types = ['std_msgs/Header','string','int32','int32','int32','geometry_msgs/Point','geometry_msgs/PointStamped','float32','std_msgs/ColorRGBA','byte','std_msgs/ColorRGBA','duration','geometry_msgs/Point[]','image_view2/PointArrayStamped','std_msgs/ColorRGBA[]','string[]','string']
00118
00119 def __init__(self, *args, **kwds):
00120 """
00121 Constructor. Any message fields that are implicitly/explicitly
00122 set to None will be assigned a default value. The recommend
00123 use is keyword arguments as this is more robust to future message
00124 changes. You cannot mix in-order arguments and keyword arguments.
00125
00126 The available fields are:
00127 header,ns,id,type,action,position,position3D,scale,outline_color,filled,fill_color,lifetime,points,points3D,outline_colors,frames,text
00128
00129 :param args: complete set of field values, in .msg order
00130 :param kwds: use keyword arguments corresponding to message field names
00131 to set specific fields.
00132 """
00133 if args or kwds:
00134 super(ImageMarker2, self).__init__(*args, **kwds)
00135
00136 if self.header is None:
00137 self.header = std_msgs.msg.Header()
00138 if self.ns is None:
00139 self.ns = ''
00140 if self.id is None:
00141 self.id = 0
00142 if self.type is None:
00143 self.type = 0
00144 if self.action is None:
00145 self.action = 0
00146 if self.position is None:
00147 self.position = geometry_msgs.msg.Point()
00148 if self.position3D is None:
00149 self.position3D = geometry_msgs.msg.PointStamped()
00150 if self.scale is None:
00151 self.scale = 0.
00152 if self.outline_color is None:
00153 self.outline_color = std_msgs.msg.ColorRGBA()
00154 if self.filled is None:
00155 self.filled = 0
00156 if self.fill_color is None:
00157 self.fill_color = std_msgs.msg.ColorRGBA()
00158 if self.lifetime is None:
00159 self.lifetime = genpy.Duration()
00160 if self.points is None:
00161 self.points = []
00162 if self.points3D is None:
00163 self.points3D = image_view2.msg.PointArrayStamped()
00164 if self.outline_colors is None:
00165 self.outline_colors = []
00166 if self.frames is None:
00167 self.frames = []
00168 if self.text is None:
00169 self.text = ''
00170 else:
00171 self.header = std_msgs.msg.Header()
00172 self.ns = ''
00173 self.id = 0
00174 self.type = 0
00175 self.action = 0
00176 self.position = geometry_msgs.msg.Point()
00177 self.position3D = geometry_msgs.msg.PointStamped()
00178 self.scale = 0.
00179 self.outline_color = std_msgs.msg.ColorRGBA()
00180 self.filled = 0
00181 self.fill_color = std_msgs.msg.ColorRGBA()
00182 self.lifetime = genpy.Duration()
00183 self.points = []
00184 self.points3D = image_view2.msg.PointArrayStamped()
00185 self.outline_colors = []
00186 self.frames = []
00187 self.text = ''
00188
00189 def _get_types(self):
00190 """
00191 internal API method
00192 """
00193 return self._slot_types
00194
00195 def serialize(self, buff):
00196 """
00197 serialize message into buffer
00198 :param buff: buffer, ``StringIO``
00199 """
00200 try:
00201 _x = self
00202 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00203 _x = self.header.frame_id
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 = self.ns
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 = self
00216 buff.write(_struct_3i3d3I.pack(_x.id, _x.type, _x.action, _x.position.x, _x.position.y, _x.position.z, _x.position3D.header.seq, _x.position3D.header.stamp.secs, _x.position3D.header.stamp.nsecs))
00217 _x = self.position3D.header.frame_id
00218 length = len(_x)
00219 if python3 or type(_x) == unicode:
00220 _x = _x.encode('utf-8')
00221 length = len(_x)
00222 buff.write(struct.pack('<I%ss'%length, length, _x))
00223 _x = self
00224 buff.write(_struct_3d5fb4f2i.pack(_x.position3D.point.x, _x.position3D.point.y, _x.position3D.point.z, _x.scale, _x.outline_color.r, _x.outline_color.g, _x.outline_color.b, _x.outline_color.a, _x.filled, _x.fill_color.r, _x.fill_color.g, _x.fill_color.b, _x.fill_color.a, _x.lifetime.secs, _x.lifetime.nsecs))
00225 length = len(self.points)
00226 buff.write(_struct_I.pack(length))
00227 for val1 in self.points:
00228 _x = val1
00229 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00230 _x = self
00231 buff.write(_struct_3I.pack(_x.points3D.header.seq, _x.points3D.header.stamp.secs, _x.points3D.header.stamp.nsecs))
00232 _x = self.points3D.header.frame_id
00233 length = len(_x)
00234 if python3 or type(_x) == unicode:
00235 _x = _x.encode('utf-8')
00236 length = len(_x)
00237 buff.write(struct.pack('<I%ss'%length, length, _x))
00238 length = len(self.points3D.points)
00239 buff.write(_struct_I.pack(length))
00240 for val1 in self.points3D.points:
00241 _x = val1
00242 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00243 length = len(self.outline_colors)
00244 buff.write(_struct_I.pack(length))
00245 for val1 in self.outline_colors:
00246 _x = val1
00247 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00248 length = len(self.frames)
00249 buff.write(_struct_I.pack(length))
00250 for val1 in self.frames:
00251 length = len(val1)
00252 if python3 or type(val1) == unicode:
00253 val1 = val1.encode('utf-8')
00254 length = len(val1)
00255 buff.write(struct.pack('<I%ss'%length, length, val1))
00256 _x = self.text
00257 length = len(_x)
00258 if python3 or type(_x) == unicode:
00259 _x = _x.encode('utf-8')
00260 length = len(_x)
00261 buff.write(struct.pack('<I%ss'%length, length, _x))
00262 except struct.error as se: self._check_types(se)
00263 except TypeError as te: self._check_types(te)
00264
00265 def deserialize(self, str):
00266 """
00267 unpack serialized message in str into this message instance
00268 :param str: byte array of serialized message, ``str``
00269 """
00270 try:
00271 if self.header is None:
00272 self.header = std_msgs.msg.Header()
00273 if self.position is None:
00274 self.position = geometry_msgs.msg.Point()
00275 if self.position3D is None:
00276 self.position3D = geometry_msgs.msg.PointStamped()
00277 if self.outline_color is None:
00278 self.outline_color = std_msgs.msg.ColorRGBA()
00279 if self.fill_color is None:
00280 self.fill_color = std_msgs.msg.ColorRGBA()
00281 if self.lifetime is None:
00282 self.lifetime = genpy.Duration()
00283 if self.points is None:
00284 self.points = None
00285 if self.points3D is None:
00286 self.points3D = image_view2.msg.PointArrayStamped()
00287 if self.outline_colors is None:
00288 self.outline_colors = None
00289 end = 0
00290 _x = self
00291 start = end
00292 end += 12
00293 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00294 start = end
00295 end += 4
00296 (length,) = _struct_I.unpack(str[start:end])
00297 start = end
00298 end += length
00299 if python3:
00300 self.header.frame_id = str[start:end].decode('utf-8')
00301 else:
00302 self.header.frame_id = str[start:end]
00303 start = end
00304 end += 4
00305 (length,) = _struct_I.unpack(str[start:end])
00306 start = end
00307 end += length
00308 if python3:
00309 self.ns = str[start:end].decode('utf-8')
00310 else:
00311 self.ns = str[start:end]
00312 _x = self
00313 start = end
00314 end += 48
00315 (_x.id, _x.type, _x.action, _x.position.x, _x.position.y, _x.position.z, _x.position3D.header.seq, _x.position3D.header.stamp.secs, _x.position3D.header.stamp.nsecs,) = _struct_3i3d3I.unpack(str[start:end])
00316 start = end
00317 end += 4
00318 (length,) = _struct_I.unpack(str[start:end])
00319 start = end
00320 end += length
00321 if python3:
00322 self.position3D.header.frame_id = str[start:end].decode('utf-8')
00323 else:
00324 self.position3D.header.frame_id = str[start:end]
00325 _x = self
00326 start = end
00327 end += 69
00328 (_x.position3D.point.x, _x.position3D.point.y, _x.position3D.point.z, _x.scale, _x.outline_color.r, _x.outline_color.g, _x.outline_color.b, _x.outline_color.a, _x.filled, _x.fill_color.r, _x.fill_color.g, _x.fill_color.b, _x.fill_color.a, _x.lifetime.secs, _x.lifetime.nsecs,) = _struct_3d5fb4f2i.unpack(str[start:end])
00329 start = end
00330 end += 4
00331 (length,) = _struct_I.unpack(str[start:end])
00332 self.points = []
00333 for i in range(0, length):
00334 val1 = geometry_msgs.msg.Point()
00335 _x = val1
00336 start = end
00337 end += 24
00338 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00339 self.points.append(val1)
00340 _x = self
00341 start = end
00342 end += 12
00343 (_x.points3D.header.seq, _x.points3D.header.stamp.secs, _x.points3D.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00344 start = end
00345 end += 4
00346 (length,) = _struct_I.unpack(str[start:end])
00347 start = end
00348 end += length
00349 if python3:
00350 self.points3D.header.frame_id = str[start:end].decode('utf-8')
00351 else:
00352 self.points3D.header.frame_id = str[start:end]
00353 start = end
00354 end += 4
00355 (length,) = _struct_I.unpack(str[start:end])
00356 self.points3D.points = []
00357 for i in range(0, length):
00358 val1 = geometry_msgs.msg.Point()
00359 _x = val1
00360 start = end
00361 end += 24
00362 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00363 self.points3D.points.append(val1)
00364 start = end
00365 end += 4
00366 (length,) = _struct_I.unpack(str[start:end])
00367 self.outline_colors = []
00368 for i in range(0, length):
00369 val1 = std_msgs.msg.ColorRGBA()
00370 _x = val1
00371 start = end
00372 end += 16
00373 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00374 self.outline_colors.append(val1)
00375 start = end
00376 end += 4
00377 (length,) = _struct_I.unpack(str[start:end])
00378 self.frames = []
00379 for i in range(0, length):
00380 start = end
00381 end += 4
00382 (length,) = _struct_I.unpack(str[start:end])
00383 start = end
00384 end += length
00385 if python3:
00386 val1 = str[start:end].decode('utf-8')
00387 else:
00388 val1 = str[start:end]
00389 self.frames.append(val1)
00390 start = end
00391 end += 4
00392 (length,) = _struct_I.unpack(str[start:end])
00393 start = end
00394 end += length
00395 if python3:
00396 self.text = str[start:end].decode('utf-8')
00397 else:
00398 self.text = str[start:end]
00399 self.lifetime.canon()
00400 return self
00401 except struct.error as e:
00402 raise genpy.DeserializationError(e)
00403
00404
00405 def serialize_numpy(self, buff, numpy):
00406 """
00407 serialize message with numpy array types into buffer
00408 :param buff: buffer, ``StringIO``
00409 :param numpy: numpy python module
00410 """
00411 try:
00412 _x = self
00413 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00414 _x = self.header.frame_id
00415 length = len(_x)
00416 if python3 or type(_x) == unicode:
00417 _x = _x.encode('utf-8')
00418 length = len(_x)
00419 buff.write(struct.pack('<I%ss'%length, length, _x))
00420 _x = self.ns
00421 length = len(_x)
00422 if python3 or type(_x) == unicode:
00423 _x = _x.encode('utf-8')
00424 length = len(_x)
00425 buff.write(struct.pack('<I%ss'%length, length, _x))
00426 _x = self
00427 buff.write(_struct_3i3d3I.pack(_x.id, _x.type, _x.action, _x.position.x, _x.position.y, _x.position.z, _x.position3D.header.seq, _x.position3D.header.stamp.secs, _x.position3D.header.stamp.nsecs))
00428 _x = self.position3D.header.frame_id
00429 length = len(_x)
00430 if python3 or type(_x) == unicode:
00431 _x = _x.encode('utf-8')
00432 length = len(_x)
00433 buff.write(struct.pack('<I%ss'%length, length, _x))
00434 _x = self
00435 buff.write(_struct_3d5fb4f2i.pack(_x.position3D.point.x, _x.position3D.point.y, _x.position3D.point.z, _x.scale, _x.outline_color.r, _x.outline_color.g, _x.outline_color.b, _x.outline_color.a, _x.filled, _x.fill_color.r, _x.fill_color.g, _x.fill_color.b, _x.fill_color.a, _x.lifetime.secs, _x.lifetime.nsecs))
00436 length = len(self.points)
00437 buff.write(_struct_I.pack(length))
00438 for val1 in self.points:
00439 _x = val1
00440 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00441 _x = self
00442 buff.write(_struct_3I.pack(_x.points3D.header.seq, _x.points3D.header.stamp.secs, _x.points3D.header.stamp.nsecs))
00443 _x = self.points3D.header.frame_id
00444 length = len(_x)
00445 if python3 or type(_x) == unicode:
00446 _x = _x.encode('utf-8')
00447 length = len(_x)
00448 buff.write(struct.pack('<I%ss'%length, length, _x))
00449 length = len(self.points3D.points)
00450 buff.write(_struct_I.pack(length))
00451 for val1 in self.points3D.points:
00452 _x = val1
00453 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00454 length = len(self.outline_colors)
00455 buff.write(_struct_I.pack(length))
00456 for val1 in self.outline_colors:
00457 _x = val1
00458 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00459 length = len(self.frames)
00460 buff.write(_struct_I.pack(length))
00461 for val1 in self.frames:
00462 length = len(val1)
00463 if python3 or type(val1) == unicode:
00464 val1 = val1.encode('utf-8')
00465 length = len(val1)
00466 buff.write(struct.pack('<I%ss'%length, length, val1))
00467 _x = self.text
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 except struct.error as se: self._check_types(se)
00474 except TypeError as te: self._check_types(te)
00475
00476 def deserialize_numpy(self, str, numpy):
00477 """
00478 unpack serialized message in str into this message instance using numpy for array types
00479 :param str: byte array of serialized message, ``str``
00480 :param numpy: numpy python module
00481 """
00482 try:
00483 if self.header is None:
00484 self.header = std_msgs.msg.Header()
00485 if self.position is None:
00486 self.position = geometry_msgs.msg.Point()
00487 if self.position3D is None:
00488 self.position3D = geometry_msgs.msg.PointStamped()
00489 if self.outline_color is None:
00490 self.outline_color = std_msgs.msg.ColorRGBA()
00491 if self.fill_color is None:
00492 self.fill_color = std_msgs.msg.ColorRGBA()
00493 if self.lifetime is None:
00494 self.lifetime = genpy.Duration()
00495 if self.points is None:
00496 self.points = None
00497 if self.points3D is None:
00498 self.points3D = image_view2.msg.PointArrayStamped()
00499 if self.outline_colors is None:
00500 self.outline_colors = None
00501 end = 0
00502 _x = self
00503 start = end
00504 end += 12
00505 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00506 start = end
00507 end += 4
00508 (length,) = _struct_I.unpack(str[start:end])
00509 start = end
00510 end += length
00511 if python3:
00512 self.header.frame_id = str[start:end].decode('utf-8')
00513 else:
00514 self.header.frame_id = str[start:end]
00515 start = end
00516 end += 4
00517 (length,) = _struct_I.unpack(str[start:end])
00518 start = end
00519 end += length
00520 if python3:
00521 self.ns = str[start:end].decode('utf-8')
00522 else:
00523 self.ns = str[start:end]
00524 _x = self
00525 start = end
00526 end += 48
00527 (_x.id, _x.type, _x.action, _x.position.x, _x.position.y, _x.position.z, _x.position3D.header.seq, _x.position3D.header.stamp.secs, _x.position3D.header.stamp.nsecs,) = _struct_3i3d3I.unpack(str[start:end])
00528 start = end
00529 end += 4
00530 (length,) = _struct_I.unpack(str[start:end])
00531 start = end
00532 end += length
00533 if python3:
00534 self.position3D.header.frame_id = str[start:end].decode('utf-8')
00535 else:
00536 self.position3D.header.frame_id = str[start:end]
00537 _x = self
00538 start = end
00539 end += 69
00540 (_x.position3D.point.x, _x.position3D.point.y, _x.position3D.point.z, _x.scale, _x.outline_color.r, _x.outline_color.g, _x.outline_color.b, _x.outline_color.a, _x.filled, _x.fill_color.r, _x.fill_color.g, _x.fill_color.b, _x.fill_color.a, _x.lifetime.secs, _x.lifetime.nsecs,) = _struct_3d5fb4f2i.unpack(str[start:end])
00541 start = end
00542 end += 4
00543 (length,) = _struct_I.unpack(str[start:end])
00544 self.points = []
00545 for i in range(0, length):
00546 val1 = geometry_msgs.msg.Point()
00547 _x = val1
00548 start = end
00549 end += 24
00550 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00551 self.points.append(val1)
00552 _x = self
00553 start = end
00554 end += 12
00555 (_x.points3D.header.seq, _x.points3D.header.stamp.secs, _x.points3D.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00556 start = end
00557 end += 4
00558 (length,) = _struct_I.unpack(str[start:end])
00559 start = end
00560 end += length
00561 if python3:
00562 self.points3D.header.frame_id = str[start:end].decode('utf-8')
00563 else:
00564 self.points3D.header.frame_id = str[start:end]
00565 start = end
00566 end += 4
00567 (length,) = _struct_I.unpack(str[start:end])
00568 self.points3D.points = []
00569 for i in range(0, length):
00570 val1 = geometry_msgs.msg.Point()
00571 _x = val1
00572 start = end
00573 end += 24
00574 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00575 self.points3D.points.append(val1)
00576 start = end
00577 end += 4
00578 (length,) = _struct_I.unpack(str[start:end])
00579 self.outline_colors = []
00580 for i in range(0, length):
00581 val1 = std_msgs.msg.ColorRGBA()
00582 _x = val1
00583 start = end
00584 end += 16
00585 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00586 self.outline_colors.append(val1)
00587 start = end
00588 end += 4
00589 (length,) = _struct_I.unpack(str[start:end])
00590 self.frames = []
00591 for i in range(0, length):
00592 start = end
00593 end += 4
00594 (length,) = _struct_I.unpack(str[start:end])
00595 start = end
00596 end += length
00597 if python3:
00598 val1 = str[start:end].decode('utf-8')
00599 else:
00600 val1 = str[start:end]
00601 self.frames.append(val1)
00602 start = end
00603 end += 4
00604 (length,) = _struct_I.unpack(str[start:end])
00605 start = end
00606 end += length
00607 if python3:
00608 self.text = str[start:end].decode('utf-8')
00609 else:
00610 self.text = str[start:end]
00611 self.lifetime.canon()
00612 return self
00613 except struct.error as e:
00614 raise genpy.DeserializationError(e)
00615
00616 _struct_I = genpy.struct_I
00617 _struct_4f = struct.Struct("<4f")
00618 _struct_3I = struct.Struct("<3I")
00619 _struct_3i3d3I = struct.Struct("<3i3d3I")
00620 _struct_3d5fb4f2i = struct.Struct("<3d5fb4f2i")
00621 _struct_3d = struct.Struct("<3d")