$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2009, 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 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of the Willow Garage nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 00034 00035 import roslib; roslib.load_manifest('pr2_plugs_actions') 00036 import rospy 00037 import PyKDL 00038 import actionlib 00039 from pr2_common_action_msgs.msg import * 00040 from pr2_plugs_msgs.msg import * 00041 from pr2_controllers_msgs.msg import * 00042 from pr2_arm_move_ik.tools import * 00043 from tf_conversions.posemath import fromMsg, toMsg 00044 from actionlib_msgs.msg import * 00045 import geometry_msgs.msg 00046 from math import pi 00047 import math 00048 from pr2_plugs_actions.tf_util import TFUtil 00049 00050 def drange(start, stop, step): 00051 r = start 00052 if start < stop: 00053 while r < stop: 00054 yield r 00055 r += step 00056 if start > stop: 00057 while r > stop: 00058 yield r 00059 r -= step 00060 00061 00062 def outlet_to_plug_error(goal): 00063 time = rospy.Time.now() 00064 try: 00065 pose_base_gripper = fromMsg(TFUtil.wait_and_lookup("base_link","r_gripper_tool_frame", time).pose) 00066 except rospy.ServiceException, e: 00067 rospy.logerr('Could not transform between gripper and wrist at time %f' %time.to_sec()) 00068 server.set_aborted() 00069 return 00070 outlet_to_plug = fromMsg(goal.base_to_outlet).Inverse() * pose_base_gripper * fromMsg(goal.gripper_to_plug) 00071 return outlet_to_plug 00072 00073 00074 def execute_cb(goal): 00075 rospy.loginfo("Action server received goal") 00076 preempt_timeout = rospy.Duration(10.0) 00077 cart_space_goal.ik_seed = get_action_seed('pr2_plugs_configuration/approach_outlet_seed') 00078 try: 00079 pose_gripper_wrist= fromMsg(TFUtil.wait_and_lookup("r_gripper_tool_frame", "r_wrist_roll_link").pose) 00080 except rospy.ServiceException, e: 00081 rospy.logerr('Could not transform between gripper and wrist at time %f' %time.to_sec()) 00082 server.set_aborted() 00083 return 00084 00085 pose_base_outlet = fromMsg(goal.base_to_outlet) 00086 pose_plug_gripper = fromMsg(goal.gripper_to_plug).Inverse() 00087 00088 rate = rospy.Rate(100.0) 00089 current_error = outlet_to_plug_error(goal) 00090 forward_start = current_error.p[0] 00091 if goal.insert == 1: 00092 forward_stop = current_error.p[0] + 0.02 00093 forward_step = 0.0005 00094 else: 00095 forward_stop = current_error.p[0] - 0.04 00096 forward_step = 0.001 00097 00098 wiggle = 1.0 00099 wiggle_count = 1 00100 for offset in drange(forward_start, forward_stop, forward_step): 00101 pose_outlet_plug = PyKDL.Frame(PyKDL.Rotation.RPY(0, math.pi/30*wiggle, 0), PyKDL.Vector(offset, 0, 0)) 00102 cart_space_goal.pose.pose = toMsg(pose_base_outlet * pose_outlet_plug * pose_plug_gripper * pose_gripper_wrist) 00103 cart_space_goal.pose.header.stamp = rospy.Time.now() 00104 cart_space_goal.pose.header.frame_id = 'base_link' 00105 cart_space_goal.move_duration = rospy.Duration(0.0) 00106 00107 result_state = cart_space_client.send_goal_and_wait(cart_space_goal, rospy.Duration(20.0), preempt_timeout) 00108 00109 if goal.insert != 1 and wiggle_count % 5 == 0 and result_state == GoalStatus.SUCCEEDED: 00110 server.set_succeeded(WigglePlugResult()) 00111 return 00112 00113 wiggle = wiggle * -1 00114 wiggle_count += 1 00115 00116 00117 pose_outlet_plug = PyKDL.Frame(PyKDL.Vector(offset, 0, 0)) 00118 cart_space_goal.pose.pose = toMsg(pose_base_outlet * pose_outlet_plug * pose_plug_gripper * pose_gripper_wrist) 00119 cart_space_goal.pose.header.stamp = rospy.Time.now() 00120 cart_space_goal.pose.header.frame_id = 'base_link' 00121 cart_space_goal.move_duration = rospy.Duration(0.5) 00122 cart_space_client.send_goal_and_wait(cart_space_goal, rospy.Duration(20.0), preempt_timeout) 00123 rate.sleep() 00124 00125 result = WigglePlugResult() 00126 server.set_succeeded(result) 00127 00128 00129 if __name__ == '__main__': 00130 #Initialize the node 00131 name = 'wiggle_plug' 00132 rospy.init_node(name) 00133 00134 # transform listener 00135 TFUtil() 00136 00137 # create action clients we use 00138 cart_space_client = actionlib.SimpleActionClient('r_arm_ik', ArmMoveIKAction) 00139 cart_space_client.wait_for_server() 00140 cart_space_goal = ArmMoveIKGoal() 00141 rospy.loginfo('Connected to action clients') 00142 00143 # create action server 00144 server = actionlib.simple_action_server.SimpleActionServer(name, WigglePlugAction, execute_cb) 00145 rospy.loginfo('%s: Action server running', name) 00146 00147 00148 rospy.spin()