menu_handler.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (c) 2011, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 #   * Redistributions of source code must retain the above copyright
00010 #     notice, this list of conditions and the following disclaimer.
00011 #   * Redistributions in binary form must reproduce the above copyright
00012 #     notice, this list of conditions and the following disclaimer in the
00013 #     documentation and/or other materials provided with the distribution.
00014 #   * Neither the name of the Willow Garage, Inc. nor the names of its
00015 #     contributors may be used to endorse or promote products derived from
00016 #     this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028 # POSSIBILITY OF SUCH DAMAGE.
00029 
00030 # Author: Michael Ferguson
00031 
00032 import roslib; roslib.load_manifest("interactive_markers")
00033 import rospy
00034 
00035 from visualization_msgs.msg import *
00036 
00037 class EntryContext:
00038     
00039     def __init__(self):
00040         self.title = ""
00041         self.command = ""
00042         self.command_type = 0
00043         self.sub_entries = list()
00044         self.visible = True
00045         self.check_state = 0
00046         self.feedback_cb = None
00047 
00048 ## @brief Simple non-intrusive helper class which creates a menu and maps its
00049 ## entries to function callbacks
00050 class MenuHandler:
00051     NO_CHECKBOX = 0
00052     CHECKED = 1
00053     UNCHECKED = 2
00054 
00055     def __init__(self):
00056         self.top_level_handles_ = list()    # std::vector<EntryHandle>
00057         self.entry_contexts_ = dict()       # boost::unordered_map<EntryHandle, EntryContext>
00058         self.current_handle_ = 1;
00059         self.managed_markers_ = set()       # std::set<std::string>
00060 
00061     ## Insert a new menu item
00062     def insert(self, title, parent=None, command_type=MenuEntry.FEEDBACK, command="", callback=None):
00063         handle = self.doInsert( title, command_type, command, callback )
00064         if parent != None:
00065             try:
00066                 parent_context = self.entry_contexts_[parent]           
00067                 parent_context.sub_entries.append( handle )
00068             except:
00069                 rospy.logerr("Parent menu entry " + str(parent) + " not found.")
00070                 return None
00071         else:
00072             self.top_level_handles_.append( handle )
00073         return handle
00074 
00075     ## Specify if an entry should be visible or hidden
00076     def setVisible(self, handle, visible):
00077         try:
00078             context = self.entry_contexts_[handle]
00079             context.visible = visible
00080             return True
00081         except:
00082             return False
00083 
00084     ## Specify if an entry is checked or can't be checked at all
00085     def setCheckState(self, handle, check_state):
00086         try:
00087             context = self.entry_contexts_[handle]
00088             context.check_state = check_state
00089             return True
00090         except:
00091             return False
00092 
00093     ## Get the current state of an entry
00094     ## @return CheckState if the entry exists and has checkbox, None otherwise
00095     def getCheckState(self, handle):
00096         try:
00097             context = self.entry_contexts_[handle]
00098             return context.check_state
00099         except:
00100             return None
00101 
00102     ## Copy current menu state into the marker given by the specified name &
00103     ## divert callback for MENU_SELECT feedback to this manager
00104     def apply(self, server, marker_name):
00105         marker = server.get(marker_name)
00106         if not marker:
00107             self.managed_markers_.remove(marker_name)
00108             return False
00109         
00110         marker.menu_entries = list()
00111         self.pushMenuEntries( self.top_level_handles_, marker.menu_entries, 0 )
00112 
00113         server.insert( marker, self.processFeedback, InteractiveMarkerFeedback.MENU_SELECT )
00114         self.managed_markers_.add( marker_name )
00115         return True
00116 
00117     ## Re-apply to all markers that this was applied to previously
00118     def reApply(self, server):
00119         success = True
00120         # self.apply() might remove elements from
00121         # self.managed_markers_. To prevent errors, copy the
00122         # managed_markers sequence and iterate over the copy
00123         managed_markers = list(self.managed_markers_)
00124         for marker in managed_markers:
00125             success = self.apply(server, marker) and success
00126         return success
00127 
00128     ## @brief Get the title for the given menu entry
00129     ## @return The title, None if menu entry does not exist.
00130     def getTitle(self, handle):
00131         try:
00132             return self.entry_contexts_[handle].title
00133         except:
00134             return None
00135 
00136     # Call registered callback functions for given feedback command
00137     def processFeedback(self, feedback):
00138         try:
00139             context = self.entry_contexts_[feedback.menu_entry_id]
00140             context.feedback_cb(feedback)
00141         except KeyError:
00142             pass
00143 
00144     # Create and push MenuEntry objects from handles_in onto
00145     # entries_out. Calls itself recursively to add the entire menu tree.
00146     def pushMenuEntries(self, handles_in, entries_out, parent_handle):
00147         for handle in handles_in:
00148             try:
00149                 context = self.entry_contexts_[handle]
00150                 if not context.visible:
00151                     continue
00152                 entries_out.append( self.makeEntry(context, handle, parent_handle) )
00153                 if not self.pushMenuEntries(context.sub_entries, entries_out, handle):
00154                     return False
00155             except:
00156                 rospy.logerr("Internal error: context handle not found! This is a bug in MenuHandler.")
00157                 return False
00158         return True
00159 
00160     def makeEntry(self, context, handle, parent_handle):
00161         menu_entry = MenuEntry()
00162         if context.check_state == self.NO_CHECKBOX:
00163             menu_entry.title = context.title
00164         elif context.check_state == self.CHECKED:
00165             menu_entry.title = "[x] "+context.title
00166         elif context.check_state == self.UNCHECKED:
00167             menu_entry.title = "[ ] "+context.title
00168 
00169         menu_entry.command = context.command
00170         menu_entry.command_type = context.command_type
00171         menu_entry.id = handle
00172         menu_entry.parent_id = parent_handle
00173 
00174         return menu_entry
00175 
00176     # Insert without adding a top-level entry
00177     def doInsert(self, title, command_type, command, feedback_cb):
00178         handle = self.current_handle_
00179         self.current_handle_ += 1
00180         
00181         context = EntryContext()
00182         context.title = title
00183         context.command = command
00184         context.command_type = command_type
00185         context.visible = True
00186         context.check_state = self.NO_CHECKBOX
00187         context.feedback_cb = feedback_cb
00188 
00189         self.entry_contexts_[handle] = context
00190         return handle
00191 


interactive_markers
Author(s): David Gossow (C++), Michael Ferguson (Python)
autogenerated on Mon Jan 6 2014 11:54:25