menu.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 """
4 Copyright (c) 2011, Willow Garage, Inc.
5 All rights reserved.
6 
7 Redistribution and use in source and binary forms, with or without
8 modification, are permitted provided that the following conditions are met:
9 
10  * Redistributions of source code must retain the above copyright
11  notice, this list of conditions and the following disclaimer.
12  * Redistributions in binary form must reproduce the above copyright
13  notice, this list of conditions and the following disclaimer in the
14  documentation and/or other materials provided with the distribution.
15  * Neither the name of the Willow Garage, Inc. nor the names of its
16  contributors may be used to endorse or promote products derived from
17  this software without specific prior written permission.
18 
19 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22 ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23 LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24 CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25 SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26 INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27 CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28 ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 POSSIBILITY OF SUCH DAMAGE.
30 """
31 
32 import rospy
33 
36 from visualization_msgs.msg import *
37 
38 server = None
39 marker_pos = 0
40 
41 menu_handler = MenuHandler()
42 
43 h_first_entry = 0
44 h_mode_last = 0
45 
46 def enableCb( feedback ):
47  handle = feedback.menu_entry_id
48  state = menu_handler.getCheckState( handle )
49 
50  if state == MenuHandler.CHECKED:
51  menu_handler.setCheckState( handle, MenuHandler.UNCHECKED )
52  rospy.loginfo("Hiding first menu entry")
53  menu_handler.setVisible( h_first_entry, False )
54  else:
55  menu_handler.setCheckState( handle, MenuHandler.CHECKED )
56  rospy.loginfo("Showing first menu entry")
57  menu_handler.setVisible( h_first_entry, True )
58 
59  menu_handler.reApply( server )
60  rospy.loginfo("update")
61  server.applyChanges()
62 
63 def modeCb(feedback):
64  global h_mode_last
65  menu_handler.setCheckState( h_mode_last, MenuHandler.UNCHECKED )
66  h_mode_last = feedback.menu_entry_id
67  menu_handler.setCheckState( h_mode_last, MenuHandler.CHECKED )
68 
69  rospy.loginfo("Switching to menu entry #" + str(h_mode_last))
70  menu_handler.reApply( server )
71  print "DONE"
72  server.applyChanges()
73 
74 def makeBox( msg ):
75  marker = Marker()
76 
77  marker.type = Marker.CUBE
78  marker.scale.x = msg.scale * 0.45
79  marker.scale.y = msg.scale * 0.45
80  marker.scale.z = msg.scale * 0.45
81  marker.color.r = 0.5
82  marker.color.g = 0.5
83  marker.color.b = 0.5
84  marker.color.a = 1.0
85 
86  return marker
87 
88 def makeBoxControl( msg ):
89  control = InteractiveMarkerControl()
90  control.always_visible = True
91  control.markers.append( makeBox(msg) )
92  msg.controls.append( control )
93  return control
94 
95 def makeEmptyMarker( dummyBox=True ):
96  global marker_pos
97  int_marker = InteractiveMarker()
98  int_marker.header.frame_id = "base_link"
99  int_marker.pose.position.y = -3.0 * marker_pos
100  marker_pos += 1
101  int_marker.scale = 1
102  return int_marker
103 
104 def makeMenuMarker( name ):
105  int_marker = makeEmptyMarker()
106  int_marker.name = name
107 
108  control = InteractiveMarkerControl()
109 
110  control.interaction_mode = InteractiveMarkerControl.BUTTON
111  control.always_visible = True
112 
113  control.markers.append( makeBox( int_marker ) )
114  int_marker.controls.append(control)
115 
116  server.insert( int_marker )
117 
118 def deepCb( feedback ):
119  rospy.loginfo("The deep sub-menu has been found.")
120 
121 def initMenu():
122  global h_first_entry, h_mode_last
123  h_first_entry = menu_handler.insert( "First Entry" )
124  entry = menu_handler.insert( "deep", parent=h_first_entry)
125  entry = menu_handler.insert( "sub", parent=entry );
126  entry = menu_handler.insert( "menu", parent=entry, callback=deepCb );
127 
128  menu_handler.setCheckState( menu_handler.insert( "Show First Entry", callback=enableCb ), MenuHandler.CHECKED )
129 
130  sub_menu_handle = menu_handler.insert( "Switch" )
131  for i in range(5):
132  s = "Mode " + str(i)
133  h_mode_last = menu_handler.insert( s, parent=sub_menu_handle, callback=modeCb )
134  menu_handler.setCheckState( h_mode_last, MenuHandler.UNCHECKED)
135  # check the very last entry
136  menu_handler.setCheckState( h_mode_last, MenuHandler.CHECKED )
137 
138 if __name__=="__main__":
139  rospy.init_node("menu")
140 
141  server = InteractiveMarkerServer("menu")
142 
143  initMenu()
144 
145  makeMenuMarker( "marker1" )
146  makeMenuMarker( "marker2" )
147 
148  menu_handler.apply( server, "marker1" )
149  menu_handler.apply( server, "marker2" )
150  server.applyChanges()
151 
152  rospy.spin()
153 
def makeMenuMarker(name)
Definition: menu.py:104
def deepCb(feedback)
Definition: menu.py:118
def enableCb(feedback)
Definition: menu.py:46
def makeBoxControl(msg)
Definition: menu.py:88
def initMenu()
Definition: menu.py:121
def makeEmptyMarker(dummyBox=True)
Definition: menu.py:95
def modeCb(feedback)
Definition: menu.py:63
def makeBox(msg)
Definition: menu.py:74


interactive_marker_tutorials
Author(s): David Gossow
autogenerated on Fri Feb 1 2019 03:33:34