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 rospy
00033 
00034 from visualization_msgs.msg import InteractiveMarkerFeedback
00035 from visualization_msgs.msg import MenuEntry
00036 
00037 
00038 class EntryContext:
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 
00049 ## @brief Simple non-intrusive helper class which creates a menu and maps its
00050 ## entries to function callbacks
00051 class MenuHandler:
00052     NO_CHECKBOX = 0
00053     CHECKED = 1
00054     UNCHECKED = 2
00055 
00056     def __init__(self):
00057         self.top_level_handles_ = list()    # std::vector<EntryHandle>
00058         self.entry_contexts_ = dict()       # boost::unordered_map<EntryHandle, EntryContext>
00059         self.current_handle_ = 1
00060         self.managed_markers_ = set()       # std::set<std::string>
00061 
00062     ## Insert a new menu item
00063     def insert(self, title, parent=None, command_type=MenuEntry.FEEDBACK, command="", callback=None):
00064         handle = self.doInsert(title, command_type, command, callback)
00065         if parent is not None:
00066             try:
00067                 parent_context = self.entry_contexts_[parent]
00068                 parent_context.sub_entries.append(handle)
00069             except:
00070                 rospy.logerr("Parent menu entry " + str(parent) + " not found.")
00071                 return None
00072         else:
00073             self.top_level_handles_.append(handle)
00074         return handle
00075 
00076     ## Specify if an entry should be visible or hidden
00077     def setVisible(self, handle, visible):
00078         try:
00079             context = self.entry_contexts_[handle]
00080             context.visible = visible
00081             return True
00082         except:
00083             return False
00084 
00085     ## Specify if an entry is checked or can't be checked at all
00086     def setCheckState(self, handle, check_state):
00087         try:
00088             context = self.entry_contexts_[handle]
00089             context.check_state = check_state
00090             return True
00091         except:
00092             return False
00093 
00094     ## Get the current state of an entry
00095     ## @return CheckState if the entry exists and has checkbox, None otherwise
00096     def getCheckState(self, handle):
00097         try:
00098             context = self.entry_contexts_[handle]
00099             return context.check_state
00100         except:
00101             return None
00102 
00103     ## Copy current menu state into the marker given by the specified name &
00104     ## divert callback for MENU_SELECT feedback to this manager
00105     def apply(self, server, marker_name):
00106         marker = server.get(marker_name)
00107         if not marker:
00108             self.managed_markers_.remove(marker_name)
00109             return False
00110 
00111         marker.menu_entries = list()
00112         self.pushMenuEntries(self.top_level_handles_, marker.menu_entries, 0)
00113 
00114         server.insert(marker, self.processFeedback, InteractiveMarkerFeedback.MENU_SELECT)
00115         self.managed_markers_.add(marker_name)
00116         return True
00117 
00118     ## Re-apply to all markers that this was applied to previously
00119     def reApply(self, server):
00120         success = True
00121         # self.apply() might remove elements from
00122         # self.managed_markers_. To prevent errors, copy the
00123         # managed_markers sequence and iterate over the copy
00124         managed_markers = list(self.managed_markers_)
00125         for marker in managed_markers:
00126             success = self.apply(server, marker) and success
00127         return success
00128 
00129     ## @brief Get the title for the given menu entry
00130     ## @return The title, None if menu entry does not exist.
00131     def getTitle(self, handle):
00132         try:
00133             return self.entry_contexts_[handle].title
00134         except:
00135             return None
00136 
00137     # Call registered callback functions for given feedback command
00138     def processFeedback(self, feedback):
00139         try:
00140             context = self.entry_contexts_[feedback.menu_entry_id]
00141             context.feedback_cb(feedback)
00142         except KeyError:
00143             pass
00144 
00145     # Create and push MenuEntry objects from handles_in onto
00146     # entries_out. Calls itself recursively to add the entire menu tree.
00147     def pushMenuEntries(self, handles_in, entries_out, parent_handle):
00148         for handle in handles_in:
00149             try:
00150                 context = self.entry_contexts_[handle]
00151                 if not context.visible:
00152                     continue
00153                 entries_out.append(self.makeEntry(context, handle, parent_handle))
00154                 if not self.pushMenuEntries(context.sub_entries, entries_out, handle):
00155                     return False
00156             except:
00157                 rospy.logerr("Internal error: context handle not found! This is a bug in MenuHandler.")
00158                 return False
00159         return True
00160 
00161     def makeEntry(self, context, handle, parent_handle):
00162         menu_entry = MenuEntry()
00163         if context.check_state == self.NO_CHECKBOX:
00164             menu_entry.title = context.title
00165         elif context.check_state == self.CHECKED:
00166             menu_entry.title = "[x] "+context.title
00167         elif context.check_state == self.UNCHECKED:
00168             menu_entry.title = "[ ] "+context.title
00169 
00170         menu_entry.command = context.command
00171         menu_entry.command_type = context.command_type
00172         menu_entry.id = handle
00173         menu_entry.parent_id = parent_handle
00174 
00175         return menu_entry
00176 
00177     # Insert without adding a top-level entry
00178     def doInsert(self, title, command_type, command, feedback_cb):
00179         handle = self.current_handle_
00180         self.current_handle_ += 1
00181 
00182         context = EntryContext()
00183         context.title = title
00184         context.command = command
00185         context.command_type = command_type
00186         context.visible = True
00187         context.check_state = self.NO_CHECKBOX
00188         context.feedback_cb = feedback_cb
00189 
00190         self.entry_contexts_[handle] = context
00191         return handle


interactive_markers
Author(s): David Gossow
autogenerated on Fri Aug 28 2015 11:11:26