00001 """autogenerated by genmsg_py from InteractiveMarkerControl.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import roslib.rostime
00006 import geometry_msgs.msg
00007 import visualization_msgs.msg
00008 import std_msgs.msg
00009
00010 class InteractiveMarkerControl(roslib.message.Message):
00011 _md5sum = "f69c49e4eb251b5b0a89651eebf5a277"
00012 _type = "visualization_msgs/InteractiveMarkerControl"
00013 _has_header = False
00014 _full_text = """# Represents a control that is to be displayed together with an interactive marker
00015
00016 # Identifying string for this control.
00017 # You need to assign a unique value to this to receive feedback from the GUI
00018 # on what actions the user performs on this control (e.g. a button click).
00019 string name
00020
00021
00022 # Defines the local coordinate frame (relative to the pose of the parent
00023 # interactive marker) in which is being rotated and translated.
00024 # Default: Identity
00025 geometry_msgs/Quaternion orientation
00026
00027
00028 # Orientation mode: controls how orientation changes.
00029 # INHERIT: Follow orientation of interactive marker
00030 # FIXED: Keep orientation fixed at initial state
00031 # VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up).
00032 uint8 INHERIT = 0
00033 uint8 FIXED = 1
00034 uint8 VIEW_FACING = 2
00035
00036 uint8 orientation_mode
00037
00038 # Interaction mode for this control
00039 #
00040 # NONE: This control is only meant for visualization; no context menu.
00041 # MENU: Like NONE, but right-click menu is active.
00042 # BUTTON: Element can be left-clicked.
00043 # MOVE_AXIS: Translate along local x-axis.
00044 # MOVE_PLANE: Translate in local y-z plane.
00045 # ROTATE_AXIS: Rotate around local x-axis.
00046 # MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS.
00047 uint8 NONE = 0
00048 uint8 MENU = 1
00049 uint8 BUTTON = 2
00050 uint8 MOVE_AXIS = 3
00051 uint8 MOVE_PLANE = 4
00052 uint8 ROTATE_AXIS = 5
00053 uint8 MOVE_ROTATE = 6
00054
00055 uint8 interaction_mode
00056
00057
00058 # If true, the contained markers will also be visible
00059 # when the gui is not in interactive mode.
00060 bool always_visible
00061
00062
00063 # Markers to be displayed as custom visual representation.
00064 # Leave this empty to use the default control handles.
00065 #
00066 # Note:
00067 # - The markers can be defined in an arbitrary coordinate frame,
00068 # but will be transformed into the local frame of the interactive marker.
00069 # - If the header of a marker is empty, its pose will be interpreted as
00070 # relative to the pose of the parent interactive marker.
00071 Marker[] markers
00072
00073
00074 # In VIEW_FACING mode, set this to true if you don't want the markers
00075 # to be aligned with the camera view point. The markers will show up
00076 # as in INHERIT mode.
00077 bool independent_marker_orientation
00078
00079
00080 # Short description (< 40 characters) of what this control does,
00081 # e.g. "Move the robot".
00082 # Default: A generic description based on the interaction mode
00083 string description
00084
00085 ================================================================================
00086 MSG: geometry_msgs/Quaternion
00087 # This represents an orientation in free space in quaternion form.
00088
00089 float64 x
00090 float64 y
00091 float64 z
00092 float64 w
00093
00094 ================================================================================
00095 MSG: visualization_msgs/Marker
00096 # See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz
00097
00098 uint8 ARROW=0
00099 uint8 CUBE=1
00100 uint8 SPHERE=2
00101 uint8 CYLINDER=3
00102 uint8 LINE_STRIP=4
00103 uint8 LINE_LIST=5
00104 uint8 CUBE_LIST=6
00105 uint8 SPHERE_LIST=7
00106 uint8 POINTS=8
00107 uint8 TEXT_VIEW_FACING=9
00108 uint8 MESH_RESOURCE=10
00109 uint8 TRIANGLE_LIST=11
00110
00111 uint8 ADD=0
00112 uint8 MODIFY=0
00113 uint8 DELETE=2
00114
00115 Header header # header for time/frame information
00116 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object
00117 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later
00118 int32 type # Type of object
00119 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object
00120 geometry_msgs/Pose pose # Pose of the object
00121 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)
00122 std_msgs/ColorRGBA color # Color [0.0-1.0]
00123 duration lifetime # How long the object should last before being automatically deleted. 0 means forever
00124 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep
00125
00126 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
00127 geometry_msgs/Point[] points
00128 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
00129 #number of colors must either be 0 or equal to the number of points
00130 #NOTE: alpha is not yet used
00131 std_msgs/ColorRGBA[] colors
00132
00133 # NOTE: only used for text markers
00134 string text
00135
00136 # NOTE: only used for MESH_RESOURCE markers
00137 string mesh_resource
00138 bool mesh_use_embedded_materials
00139
00140 ================================================================================
00141 MSG: std_msgs/Header
00142 # Standard metadata for higher-level stamped data types.
00143 # This is generally used to communicate timestamped data
00144 # in a particular coordinate frame.
00145 #
00146 # sequence ID: consecutively increasing ID
00147 uint32 seq
00148 #Two-integer timestamp that is expressed as:
00149 # * stamp.secs: seconds (stamp_secs) since epoch
00150 # * stamp.nsecs: nanoseconds since stamp_secs
00151 # time-handling sugar is provided by the client library
00152 time stamp
00153 #Frame this data is associated with
00154 # 0: no frame
00155 # 1: global frame
00156 string frame_id
00157
00158 ================================================================================
00159 MSG: geometry_msgs/Pose
00160 # A representation of pose in free space, composed of postion and orientation.
00161 Point position
00162 Quaternion orientation
00163
00164 ================================================================================
00165 MSG: geometry_msgs/Point
00166 # This contains the position of a point in free space
00167 float64 x
00168 float64 y
00169 float64 z
00170
00171 ================================================================================
00172 MSG: geometry_msgs/Vector3
00173 # This represents a vector in free space.
00174
00175 float64 x
00176 float64 y
00177 float64 z
00178 ================================================================================
00179 MSG: std_msgs/ColorRGBA
00180 float32 r
00181 float32 g
00182 float32 b
00183 float32 a
00184
00185 """
00186
00187 INHERIT = 0
00188 FIXED = 1
00189 VIEW_FACING = 2
00190 NONE = 0
00191 MENU = 1
00192 BUTTON = 2
00193 MOVE_AXIS = 3
00194 MOVE_PLANE = 4
00195 ROTATE_AXIS = 5
00196 MOVE_ROTATE = 6
00197
00198 __slots__ = ['name','orientation','orientation_mode','interaction_mode','always_visible','markers','independent_marker_orientation','description']
00199 _slot_types = ['string','geometry_msgs/Quaternion','uint8','uint8','bool','visualization_msgs/Marker[]','bool','string']
00200
00201 def __init__(self, *args, **kwds):
00202 """
00203 Constructor. Any message fields that are implicitly/explicitly
00204 set to None will be assigned a default value. The recommend
00205 use is keyword arguments as this is more robust to future message
00206 changes. You cannot mix in-order arguments and keyword arguments.
00207
00208 The available fields are:
00209 name,orientation,orientation_mode,interaction_mode,always_visible,markers,independent_marker_orientation,description
00210
00211 @param args: complete set of field values, in .msg order
00212 @param kwds: use keyword arguments corresponding to message field names
00213 to set specific fields.
00214 """
00215 if args or kwds:
00216 super(InteractiveMarkerControl, self).__init__(*args, **kwds)
00217
00218 if self.name is None:
00219 self.name = ''
00220 if self.orientation is None:
00221 self.orientation = geometry_msgs.msg.Quaternion()
00222 if self.orientation_mode is None:
00223 self.orientation_mode = 0
00224 if self.interaction_mode is None:
00225 self.interaction_mode = 0
00226 if self.always_visible is None:
00227 self.always_visible = False
00228 if self.markers is None:
00229 self.markers = []
00230 if self.independent_marker_orientation is None:
00231 self.independent_marker_orientation = False
00232 if self.description is None:
00233 self.description = ''
00234 else:
00235 self.name = ''
00236 self.orientation = geometry_msgs.msg.Quaternion()
00237 self.orientation_mode = 0
00238 self.interaction_mode = 0
00239 self.always_visible = False
00240 self.markers = []
00241 self.independent_marker_orientation = False
00242 self.description = ''
00243
00244 def _get_types(self):
00245 """
00246 internal API method
00247 """
00248 return self._slot_types
00249
00250 def serialize(self, buff):
00251 """
00252 serialize message into buffer
00253 @param buff: buffer
00254 @type buff: StringIO
00255 """
00256 try:
00257 _x = self.name
00258 length = len(_x)
00259 buff.write(struct.pack('<I%ss'%length, length, _x))
00260 _x = self
00261 buff.write(_struct_4d3B.pack(_x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w, _x.orientation_mode, _x.interaction_mode, _x.always_visible))
00262 length = len(self.markers)
00263 buff.write(_struct_I.pack(length))
00264 for val1 in self.markers:
00265 _v1 = val1.header
00266 buff.write(_struct_I.pack(_v1.seq))
00267 _v2 = _v1.stamp
00268 _x = _v2
00269 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00270 _x = _v1.frame_id
00271 length = len(_x)
00272 buff.write(struct.pack('<I%ss'%length, length, _x))
00273 _x = val1.ns
00274 length = len(_x)
00275 buff.write(struct.pack('<I%ss'%length, length, _x))
00276 _x = val1
00277 buff.write(_struct_3i.pack(_x.id, _x.type, _x.action))
00278 _v3 = val1.pose
00279 _v4 = _v3.position
00280 _x = _v4
00281 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00282 _v5 = _v3.orientation
00283 _x = _v5
00284 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00285 _v6 = val1.scale
00286 _x = _v6
00287 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00288 _v7 = val1.color
00289 _x = _v7
00290 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00291 _v8 = val1.lifetime
00292 _x = _v8
00293 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00294 buff.write(_struct_B.pack(val1.frame_locked))
00295 length = len(val1.points)
00296 buff.write(_struct_I.pack(length))
00297 for val2 in val1.points:
00298 _x = val2
00299 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00300 length = len(val1.colors)
00301 buff.write(_struct_I.pack(length))
00302 for val2 in val1.colors:
00303 _x = val2
00304 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00305 _x = val1.text
00306 length = len(_x)
00307 buff.write(struct.pack('<I%ss'%length, length, _x))
00308 _x = val1.mesh_resource
00309 length = len(_x)
00310 buff.write(struct.pack('<I%ss'%length, length, _x))
00311 buff.write(_struct_B.pack(val1.mesh_use_embedded_materials))
00312 buff.write(_struct_B.pack(self.independent_marker_orientation))
00313 _x = self.description
00314 length = len(_x)
00315 buff.write(struct.pack('<I%ss'%length, length, _x))
00316 except struct.error as se: self._check_types(se)
00317 except TypeError as te: self._check_types(te)
00318
00319 def deserialize(self, str):
00320 """
00321 unpack serialized message in str into this message instance
00322 @param str: byte array of serialized message
00323 @type str: str
00324 """
00325 try:
00326 if self.orientation is None:
00327 self.orientation = geometry_msgs.msg.Quaternion()
00328 end = 0
00329 start = end
00330 end += 4
00331 (length,) = _struct_I.unpack(str[start:end])
00332 start = end
00333 end += length
00334 self.name = str[start:end]
00335 _x = self
00336 start = end
00337 end += 35
00338 (_x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w, _x.orientation_mode, _x.interaction_mode, _x.always_visible,) = _struct_4d3B.unpack(str[start:end])
00339 self.always_visible = bool(self.always_visible)
00340 start = end
00341 end += 4
00342 (length,) = _struct_I.unpack(str[start:end])
00343 self.markers = []
00344 for i in range(0, length):
00345 val1 = visualization_msgs.msg.Marker()
00346 _v9 = val1.header
00347 start = end
00348 end += 4
00349 (_v9.seq,) = _struct_I.unpack(str[start:end])
00350 _v10 = _v9.stamp
00351 _x = _v10
00352 start = end
00353 end += 8
00354 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00355 start = end
00356 end += 4
00357 (length,) = _struct_I.unpack(str[start:end])
00358 start = end
00359 end += length
00360 _v9.frame_id = str[start:end]
00361 start = end
00362 end += 4
00363 (length,) = _struct_I.unpack(str[start:end])
00364 start = end
00365 end += length
00366 val1.ns = str[start:end]
00367 _x = val1
00368 start = end
00369 end += 12
00370 (_x.id, _x.type, _x.action,) = _struct_3i.unpack(str[start:end])
00371 _v11 = val1.pose
00372 _v12 = _v11.position
00373 _x = _v12
00374 start = end
00375 end += 24
00376 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00377 _v13 = _v11.orientation
00378 _x = _v13
00379 start = end
00380 end += 32
00381 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00382 _v14 = val1.scale
00383 _x = _v14
00384 start = end
00385 end += 24
00386 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00387 _v15 = val1.color
00388 _x = _v15
00389 start = end
00390 end += 16
00391 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00392 _v16 = val1.lifetime
00393 _x = _v16
00394 start = end
00395 end += 8
00396 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00397 start = end
00398 end += 1
00399 (val1.frame_locked,) = _struct_B.unpack(str[start:end])
00400 val1.frame_locked = bool(val1.frame_locked)
00401 start = end
00402 end += 4
00403 (length,) = _struct_I.unpack(str[start:end])
00404 val1.points = []
00405 for i in range(0, length):
00406 val2 = geometry_msgs.msg.Point()
00407 _x = val2
00408 start = end
00409 end += 24
00410 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00411 val1.points.append(val2)
00412 start = end
00413 end += 4
00414 (length,) = _struct_I.unpack(str[start:end])
00415 val1.colors = []
00416 for i in range(0, length):
00417 val2 = std_msgs.msg.ColorRGBA()
00418 _x = val2
00419 start = end
00420 end += 16
00421 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00422 val1.colors.append(val2)
00423 start = end
00424 end += 4
00425 (length,) = _struct_I.unpack(str[start:end])
00426 start = end
00427 end += length
00428 val1.text = str[start:end]
00429 start = end
00430 end += 4
00431 (length,) = _struct_I.unpack(str[start:end])
00432 start = end
00433 end += length
00434 val1.mesh_resource = str[start:end]
00435 start = end
00436 end += 1
00437 (val1.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
00438 val1.mesh_use_embedded_materials = bool(val1.mesh_use_embedded_materials)
00439 self.markers.append(val1)
00440 start = end
00441 end += 1
00442 (self.independent_marker_orientation,) = _struct_B.unpack(str[start:end])
00443 self.independent_marker_orientation = bool(self.independent_marker_orientation)
00444 start = end
00445 end += 4
00446 (length,) = _struct_I.unpack(str[start:end])
00447 start = end
00448 end += length
00449 self.description = str[start:end]
00450 return self
00451 except struct.error as e:
00452 raise roslib.message.DeserializationError(e)
00453
00454
00455 def serialize_numpy(self, buff, numpy):
00456 """
00457 serialize message with numpy array types into buffer
00458 @param buff: buffer
00459 @type buff: StringIO
00460 @param numpy: numpy python module
00461 @type numpy module
00462 """
00463 try:
00464 _x = self.name
00465 length = len(_x)
00466 buff.write(struct.pack('<I%ss'%length, length, _x))
00467 _x = self
00468 buff.write(_struct_4d3B.pack(_x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w, _x.orientation_mode, _x.interaction_mode, _x.always_visible))
00469 length = len(self.markers)
00470 buff.write(_struct_I.pack(length))
00471 for val1 in self.markers:
00472 _v17 = val1.header
00473 buff.write(_struct_I.pack(_v17.seq))
00474 _v18 = _v17.stamp
00475 _x = _v18
00476 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00477 _x = _v17.frame_id
00478 length = len(_x)
00479 buff.write(struct.pack('<I%ss'%length, length, _x))
00480 _x = val1.ns
00481 length = len(_x)
00482 buff.write(struct.pack('<I%ss'%length, length, _x))
00483 _x = val1
00484 buff.write(_struct_3i.pack(_x.id, _x.type, _x.action))
00485 _v19 = val1.pose
00486 _v20 = _v19.position
00487 _x = _v20
00488 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00489 _v21 = _v19.orientation
00490 _x = _v21
00491 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00492 _v22 = val1.scale
00493 _x = _v22
00494 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00495 _v23 = val1.color
00496 _x = _v23
00497 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00498 _v24 = val1.lifetime
00499 _x = _v24
00500 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00501 buff.write(_struct_B.pack(val1.frame_locked))
00502 length = len(val1.points)
00503 buff.write(_struct_I.pack(length))
00504 for val2 in val1.points:
00505 _x = val2
00506 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00507 length = len(val1.colors)
00508 buff.write(_struct_I.pack(length))
00509 for val2 in val1.colors:
00510 _x = val2
00511 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00512 _x = val1.text
00513 length = len(_x)
00514 buff.write(struct.pack('<I%ss'%length, length, _x))
00515 _x = val1.mesh_resource
00516 length = len(_x)
00517 buff.write(struct.pack('<I%ss'%length, length, _x))
00518 buff.write(_struct_B.pack(val1.mesh_use_embedded_materials))
00519 buff.write(_struct_B.pack(self.independent_marker_orientation))
00520 _x = self.description
00521 length = len(_x)
00522 buff.write(struct.pack('<I%ss'%length, length, _x))
00523 except struct.error as se: self._check_types(se)
00524 except TypeError as te: self._check_types(te)
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
00530 @type str: str
00531 @param numpy: numpy python module
00532 @type numpy: module
00533 """
00534 try:
00535 if self.orientation is None:
00536 self.orientation = geometry_msgs.msg.Quaternion()
00537 end = 0
00538 start = end
00539 end += 4
00540 (length,) = _struct_I.unpack(str[start:end])
00541 start = end
00542 end += length
00543 self.name = str[start:end]
00544 _x = self
00545 start = end
00546 end += 35
00547 (_x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w, _x.orientation_mode, _x.interaction_mode, _x.always_visible,) = _struct_4d3B.unpack(str[start:end])
00548 self.always_visible = bool(self.always_visible)
00549 start = end
00550 end += 4
00551 (length,) = _struct_I.unpack(str[start:end])
00552 self.markers = []
00553 for i in range(0, length):
00554 val1 = visualization_msgs.msg.Marker()
00555 _v25 = val1.header
00556 start = end
00557 end += 4
00558 (_v25.seq,) = _struct_I.unpack(str[start:end])
00559 _v26 = _v25.stamp
00560 _x = _v26
00561 start = end
00562 end += 8
00563 (_x.secs, _x.nsecs,) = _struct_2I.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 _v25.frame_id = str[start:end]
00570 start = end
00571 end += 4
00572 (length,) = _struct_I.unpack(str[start:end])
00573 start = end
00574 end += length
00575 val1.ns = str[start:end]
00576 _x = val1
00577 start = end
00578 end += 12
00579 (_x.id, _x.type, _x.action,) = _struct_3i.unpack(str[start:end])
00580 _v27 = val1.pose
00581 _v28 = _v27.position
00582 _x = _v28
00583 start = end
00584 end += 24
00585 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00586 _v29 = _v27.orientation
00587 _x = _v29
00588 start = end
00589 end += 32
00590 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00591 _v30 = val1.scale
00592 _x = _v30
00593 start = end
00594 end += 24
00595 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00596 _v31 = val1.color
00597 _x = _v31
00598 start = end
00599 end += 16
00600 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00601 _v32 = val1.lifetime
00602 _x = _v32
00603 start = end
00604 end += 8
00605 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00606 start = end
00607 end += 1
00608 (val1.frame_locked,) = _struct_B.unpack(str[start:end])
00609 val1.frame_locked = bool(val1.frame_locked)
00610 start = end
00611 end += 4
00612 (length,) = _struct_I.unpack(str[start:end])
00613 val1.points = []
00614 for i in range(0, length):
00615 val2 = geometry_msgs.msg.Point()
00616 _x = val2
00617 start = end
00618 end += 24
00619 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00620 val1.points.append(val2)
00621 start = end
00622 end += 4
00623 (length,) = _struct_I.unpack(str[start:end])
00624 val1.colors = []
00625 for i in range(0, length):
00626 val2 = std_msgs.msg.ColorRGBA()
00627 _x = val2
00628 start = end
00629 end += 16
00630 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00631 val1.colors.append(val2)
00632 start = end
00633 end += 4
00634 (length,) = _struct_I.unpack(str[start:end])
00635 start = end
00636 end += length
00637 val1.text = str[start:end]
00638 start = end
00639 end += 4
00640 (length,) = _struct_I.unpack(str[start:end])
00641 start = end
00642 end += length
00643 val1.mesh_resource = str[start:end]
00644 start = end
00645 end += 1
00646 (val1.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
00647 val1.mesh_use_embedded_materials = bool(val1.mesh_use_embedded_materials)
00648 self.markers.append(val1)
00649 start = end
00650 end += 1
00651 (self.independent_marker_orientation,) = _struct_B.unpack(str[start:end])
00652 self.independent_marker_orientation = bool(self.independent_marker_orientation)
00653 start = end
00654 end += 4
00655 (length,) = _struct_I.unpack(str[start:end])
00656 start = end
00657 end += length
00658 self.description = str[start:end]
00659 return self
00660 except struct.error as e:
00661 raise roslib.message.DeserializationError(e)
00662
00663 _struct_I = roslib.message.struct_I
00664 _struct_B = struct.Struct("<B")
00665 _struct_2i = struct.Struct("<2i")
00666 _struct_3i = struct.Struct("<3i")
00667 _struct_4d3B = struct.Struct("<4d3B")
00668 _struct_4f = struct.Struct("<4f")
00669 _struct_4d = struct.Struct("<4d")
00670 _struct_2I = struct.Struct("<2I")
00671 _struct_3d = struct.Struct("<3d")