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