$search
00001 """autogenerated by genmsg_py from InteractiveMarkerFeedback.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import geometry_msgs.msg 00006 import std_msgs.msg 00007 00008 class InteractiveMarkerFeedback(roslib.message.Message): 00009 _md5sum = "ab0f1eee058667e28c19ff3ffc3f4b78" 00010 _type = "visualization_msgs/InteractiveMarkerFeedback" 00011 _has_header = True #flag to mark the presence of a Header object 00012 _full_text = """# Time/frame info. 00013 Header header 00014 00015 # Identifying string. Must be unique in the topic namespace. 00016 string client_id 00017 00018 # Feedback message sent back from the GUI, e.g. 00019 # when the status of an interactive marker was modified by the user. 00020 00021 # Specifies which interactive marker and control this message refers to 00022 string marker_name 00023 string control_name 00024 00025 # Type of the event 00026 # KEEP_ALIVE: sent while dragging to keep up control of the marker 00027 # MENU_SELECT: a menu entry has been selected 00028 # BUTTON_CLICK: a button control has been clicked 00029 # POSE_UPDATE: the pose has been changed using one of the controls 00030 uint8 KEEP_ALIVE = 0 00031 uint8 POSE_UPDATE = 1 00032 uint8 MENU_SELECT = 2 00033 uint8 BUTTON_CLICK = 3 00034 00035 uint8 MOUSE_DOWN = 4 00036 uint8 MOUSE_UP = 5 00037 00038 uint8 event_type 00039 00040 # Current pose of the marker 00041 # Note: Has to be valid for all feedback types. 00042 geometry_msgs/Pose pose 00043 00044 # Contains the ID of the selected menu entry 00045 # Only valid for MENU_SELECT events. 00046 uint32 menu_entry_id 00047 00048 # If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point 00049 # may contain the 3 dimensional position of the event on the 00050 # control. If it does, mouse_point_valid will be true. mouse_point 00051 # will be relative to the frame listed in the header. 00052 geometry_msgs/Point mouse_point 00053 bool mouse_point_valid 00054 00055 ================================================================================ 00056 MSG: std_msgs/Header 00057 # Standard metadata for higher-level stamped data types. 00058 # This is generally used to communicate timestamped data 00059 # in a particular coordinate frame. 00060 # 00061 # sequence ID: consecutively increasing ID 00062 uint32 seq 00063 #Two-integer timestamp that is expressed as: 00064 # * stamp.secs: seconds (stamp_secs) since epoch 00065 # * stamp.nsecs: nanoseconds since stamp_secs 00066 # time-handling sugar is provided by the client library 00067 time stamp 00068 #Frame this data is associated with 00069 # 0: no frame 00070 # 1: global frame 00071 string frame_id 00072 00073 ================================================================================ 00074 MSG: geometry_msgs/Pose 00075 # A representation of pose in free space, composed of postion and orientation. 00076 Point position 00077 Quaternion orientation 00078 00079 ================================================================================ 00080 MSG: geometry_msgs/Point 00081 # This contains the position of a point in free space 00082 float64 x 00083 float64 y 00084 float64 z 00085 00086 ================================================================================ 00087 MSG: geometry_msgs/Quaternion 00088 # This represents an orientation in free space in quaternion form. 00089 00090 float64 x 00091 float64 y 00092 float64 z 00093 float64 w 00094 00095 """ 00096 # Pseudo-constants 00097 KEEP_ALIVE = 0 00098 POSE_UPDATE = 1 00099 MENU_SELECT = 2 00100 BUTTON_CLICK = 3 00101 MOUSE_DOWN = 4 00102 MOUSE_UP = 5 00103 00104 __slots__ = ['header','client_id','marker_name','control_name','event_type','pose','menu_entry_id','mouse_point','mouse_point_valid'] 00105 _slot_types = ['Header','string','string','string','uint8','geometry_msgs/Pose','uint32','geometry_msgs/Point','bool'] 00106 00107 def __init__(self, *args, **kwds): 00108 """ 00109 Constructor. Any message fields that are implicitly/explicitly 00110 set to None will be assigned a default value. The recommend 00111 use is keyword arguments as this is more robust to future message 00112 changes. You cannot mix in-order arguments and keyword arguments. 00113 00114 The available fields are: 00115 header,client_id,marker_name,control_name,event_type,pose,menu_entry_id,mouse_point,mouse_point_valid 00116 00117 @param args: complete set of field values, in .msg order 00118 @param kwds: use keyword arguments corresponding to message field names 00119 to set specific fields. 00120 """ 00121 if args or kwds: 00122 super(InteractiveMarkerFeedback, self).__init__(*args, **kwds) 00123 #message fields cannot be None, assign default values for those that are 00124 if self.header is None: 00125 self.header = std_msgs.msg._Header.Header() 00126 if self.client_id is None: 00127 self.client_id = '' 00128 if self.marker_name is None: 00129 self.marker_name = '' 00130 if self.control_name is None: 00131 self.control_name = '' 00132 if self.event_type is None: 00133 self.event_type = 0 00134 if self.pose is None: 00135 self.pose = geometry_msgs.msg.Pose() 00136 if self.menu_entry_id is None: 00137 self.menu_entry_id = 0 00138 if self.mouse_point is None: 00139 self.mouse_point = geometry_msgs.msg.Point() 00140 if self.mouse_point_valid is None: 00141 self.mouse_point_valid = False 00142 else: 00143 self.header = std_msgs.msg._Header.Header() 00144 self.client_id = '' 00145 self.marker_name = '' 00146 self.control_name = '' 00147 self.event_type = 0 00148 self.pose = geometry_msgs.msg.Pose() 00149 self.menu_entry_id = 0 00150 self.mouse_point = geometry_msgs.msg.Point() 00151 self.mouse_point_valid = False 00152 00153 def _get_types(self): 00154 """ 00155 internal API method 00156 """ 00157 return self._slot_types 00158 00159 def serialize(self, buff): 00160 """ 00161 serialize message into buffer 00162 @param buff: buffer 00163 @type buff: StringIO 00164 """ 00165 try: 00166 _x = self 00167 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00168 _x = self.header.frame_id 00169 length = len(_x) 00170 buff.write(struct.pack('<I%ss'%length, length, _x)) 00171 _x = self.client_id 00172 length = len(_x) 00173 buff.write(struct.pack('<I%ss'%length, length, _x)) 00174 _x = self.marker_name 00175 length = len(_x) 00176 buff.write(struct.pack('<I%ss'%length, length, _x)) 00177 _x = self.control_name 00178 length = len(_x) 00179 buff.write(struct.pack('<I%ss'%length, length, _x)) 00180 _x = self 00181 buff.write(_struct_B7dI3dB.pack(_x.event_type, _x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w, _x.menu_entry_id, _x.mouse_point.x, _x.mouse_point.y, _x.mouse_point.z, _x.mouse_point_valid)) 00182 except struct.error as se: self._check_types(se) 00183 except TypeError as te: self._check_types(te) 00184 00185 def deserialize(self, str): 00186 """ 00187 unpack serialized message in str into this message instance 00188 @param str: byte array of serialized message 00189 @type str: str 00190 """ 00191 try: 00192 if self.header is None: 00193 self.header = std_msgs.msg._Header.Header() 00194 if self.pose is None: 00195 self.pose = geometry_msgs.msg.Pose() 00196 if self.mouse_point is None: 00197 self.mouse_point = geometry_msgs.msg.Point() 00198 end = 0 00199 _x = self 00200 start = end 00201 end += 12 00202 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00203 start = end 00204 end += 4 00205 (length,) = _struct_I.unpack(str[start:end]) 00206 start = end 00207 end += length 00208 self.header.frame_id = str[start:end] 00209 start = end 00210 end += 4 00211 (length,) = _struct_I.unpack(str[start:end]) 00212 start = end 00213 end += length 00214 self.client_id = str[start:end] 00215 start = end 00216 end += 4 00217 (length,) = _struct_I.unpack(str[start:end]) 00218 start = end 00219 end += length 00220 self.marker_name = str[start:end] 00221 start = end 00222 end += 4 00223 (length,) = _struct_I.unpack(str[start:end]) 00224 start = end 00225 end += length 00226 self.control_name = str[start:end] 00227 _x = self 00228 start = end 00229 end += 86 00230 (_x.event_type, _x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w, _x.menu_entry_id, _x.mouse_point.x, _x.mouse_point.y, _x.mouse_point.z, _x.mouse_point_valid,) = _struct_B7dI3dB.unpack(str[start:end]) 00231 self.mouse_point_valid = bool(self.mouse_point_valid) 00232 return self 00233 except struct.error as e: 00234 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00235 00236 00237 def serialize_numpy(self, buff, numpy): 00238 """ 00239 serialize message with numpy array types into buffer 00240 @param buff: buffer 00241 @type buff: StringIO 00242 @param numpy: numpy python module 00243 @type numpy module 00244 """ 00245 try: 00246 _x = self 00247 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00248 _x = self.header.frame_id 00249 length = len(_x) 00250 buff.write(struct.pack('<I%ss'%length, length, _x)) 00251 _x = self.client_id 00252 length = len(_x) 00253 buff.write(struct.pack('<I%ss'%length, length, _x)) 00254 _x = self.marker_name 00255 length = len(_x) 00256 buff.write(struct.pack('<I%ss'%length, length, _x)) 00257 _x = self.control_name 00258 length = len(_x) 00259 buff.write(struct.pack('<I%ss'%length, length, _x)) 00260 _x = self 00261 buff.write(_struct_B7dI3dB.pack(_x.event_type, _x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w, _x.menu_entry_id, _x.mouse_point.x, _x.mouse_point.y, _x.mouse_point.z, _x.mouse_point_valid)) 00262 except struct.error as se: self._check_types(se) 00263 except TypeError as te: self._check_types(te) 00264 00265 def deserialize_numpy(self, str, numpy): 00266 """ 00267 unpack serialized message in str into this message instance using numpy for array types 00268 @param str: byte array of serialized message 00269 @type str: str 00270 @param numpy: numpy python module 00271 @type numpy: module 00272 """ 00273 try: 00274 if self.header is None: 00275 self.header = std_msgs.msg._Header.Header() 00276 if self.pose is None: 00277 self.pose = geometry_msgs.msg.Pose() 00278 if self.mouse_point is None: 00279 self.mouse_point = geometry_msgs.msg.Point() 00280 end = 0 00281 _x = self 00282 start = end 00283 end += 12 00284 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00285 start = end 00286 end += 4 00287 (length,) = _struct_I.unpack(str[start:end]) 00288 start = end 00289 end += length 00290 self.header.frame_id = str[start:end] 00291 start = end 00292 end += 4 00293 (length,) = _struct_I.unpack(str[start:end]) 00294 start = end 00295 end += length 00296 self.client_id = str[start:end] 00297 start = end 00298 end += 4 00299 (length,) = _struct_I.unpack(str[start:end]) 00300 start = end 00301 end += length 00302 self.marker_name = str[start:end] 00303 start = end 00304 end += 4 00305 (length,) = _struct_I.unpack(str[start:end]) 00306 start = end 00307 end += length 00308 self.control_name = str[start:end] 00309 _x = self 00310 start = end 00311 end += 86 00312 (_x.event_type, _x.pose.position.x, _x.pose.position.y, _x.pose.position.z, _x.pose.orientation.x, _x.pose.orientation.y, _x.pose.orientation.z, _x.pose.orientation.w, _x.menu_entry_id, _x.mouse_point.x, _x.mouse_point.y, _x.mouse_point.z, _x.mouse_point_valid,) = _struct_B7dI3dB.unpack(str[start:end]) 00313 self.mouse_point_valid = bool(self.mouse_point_valid) 00314 return self 00315 except struct.error as e: 00316 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00317 00318 _struct_I = roslib.message.struct_I 00319 _struct_3I = struct.Struct("<3I") 00320 _struct_B7dI3dB = struct.Struct("<B7dI3dB")