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("lwr_markers")
00033 import rospy
00034 import copy
00035
00036 import actionlib
00037 import arm_navigation_msgs.msg
00038
00039 from arm_navigation_msgs.msg import PositionConstraint
00040 from arm_navigation_msgs.msg import OrientationConstraint
00041
00042 from arm_navigation_msgs.msg import Shape
00043
00044 from interactive_markers.interactive_marker_server import *
00045 from interactive_markers.menu_handler import *
00046
00047 menu_handler = MenuHandler()
00048 client = actionlib.SimpleActionClient('move_right', arm_navigation_msgs.msg.MoveArmAction)
00049
00050
00051 def processFeedback(feedback):
00052
00053
00054
00055
00056
00057
00058 if feedback.event_type == InteractiveMarkerFeedback.MENU_SELECT:
00059 if (feedback.menu_entry_id == 1):
00060 p = feedback.pose
00061 print p
00062
00063 goalA = arm_navigation_msgs.msg.MoveArmGoal()
00064 goalA.motion_plan_request.group_name = "right";
00065 goalA.motion_plan_request.num_planning_attempts = 1;
00066 goalA.motion_plan_request.planner_id = "";
00067 goalA.planner_service_name = "ompl_planning/plan_kinematic_path";
00068 goalA.motion_plan_request.allowed_planning_time = rospy.Duration(5.0);
00069
00070 desired_pose = PositionConstraint()
00071 desired_pose.header.frame_id = "/world";
00072 desired_pose.link_name = "right_arm_7_link";
00073 desired_pose.position = p.position
00074
00075 desired_pose.constraint_region_shape.type = Shape.BOX
00076 desired_pose.constraint_region_shape.dimensions = [0.02, 0.02, 0.02]
00077 desired_pose.constraint_region_orientation.w = 1.0
00078
00079
00080 goalA.motion_plan_request.goal_constraints.position_constraints.append(desired_pose)
00081
00082 oc = OrientationConstraint()
00083 oc.header.stamp = rospy.Time.now()
00084 oc.header.frame_id = "/world";
00085 oc.link_name = "right_arm_7_link";
00086 oc.orientation = p.orientation
00087
00088 oc.absolute_roll_tolerance = 0.04
00089 oc.absolute_pitch_tolerance = 0.04
00090 oc.absolute_yaw_tolerance = 0.04
00091 oc.weight = 1.
00092
00093 goalA.motion_plan_request.goal_constraints.orientation_constraints.append(oc)
00094
00095 client.send_goal(goalA)
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106 if __name__=="__main__":
00107 rospy.init_node("simple_marker")
00108
00109
00110
00111 client = actionlib.SimpleActionClient('move_right', arm_navigation_msgs.msg.MoveArmAction)
00112 client.wait_for_server()
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122 server = InteractiveMarkerServer("simple_marker")
00123
00124 menu_handler.insert( "Go to", callback=processFeedback )
00125
00126
00127 int_marker = InteractiveMarker()
00128 int_marker.header.frame_id = "/world"
00129 int_marker.name = "my_marker"
00130 int_marker.description = "Right"
00131
00132
00133 box_marker = Marker()
00134 box_marker.type = Marker.CUBE
00135 box_marker.scale.x = 0.1
00136 box_marker.scale.y = 0.1
00137 box_marker.scale.z = 0.1
00138 box_marker.color.r = 0.0
00139 box_marker.color.g = 0.5
00140 box_marker.color.b = 0.5
00141 box_marker.color.a = 0.5
00142
00143
00144 box_control = InteractiveMarkerControl()
00145 box_control.always_visible = True
00146 box_control.markers.append( box_marker )
00147
00148
00149 int_marker.controls.append( box_control )
00150
00151 control = InteractiveMarkerControl()
00152 control.orientation.w = 1
00153 control.orientation.x = 1
00154 control.orientation.y = 0
00155 control.orientation.z = 0
00156 control.name = "rotate_x"
00157 control.interaction_mode = InteractiveMarkerControl.ROTATE_AXIS
00158 int_marker.controls.append(control)
00159
00160 control = InteractiveMarkerControl()
00161 control.orientation.w = 1
00162 control.orientation.x = 1
00163 control.orientation.y = 0
00164 control.orientation.z = 0
00165 control.name = "move_x"
00166 control.interaction_mode = InteractiveMarkerControl.MOVE_AXIS
00167 int_marker.controls.append(control)
00168
00169 control = InteractiveMarkerControl()
00170 control.orientation.w = 1
00171 control.orientation.x = 0
00172 control.orientation.y = 1
00173 control.orientation.z = 0
00174 control.name = "rotate_z"
00175 control.interaction_mode = InteractiveMarkerControl.ROTATE_AXIS
00176 int_marker.controls.append(control)
00177
00178 control = InteractiveMarkerControl()
00179 control.orientation.w = 1
00180 control.orientation.x = 0
00181 control.orientation.y = 1
00182 control.orientation.z = 0
00183 control.name = "move_z"
00184 control.interaction_mode = InteractiveMarkerControl.MOVE_AXIS
00185 int_marker.controls.append(control)
00186
00187 control = InteractiveMarkerControl()
00188 control.orientation.w = 1
00189 control.orientation.x = 0
00190 control.orientation.y = 0
00191 control.orientation.z = 1
00192 control.name = "rotate_y"
00193 control.interaction_mode = InteractiveMarkerControl.ROTATE_AXIS
00194 int_marker.controls.append(control)
00195
00196 control = InteractiveMarkerControl()
00197 control.orientation.w = 1
00198 control.orientation.x = 0
00199 control.orientation.y = 0
00200 control.orientation.z = 1
00201 control.name = "move_y"
00202 control.interaction_mode = InteractiveMarkerControl.MOVE_AXIS
00203 int_marker.controls.append(control)
00204
00205
00206 control = InteractiveMarkerControl()
00207 control.interaction_mode = InteractiveMarkerControl.MENU
00208 control.description="Right"
00209 control.name = "menu_only_control"
00210 int_marker.controls.append(copy.deepcopy(control))
00211
00212 int_marker.scale=0.2
00213
00214
00215
00216 server.insert(int_marker, processFeedback)
00217
00218 menu_handler.apply( server, int_marker.name )
00219
00220
00221 server.applyChanges()
00222
00223 rospy.spin()