Go to the documentation of this file.00001
00002
00003 """
00004 Copyright (c) 2011, Willow Garage, Inc.
00005 All rights reserved.
00006
00007 Redistribution and use in source and binary forms, with or without
00008 modification, are permitted provided that the following conditions are met:
00009
00010 * Redistributions of source code must retain the above copyright
00011 notice, this list of conditions and the following disclaimer.
00012 * Redistributions in binary form must reproduce the above copyright
00013 notice, this list of conditions and the following disclaimer in the
00014 documentation and/or other materials provided with the distribution.
00015 * Neither the name of the Willow Garage, Inc. nor the names of its
00016 contributors may be used to endorse or promote products derived from
00017 this software without specific prior written permission.
00018
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022 ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023 LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024 CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025 SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026 INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027 CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028 ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029 POSSIBILITY OF SUCH DAMAGE.
00030 """
00031
00032 import roslib; roslib.load_manifest("interactive_markers")
00033 import rospy
00034
00035 from interactive_markers.interactive_marker_server import *
00036
00037 def processFeedback(feedback):
00038 p = feedback.pose.position
00039 print feedback.marker_name + " is now at " + str(p.x) + ", " + str(p.y) + ", " + str(p.z)
00040
00041 if __name__=="__main__":
00042 rospy.init_node("simple_marker")
00043
00044
00045 server = InteractiveMarkerServer("simple_marker")
00046
00047
00048 int_marker = InteractiveMarker()
00049 int_marker.header.frame_id = "/base_link"
00050 int_marker.name = "my_marker"
00051 int_marker.description = "Simple 1-DOF Control"
00052
00053
00054 box_marker = Marker()
00055 box_marker.type = Marker.CUBE
00056 box_marker.scale.x = 0.45
00057 box_marker.scale.y = 0.45
00058 box_marker.scale.z = 0.45
00059 box_marker.color.r = 0.0
00060 box_marker.color.g = 0.5
00061 box_marker.color.b = 0.5
00062 box_marker.color.a = 1.0
00063
00064
00065 box_control = InteractiveMarkerControl()
00066 box_control.always_visible = True
00067 box_control.markers.append( box_marker )
00068
00069
00070 int_marker.controls.append( box_control )
00071
00072
00073
00074
00075 rotate_control = InteractiveMarkerControl()
00076 rotate_control.name = "move_x"
00077 rotate_control.interaction_mode = InteractiveMarkerControl.MOVE_AXIS
00078
00079
00080 int_marker.controls.append(rotate_control);
00081
00082
00083
00084 server.insert(int_marker, processFeedback)
00085
00086
00087 server.applyChanges()
00088
00089 rospy.spin()
00090