00001 """autogenerated by genmsg_py from InteractiveMarkerInit.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 InteractiveMarkerInit(roslib.message.Message):
00011 _md5sum = "467a93e72a544fd966aafe47c72160b7"
00012 _type = "visualization_msgs/InteractiveMarkerInit"
00013 _has_header = False
00014 _full_text = """# Identifying string. Must be unique in the topic namespace
00015 # that this server works on.
00016 string server_id
00017
00018 # Sequence number.
00019 # The client will use this to detect if it has missed a subsequent
00020 # update. Every update message will have the same sequence number as
00021 # an init message. Clients will likely want to unsubscribe from the
00022 # init topic after a successful initialization to avoid receiving
00023 # duplicate data.
00024 uint64 seq_num
00025
00026 # All markers.
00027 InteractiveMarker[] markers
00028
00029 ================================================================================
00030 MSG: visualization_msgs/InteractiveMarker
00031 # Time/frame info.
00032 # If header.time is set to 0, the marker will be retransformed into
00033 # its frame on each timestep. You will receive the pose feedback
00034 # in the same frame.
00035 # Otherwise, you might receive feedback in a different frame.
00036 # For rviz, this will be the current 'fixed frame' set by the user.
00037 Header header
00038
00039 # Initial pose. Also, defines the pivot point for rotations.
00040 geometry_msgs/Pose pose
00041
00042 # Identifying string. Must be globally unique in
00043 # the topic that this message is sent through.
00044 string name
00045
00046 # Short description (< 40 characters).
00047 string description
00048
00049 # Scale to be used for default controls (default=1).
00050 float32 scale
00051
00052 # All menu and submenu entries associated with this marker.
00053 MenuEntry[] menu_entries
00054
00055 # List of controls displayed for this marker.
00056 InteractiveMarkerControl[] controls
00057
00058 ================================================================================
00059 MSG: std_msgs/Header
00060 # Standard metadata for higher-level stamped data types.
00061 # This is generally used to communicate timestamped data
00062 # in a particular coordinate frame.
00063 #
00064 # sequence ID: consecutively increasing ID
00065 uint32 seq
00066 #Two-integer timestamp that is expressed as:
00067 # * stamp.secs: seconds (stamp_secs) since epoch
00068 # * stamp.nsecs: nanoseconds since stamp_secs
00069 # time-handling sugar is provided by the client library
00070 time stamp
00071 #Frame this data is associated with
00072 # 0: no frame
00073 # 1: global frame
00074 string frame_id
00075
00076 ================================================================================
00077 MSG: geometry_msgs/Pose
00078 # A representation of pose in free space, composed of postion and orientation.
00079 Point position
00080 Quaternion orientation
00081
00082 ================================================================================
00083 MSG: geometry_msgs/Point
00084 # This contains the position of a point in free space
00085 float64 x
00086 float64 y
00087 float64 z
00088
00089 ================================================================================
00090 MSG: geometry_msgs/Quaternion
00091 # This represents an orientation in free space in quaternion form.
00092
00093 float64 x
00094 float64 y
00095 float64 z
00096 float64 w
00097
00098 ================================================================================
00099 MSG: visualization_msgs/MenuEntry
00100 # MenuEntry message.
00101
00102 # Each InteractiveMarker message has an array of MenuEntry messages.
00103 # A collection of MenuEntries together describe a
00104 # menu/submenu/subsubmenu/etc tree, though they are stored in a flat
00105 # array. The tree structure is represented by giving each menu entry
00106 # an ID number and a "parent_id" field. Top-level entries are the
00107 # ones with parent_id = 0. Menu entries are ordered within their
00108 # level the same way they are ordered in the containing array. Parent
00109 # entries must appear before their children.
00110
00111 # Example:
00112 # - id = 3
00113 # parent_id = 0
00114 # title = "fun"
00115 # - id = 2
00116 # parent_id = 0
00117 # title = "robot"
00118 # - id = 4
00119 # parent_id = 2
00120 # title = "pr2"
00121 # - id = 5
00122 # parent_id = 2
00123 # title = "turtle"
00124 #
00125 # Gives a menu tree like this:
00126 # - fun
00127 # - robot
00128 # - pr2
00129 # - turtle
00130
00131 # ID is a number for each menu entry. Must be unique within the
00132 # control, and should never be 0.
00133 uint32 id
00134
00135 # ID of the parent of this menu entry, if it is a submenu. If this
00136 # menu entry is a top-level entry, set parent_id to 0.
00137 uint32 parent_id
00138
00139 # menu / entry title
00140 string title
00141
00142 # Arguments to command indicated by command_type (below)
00143 string command
00144
00145 # Command_type stores the type of response desired when this menu
00146 # entry is clicked.
00147 # FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id.
00148 # ROSRUN: execute "rosrun" with arguments given in the command field (above).
00149 # ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above).
00150 uint8 FEEDBACK=0
00151 uint8 ROSRUN=1
00152 uint8 ROSLAUNCH=2
00153 uint8 command_type
00154
00155 ================================================================================
00156 MSG: visualization_msgs/InteractiveMarkerControl
00157 # Represents a control that is to be displayed together with an interactive marker
00158
00159 # Identifying string for this control.
00160 # You need to assign a unique value to this to receive feedback from the GUI
00161 # on what actions the user performs on this control (e.g. a button click).
00162 string name
00163
00164
00165 # Defines the local coordinate frame (relative to the pose of the parent
00166 # interactive marker) in which is being rotated and translated.
00167 # Default: Identity
00168 geometry_msgs/Quaternion orientation
00169
00170
00171 # Orientation mode: controls how orientation changes.
00172 # INHERIT: Follow orientation of interactive marker
00173 # FIXED: Keep orientation fixed at initial state
00174 # VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up).
00175 uint8 INHERIT = 0
00176 uint8 FIXED = 1
00177 uint8 VIEW_FACING = 2
00178
00179 uint8 orientation_mode
00180
00181 # Interaction mode for this control
00182 #
00183 # NONE: This control is only meant for visualization; no context menu.
00184 # MENU: Like NONE, but right-click menu is active.
00185 # BUTTON: Element can be left-clicked.
00186 # MOVE_AXIS: Translate along local x-axis.
00187 # MOVE_PLANE: Translate in local y-z plane.
00188 # ROTATE_AXIS: Rotate around local x-axis.
00189 # MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS.
00190 uint8 NONE = 0
00191 uint8 MENU = 1
00192 uint8 BUTTON = 2
00193 uint8 MOVE_AXIS = 3
00194 uint8 MOVE_PLANE = 4
00195 uint8 ROTATE_AXIS = 5
00196 uint8 MOVE_ROTATE = 6
00197
00198 uint8 interaction_mode
00199
00200
00201 # If true, the contained markers will also be visible
00202 # when the gui is not in interactive mode.
00203 bool always_visible
00204
00205
00206 # Markers to be displayed as custom visual representation.
00207 # Leave this empty to use the default control handles.
00208 #
00209 # Note:
00210 # - The markers can be defined in an arbitrary coordinate frame,
00211 # but will be transformed into the local frame of the interactive marker.
00212 # - If the header of a marker is empty, its pose will be interpreted as
00213 # relative to the pose of the parent interactive marker.
00214 Marker[] markers
00215
00216
00217 # In VIEW_FACING mode, set this to true if you don't want the markers
00218 # to be aligned with the camera view point. The markers will show up
00219 # as in INHERIT mode.
00220 bool independent_marker_orientation
00221
00222
00223 # Short description (< 40 characters) of what this control does,
00224 # e.g. "Move the robot".
00225 # Default: A generic description based on the interaction mode
00226 string description
00227
00228 ================================================================================
00229 MSG: visualization_msgs/Marker
00230 # 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
00231
00232 uint8 ARROW=0
00233 uint8 CUBE=1
00234 uint8 SPHERE=2
00235 uint8 CYLINDER=3
00236 uint8 LINE_STRIP=4
00237 uint8 LINE_LIST=5
00238 uint8 CUBE_LIST=6
00239 uint8 SPHERE_LIST=7
00240 uint8 POINTS=8
00241 uint8 TEXT_VIEW_FACING=9
00242 uint8 MESH_RESOURCE=10
00243 uint8 TRIANGLE_LIST=11
00244
00245 uint8 ADD=0
00246 uint8 MODIFY=0
00247 uint8 DELETE=2
00248
00249 Header header # header for time/frame information
00250 string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object
00251 int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later
00252 int32 type # Type of object
00253 int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object
00254 geometry_msgs/Pose pose # Pose of the object
00255 geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square)
00256 std_msgs/ColorRGBA color # Color [0.0-1.0]
00257 duration lifetime # How long the object should last before being automatically deleted. 0 means forever
00258 bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep
00259
00260 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
00261 geometry_msgs/Point[] points
00262 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
00263 #number of colors must either be 0 or equal to the number of points
00264 #NOTE: alpha is not yet used
00265 std_msgs/ColorRGBA[] colors
00266
00267 # NOTE: only used for text markers
00268 string text
00269
00270 # NOTE: only used for MESH_RESOURCE markers
00271 string mesh_resource
00272 bool mesh_use_embedded_materials
00273
00274 ================================================================================
00275 MSG: geometry_msgs/Vector3
00276 # This represents a vector in free space.
00277
00278 float64 x
00279 float64 y
00280 float64 z
00281 ================================================================================
00282 MSG: std_msgs/ColorRGBA
00283 float32 r
00284 float32 g
00285 float32 b
00286 float32 a
00287
00288 """
00289 __slots__ = ['server_id','seq_num','markers']
00290 _slot_types = ['string','uint64','visualization_msgs/InteractiveMarker[]']
00291
00292 def __init__(self, *args, **kwds):
00293 """
00294 Constructor. Any message fields that are implicitly/explicitly
00295 set to None will be assigned a default value. The recommend
00296 use is keyword arguments as this is more robust to future message
00297 changes. You cannot mix in-order arguments and keyword arguments.
00298
00299 The available fields are:
00300 server_id,seq_num,markers
00301
00302 @param args: complete set of field values, in .msg order
00303 @param kwds: use keyword arguments corresponding to message field names
00304 to set specific fields.
00305 """
00306 if args or kwds:
00307 super(InteractiveMarkerInit, self).__init__(*args, **kwds)
00308
00309 if self.server_id is None:
00310 self.server_id = ''
00311 if self.seq_num is None:
00312 self.seq_num = 0
00313 if self.markers is None:
00314 self.markers = []
00315 else:
00316 self.server_id = ''
00317 self.seq_num = 0
00318 self.markers = []
00319
00320 def _get_types(self):
00321 """
00322 internal API method
00323 """
00324 return self._slot_types
00325
00326 def serialize(self, buff):
00327 """
00328 serialize message into buffer
00329 @param buff: buffer
00330 @type buff: StringIO
00331 """
00332 try:
00333 _x = self.server_id
00334 length = len(_x)
00335 buff.write(struct.pack('<I%ss'%length, length, _x))
00336 buff.write(_struct_Q.pack(self.seq_num))
00337 length = len(self.markers)
00338 buff.write(_struct_I.pack(length))
00339 for val1 in self.markers:
00340 _v1 = val1.header
00341 buff.write(_struct_I.pack(_v1.seq))
00342 _v2 = _v1.stamp
00343 _x = _v2
00344 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00345 _x = _v1.frame_id
00346 length = len(_x)
00347 buff.write(struct.pack('<I%ss'%length, length, _x))
00348 _v3 = val1.pose
00349 _v4 = _v3.position
00350 _x = _v4
00351 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00352 _v5 = _v3.orientation
00353 _x = _v5
00354 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00355 _x = val1.name
00356 length = len(_x)
00357 buff.write(struct.pack('<I%ss'%length, length, _x))
00358 _x = val1.description
00359 length = len(_x)
00360 buff.write(struct.pack('<I%ss'%length, length, _x))
00361 buff.write(_struct_f.pack(val1.scale))
00362 length = len(val1.menu_entries)
00363 buff.write(_struct_I.pack(length))
00364 for val2 in val1.menu_entries:
00365 _x = val2
00366 buff.write(_struct_2I.pack(_x.id, _x.parent_id))
00367 _x = val2.title
00368 length = len(_x)
00369 buff.write(struct.pack('<I%ss'%length, length, _x))
00370 _x = val2.command
00371 length = len(_x)
00372 buff.write(struct.pack('<I%ss'%length, length, _x))
00373 buff.write(_struct_B.pack(val2.command_type))
00374 length = len(val1.controls)
00375 buff.write(_struct_I.pack(length))
00376 for val2 in val1.controls:
00377 _x = val2.name
00378 length = len(_x)
00379 buff.write(struct.pack('<I%ss'%length, length, _x))
00380 _v6 = val2.orientation
00381 _x = _v6
00382 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00383 _x = val2
00384 buff.write(_struct_3B.pack(_x.orientation_mode, _x.interaction_mode, _x.always_visible))
00385 length = len(val2.markers)
00386 buff.write(_struct_I.pack(length))
00387 for val3 in val2.markers:
00388 _v7 = val3.header
00389 buff.write(_struct_I.pack(_v7.seq))
00390 _v8 = _v7.stamp
00391 _x = _v8
00392 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00393 _x = _v7.frame_id
00394 length = len(_x)
00395 buff.write(struct.pack('<I%ss'%length, length, _x))
00396 _x = val3.ns
00397 length = len(_x)
00398 buff.write(struct.pack('<I%ss'%length, length, _x))
00399 _x = val3
00400 buff.write(_struct_3i.pack(_x.id, _x.type, _x.action))
00401 _v9 = val3.pose
00402 _v10 = _v9.position
00403 _x = _v10
00404 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00405 _v11 = _v9.orientation
00406 _x = _v11
00407 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00408 _v12 = val3.scale
00409 _x = _v12
00410 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00411 _v13 = val3.color
00412 _x = _v13
00413 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00414 _v14 = val3.lifetime
00415 _x = _v14
00416 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00417 buff.write(_struct_B.pack(val3.frame_locked))
00418 length = len(val3.points)
00419 buff.write(_struct_I.pack(length))
00420 for val4 in val3.points:
00421 _x = val4
00422 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00423 length = len(val3.colors)
00424 buff.write(_struct_I.pack(length))
00425 for val4 in val3.colors:
00426 _x = val4
00427 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00428 _x = val3.text
00429 length = len(_x)
00430 buff.write(struct.pack('<I%ss'%length, length, _x))
00431 _x = val3.mesh_resource
00432 length = len(_x)
00433 buff.write(struct.pack('<I%ss'%length, length, _x))
00434 buff.write(_struct_B.pack(val3.mesh_use_embedded_materials))
00435 buff.write(_struct_B.pack(val2.independent_marker_orientation))
00436 _x = val2.description
00437 length = len(_x)
00438 buff.write(struct.pack('<I%ss'%length, length, _x))
00439 except struct.error as se: self._check_types(se)
00440 except TypeError as te: self._check_types(te)
00441
00442 def deserialize(self, str):
00443 """
00444 unpack serialized message in str into this message instance
00445 @param str: byte array of serialized message
00446 @type str: str
00447 """
00448 try:
00449 end = 0
00450 start = end
00451 end += 4
00452 (length,) = _struct_I.unpack(str[start:end])
00453 start = end
00454 end += length
00455 self.server_id = str[start:end]
00456 start = end
00457 end += 8
00458 (self.seq_num,) = _struct_Q.unpack(str[start:end])
00459 start = end
00460 end += 4
00461 (length,) = _struct_I.unpack(str[start:end])
00462 self.markers = []
00463 for i in range(0, length):
00464 val1 = visualization_msgs.msg.InteractiveMarker()
00465 _v15 = val1.header
00466 start = end
00467 end += 4
00468 (_v15.seq,) = _struct_I.unpack(str[start:end])
00469 _v16 = _v15.stamp
00470 _x = _v16
00471 start = end
00472 end += 8
00473 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00474 start = end
00475 end += 4
00476 (length,) = _struct_I.unpack(str[start:end])
00477 start = end
00478 end += length
00479 _v15.frame_id = str[start:end]
00480 _v17 = val1.pose
00481 _v18 = _v17.position
00482 _x = _v18
00483 start = end
00484 end += 24
00485 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00486 _v19 = _v17.orientation
00487 _x = _v19
00488 start = end
00489 end += 32
00490 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00491 start = end
00492 end += 4
00493 (length,) = _struct_I.unpack(str[start:end])
00494 start = end
00495 end += length
00496 val1.name = str[start:end]
00497 start = end
00498 end += 4
00499 (length,) = _struct_I.unpack(str[start:end])
00500 start = end
00501 end += length
00502 val1.description = str[start:end]
00503 start = end
00504 end += 4
00505 (val1.scale,) = _struct_f.unpack(str[start:end])
00506 start = end
00507 end += 4
00508 (length,) = _struct_I.unpack(str[start:end])
00509 val1.menu_entries = []
00510 for i in range(0, length):
00511 val2 = visualization_msgs.msg.MenuEntry()
00512 _x = val2
00513 start = end
00514 end += 8
00515 (_x.id, _x.parent_id,) = _struct_2I.unpack(str[start:end])
00516 start = end
00517 end += 4
00518 (length,) = _struct_I.unpack(str[start:end])
00519 start = end
00520 end += length
00521 val2.title = str[start:end]
00522 start = end
00523 end += 4
00524 (length,) = _struct_I.unpack(str[start:end])
00525 start = end
00526 end += length
00527 val2.command = str[start:end]
00528 start = end
00529 end += 1
00530 (val2.command_type,) = _struct_B.unpack(str[start:end])
00531 val1.menu_entries.append(val2)
00532 start = end
00533 end += 4
00534 (length,) = _struct_I.unpack(str[start:end])
00535 val1.controls = []
00536 for i in range(0, length):
00537 val2 = visualization_msgs.msg.InteractiveMarkerControl()
00538 start = end
00539 end += 4
00540 (length,) = _struct_I.unpack(str[start:end])
00541 start = end
00542 end += length
00543 val2.name = str[start:end]
00544 _v20 = val2.orientation
00545 _x = _v20
00546 start = end
00547 end += 32
00548 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00549 _x = val2
00550 start = end
00551 end += 3
00552 (_x.orientation_mode, _x.interaction_mode, _x.always_visible,) = _struct_3B.unpack(str[start:end])
00553 val2.always_visible = bool(val2.always_visible)
00554 start = end
00555 end += 4
00556 (length,) = _struct_I.unpack(str[start:end])
00557 val2.markers = []
00558 for i in range(0, length):
00559 val3 = visualization_msgs.msg.Marker()
00560 _v21 = val3.header
00561 start = end
00562 end += 4
00563 (_v21.seq,) = _struct_I.unpack(str[start:end])
00564 _v22 = _v21.stamp
00565 _x = _v22
00566 start = end
00567 end += 8
00568 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00569 start = end
00570 end += 4
00571 (length,) = _struct_I.unpack(str[start:end])
00572 start = end
00573 end += length
00574 _v21.frame_id = str[start:end]
00575 start = end
00576 end += 4
00577 (length,) = _struct_I.unpack(str[start:end])
00578 start = end
00579 end += length
00580 val3.ns = str[start:end]
00581 _x = val3
00582 start = end
00583 end += 12
00584 (_x.id, _x.type, _x.action,) = _struct_3i.unpack(str[start:end])
00585 _v23 = val3.pose
00586 _v24 = _v23.position
00587 _x = _v24
00588 start = end
00589 end += 24
00590 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00591 _v25 = _v23.orientation
00592 _x = _v25
00593 start = end
00594 end += 32
00595 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00596 _v26 = val3.scale
00597 _x = _v26
00598 start = end
00599 end += 24
00600 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00601 _v27 = val3.color
00602 _x = _v27
00603 start = end
00604 end += 16
00605 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00606 _v28 = val3.lifetime
00607 _x = _v28
00608 start = end
00609 end += 8
00610 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00611 start = end
00612 end += 1
00613 (val3.frame_locked,) = _struct_B.unpack(str[start:end])
00614 val3.frame_locked = bool(val3.frame_locked)
00615 start = end
00616 end += 4
00617 (length,) = _struct_I.unpack(str[start:end])
00618 val3.points = []
00619 for i in range(0, length):
00620 val4 = geometry_msgs.msg.Point()
00621 _x = val4
00622 start = end
00623 end += 24
00624 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00625 val3.points.append(val4)
00626 start = end
00627 end += 4
00628 (length,) = _struct_I.unpack(str[start:end])
00629 val3.colors = []
00630 for i in range(0, length):
00631 val4 = std_msgs.msg.ColorRGBA()
00632 _x = val4
00633 start = end
00634 end += 16
00635 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00636 val3.colors.append(val4)
00637 start = end
00638 end += 4
00639 (length,) = _struct_I.unpack(str[start:end])
00640 start = end
00641 end += length
00642 val3.text = str[start:end]
00643 start = end
00644 end += 4
00645 (length,) = _struct_I.unpack(str[start:end])
00646 start = end
00647 end += length
00648 val3.mesh_resource = str[start:end]
00649 start = end
00650 end += 1
00651 (val3.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
00652 val3.mesh_use_embedded_materials = bool(val3.mesh_use_embedded_materials)
00653 val2.markers.append(val3)
00654 start = end
00655 end += 1
00656 (val2.independent_marker_orientation,) = _struct_B.unpack(str[start:end])
00657 val2.independent_marker_orientation = bool(val2.independent_marker_orientation)
00658 start = end
00659 end += 4
00660 (length,) = _struct_I.unpack(str[start:end])
00661 start = end
00662 end += length
00663 val2.description = str[start:end]
00664 val1.controls.append(val2)
00665 self.markers.append(val1)
00666 return self
00667 except struct.error as e:
00668 raise roslib.message.DeserializationError(e)
00669
00670
00671 def serialize_numpy(self, buff, numpy):
00672 """
00673 serialize message with numpy array types into buffer
00674 @param buff: buffer
00675 @type buff: StringIO
00676 @param numpy: numpy python module
00677 @type numpy module
00678 """
00679 try:
00680 _x = self.server_id
00681 length = len(_x)
00682 buff.write(struct.pack('<I%ss'%length, length, _x))
00683 buff.write(_struct_Q.pack(self.seq_num))
00684 length = len(self.markers)
00685 buff.write(_struct_I.pack(length))
00686 for val1 in self.markers:
00687 _v29 = val1.header
00688 buff.write(_struct_I.pack(_v29.seq))
00689 _v30 = _v29.stamp
00690 _x = _v30
00691 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00692 _x = _v29.frame_id
00693 length = len(_x)
00694 buff.write(struct.pack('<I%ss'%length, length, _x))
00695 _v31 = val1.pose
00696 _v32 = _v31.position
00697 _x = _v32
00698 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00699 _v33 = _v31.orientation
00700 _x = _v33
00701 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00702 _x = val1.name
00703 length = len(_x)
00704 buff.write(struct.pack('<I%ss'%length, length, _x))
00705 _x = val1.description
00706 length = len(_x)
00707 buff.write(struct.pack('<I%ss'%length, length, _x))
00708 buff.write(_struct_f.pack(val1.scale))
00709 length = len(val1.menu_entries)
00710 buff.write(_struct_I.pack(length))
00711 for val2 in val1.menu_entries:
00712 _x = val2
00713 buff.write(_struct_2I.pack(_x.id, _x.parent_id))
00714 _x = val2.title
00715 length = len(_x)
00716 buff.write(struct.pack('<I%ss'%length, length, _x))
00717 _x = val2.command
00718 length = len(_x)
00719 buff.write(struct.pack('<I%ss'%length, length, _x))
00720 buff.write(_struct_B.pack(val2.command_type))
00721 length = len(val1.controls)
00722 buff.write(_struct_I.pack(length))
00723 for val2 in val1.controls:
00724 _x = val2.name
00725 length = len(_x)
00726 buff.write(struct.pack('<I%ss'%length, length, _x))
00727 _v34 = val2.orientation
00728 _x = _v34
00729 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00730 _x = val2
00731 buff.write(_struct_3B.pack(_x.orientation_mode, _x.interaction_mode, _x.always_visible))
00732 length = len(val2.markers)
00733 buff.write(_struct_I.pack(length))
00734 for val3 in val2.markers:
00735 _v35 = val3.header
00736 buff.write(_struct_I.pack(_v35.seq))
00737 _v36 = _v35.stamp
00738 _x = _v36
00739 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00740 _x = _v35.frame_id
00741 length = len(_x)
00742 buff.write(struct.pack('<I%ss'%length, length, _x))
00743 _x = val3.ns
00744 length = len(_x)
00745 buff.write(struct.pack('<I%ss'%length, length, _x))
00746 _x = val3
00747 buff.write(_struct_3i.pack(_x.id, _x.type, _x.action))
00748 _v37 = val3.pose
00749 _v38 = _v37.position
00750 _x = _v38
00751 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00752 _v39 = _v37.orientation
00753 _x = _v39
00754 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00755 _v40 = val3.scale
00756 _x = _v40
00757 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00758 _v41 = val3.color
00759 _x = _v41
00760 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00761 _v42 = val3.lifetime
00762 _x = _v42
00763 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00764 buff.write(_struct_B.pack(val3.frame_locked))
00765 length = len(val3.points)
00766 buff.write(_struct_I.pack(length))
00767 for val4 in val3.points:
00768 _x = val4
00769 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00770 length = len(val3.colors)
00771 buff.write(_struct_I.pack(length))
00772 for val4 in val3.colors:
00773 _x = val4
00774 buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00775 _x = val3.text
00776 length = len(_x)
00777 buff.write(struct.pack('<I%ss'%length, length, _x))
00778 _x = val3.mesh_resource
00779 length = len(_x)
00780 buff.write(struct.pack('<I%ss'%length, length, _x))
00781 buff.write(_struct_B.pack(val3.mesh_use_embedded_materials))
00782 buff.write(_struct_B.pack(val2.independent_marker_orientation))
00783 _x = val2.description
00784 length = len(_x)
00785 buff.write(struct.pack('<I%ss'%length, length, _x))
00786 except struct.error as se: self._check_types(se)
00787 except TypeError as te: self._check_types(te)
00788
00789 def deserialize_numpy(self, str, numpy):
00790 """
00791 unpack serialized message in str into this message instance using numpy for array types
00792 @param str: byte array of serialized message
00793 @type str: str
00794 @param numpy: numpy python module
00795 @type numpy: module
00796 """
00797 try:
00798 end = 0
00799 start = end
00800 end += 4
00801 (length,) = _struct_I.unpack(str[start:end])
00802 start = end
00803 end += length
00804 self.server_id = str[start:end]
00805 start = end
00806 end += 8
00807 (self.seq_num,) = _struct_Q.unpack(str[start:end])
00808 start = end
00809 end += 4
00810 (length,) = _struct_I.unpack(str[start:end])
00811 self.markers = []
00812 for i in range(0, length):
00813 val1 = visualization_msgs.msg.InteractiveMarker()
00814 _v43 = val1.header
00815 start = end
00816 end += 4
00817 (_v43.seq,) = _struct_I.unpack(str[start:end])
00818 _v44 = _v43.stamp
00819 _x = _v44
00820 start = end
00821 end += 8
00822 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00823 start = end
00824 end += 4
00825 (length,) = _struct_I.unpack(str[start:end])
00826 start = end
00827 end += length
00828 _v43.frame_id = str[start:end]
00829 _v45 = val1.pose
00830 _v46 = _v45.position
00831 _x = _v46
00832 start = end
00833 end += 24
00834 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00835 _v47 = _v45.orientation
00836 _x = _v47
00837 start = end
00838 end += 32
00839 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00840 start = end
00841 end += 4
00842 (length,) = _struct_I.unpack(str[start:end])
00843 start = end
00844 end += length
00845 val1.name = str[start:end]
00846 start = end
00847 end += 4
00848 (length,) = _struct_I.unpack(str[start:end])
00849 start = end
00850 end += length
00851 val1.description = str[start:end]
00852 start = end
00853 end += 4
00854 (val1.scale,) = _struct_f.unpack(str[start:end])
00855 start = end
00856 end += 4
00857 (length,) = _struct_I.unpack(str[start:end])
00858 val1.menu_entries = []
00859 for i in range(0, length):
00860 val2 = visualization_msgs.msg.MenuEntry()
00861 _x = val2
00862 start = end
00863 end += 8
00864 (_x.id, _x.parent_id,) = _struct_2I.unpack(str[start:end])
00865 start = end
00866 end += 4
00867 (length,) = _struct_I.unpack(str[start:end])
00868 start = end
00869 end += length
00870 val2.title = str[start:end]
00871 start = end
00872 end += 4
00873 (length,) = _struct_I.unpack(str[start:end])
00874 start = end
00875 end += length
00876 val2.command = str[start:end]
00877 start = end
00878 end += 1
00879 (val2.command_type,) = _struct_B.unpack(str[start:end])
00880 val1.menu_entries.append(val2)
00881 start = end
00882 end += 4
00883 (length,) = _struct_I.unpack(str[start:end])
00884 val1.controls = []
00885 for i in range(0, length):
00886 val2 = visualization_msgs.msg.InteractiveMarkerControl()
00887 start = end
00888 end += 4
00889 (length,) = _struct_I.unpack(str[start:end])
00890 start = end
00891 end += length
00892 val2.name = str[start:end]
00893 _v48 = val2.orientation
00894 _x = _v48
00895 start = end
00896 end += 32
00897 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00898 _x = val2
00899 start = end
00900 end += 3
00901 (_x.orientation_mode, _x.interaction_mode, _x.always_visible,) = _struct_3B.unpack(str[start:end])
00902 val2.always_visible = bool(val2.always_visible)
00903 start = end
00904 end += 4
00905 (length,) = _struct_I.unpack(str[start:end])
00906 val2.markers = []
00907 for i in range(0, length):
00908 val3 = visualization_msgs.msg.Marker()
00909 _v49 = val3.header
00910 start = end
00911 end += 4
00912 (_v49.seq,) = _struct_I.unpack(str[start:end])
00913 _v50 = _v49.stamp
00914 _x = _v50
00915 start = end
00916 end += 8
00917 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00918 start = end
00919 end += 4
00920 (length,) = _struct_I.unpack(str[start:end])
00921 start = end
00922 end += length
00923 _v49.frame_id = str[start:end]
00924 start = end
00925 end += 4
00926 (length,) = _struct_I.unpack(str[start:end])
00927 start = end
00928 end += length
00929 val3.ns = str[start:end]
00930 _x = val3
00931 start = end
00932 end += 12
00933 (_x.id, _x.type, _x.action,) = _struct_3i.unpack(str[start:end])
00934 _v51 = val3.pose
00935 _v52 = _v51.position
00936 _x = _v52
00937 start = end
00938 end += 24
00939 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00940 _v53 = _v51.orientation
00941 _x = _v53
00942 start = end
00943 end += 32
00944 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00945 _v54 = val3.scale
00946 _x = _v54
00947 start = end
00948 end += 24
00949 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00950 _v55 = val3.color
00951 _x = _v55
00952 start = end
00953 end += 16
00954 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00955 _v56 = val3.lifetime
00956 _x = _v56
00957 start = end
00958 end += 8
00959 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00960 start = end
00961 end += 1
00962 (val3.frame_locked,) = _struct_B.unpack(str[start:end])
00963 val3.frame_locked = bool(val3.frame_locked)
00964 start = end
00965 end += 4
00966 (length,) = _struct_I.unpack(str[start:end])
00967 val3.points = []
00968 for i in range(0, length):
00969 val4 = geometry_msgs.msg.Point()
00970 _x = val4
00971 start = end
00972 end += 24
00973 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00974 val3.points.append(val4)
00975 start = end
00976 end += 4
00977 (length,) = _struct_I.unpack(str[start:end])
00978 val3.colors = []
00979 for i in range(0, length):
00980 val4 = std_msgs.msg.ColorRGBA()
00981 _x = val4
00982 start = end
00983 end += 16
00984 (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00985 val3.colors.append(val4)
00986 start = end
00987 end += 4
00988 (length,) = _struct_I.unpack(str[start:end])
00989 start = end
00990 end += length
00991 val3.text = str[start:end]
00992 start = end
00993 end += 4
00994 (length,) = _struct_I.unpack(str[start:end])
00995 start = end
00996 end += length
00997 val3.mesh_resource = str[start:end]
00998 start = end
00999 end += 1
01000 (val3.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
01001 val3.mesh_use_embedded_materials = bool(val3.mesh_use_embedded_materials)
01002 val2.markers.append(val3)
01003 start = end
01004 end += 1
01005 (val2.independent_marker_orientation,) = _struct_B.unpack(str[start:end])
01006 val2.independent_marker_orientation = bool(val2.independent_marker_orientation)
01007 start = end
01008 end += 4
01009 (length,) = _struct_I.unpack(str[start:end])
01010 start = end
01011 end += length
01012 val2.description = str[start:end]
01013 val1.controls.append(val2)
01014 self.markers.append(val1)
01015 return self
01016 except struct.error as e:
01017 raise roslib.message.DeserializationError(e)
01018
01019 _struct_I = roslib.message.struct_I
01020 _struct_B = struct.Struct("<B")
01021 _struct_f = struct.Struct("<f")
01022 _struct_2i = struct.Struct("<2i")
01023 _struct_Q = struct.Struct("<Q")
01024 _struct_3i = struct.Struct("<3i")
01025 _struct_4f = struct.Struct("<4f")
01026 _struct_3B = struct.Struct("<3B")
01027 _struct_4d = struct.Struct("<4d")
01028 _struct_2I = struct.Struct("<2I")
01029 _struct_3d = struct.Struct("<3d")