00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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 joint_trajectory_action_tools.tools import *
00043 from pr2_arm_move_ik.tools import *
00044 from tf_conversions.posemath import fromMsg, toMsg
00045 from actionlib_msgs.msg import *
00046 import geometry_msgs.msg
00047 from trajectory_msgs.msg import JointTrajectoryPoint
00048 from math import pi
00049 from pr2_plugs_actions.tf_util import TFUtil
00050
00051
00052
00053
00054 def execute_cb(goal):
00055 rospy.loginfo("Action server received goal")
00056 preempt_timeout = rospy.Duration(5.0)
00057
00058
00059 rospy.loginfo("Moving up spine...")
00060 spine_goal.position = 0.16
00061 if spine_client.send_goal_and_wait(spine_goal, rospy.Duration(20.0), preempt_timeout) != GoalStatus.SUCCEEDED:
00062 rospy.logerr('Moving up spine failed')
00063 server.set_aborted()
00064 return
00065
00066
00067
00068 error = 1.0
00069 free_cord = False
00070 while error > 0.01 and not rospy.is_shutdown():
00071
00072 if free_cord:
00073 rospy.loginfo("Free plug cord by doing approach...")
00074 if joint_space_client.send_goal_and_wait(get_action_goal('pr2_plugs_configuration/free_plug_cord'), rospy.Duration(20.0), preempt_timeout) != GoalStatus.SUCCEEDED:
00075 rospy.logerr('Free plug cord failed')
00076 server.set_aborted()
00077 return
00078 free_cord = True
00079
00080
00081 rospy.loginfo("Move in joint space...")
00082 if joint_space_client.send_goal_and_wait(get_action_goal('pr2_plugs_configuration/stow_plug'), rospy.Duration(20.0), preempt_timeout) != GoalStatus.SUCCEEDED:
00083 rospy.logerr('Move approach in joint space failed')
00084 server.set_aborted()
00085 return
00086
00087
00088 cart_space_goal.ik_seed = get_action_seed('pr2_plugs_configuration/return_plug_seed')
00089 pose_plug_gripper = fromMsg(goal.gripper_to_plug_grasp).Inverse()
00090 pose_base_plug = fromMsg(goal.base_to_plug)
00091 pose_gripper_wrist = fromMsg(TFUtil.wait_and_lookup('r_gripper_tool_frame', 'r_wrist_roll_link').pose)
00092 cart_space_goal.pose.pose = toMsg(pose_base_plug * pose_plug_gripper * pose_gripper_wrist)
00093 cart_space_goal.pose.header.stamp = rospy.Time.now()
00094 cart_space_goal.pose.header.frame_id = "base_link"
00095 cart_space_goal.move_duration = rospy.Duration(3.0)
00096 if cart_space_client.send_goal_and_wait(cart_space_goal, rospy.Duration(20.0), preempt_timeout) != GoalStatus.SUCCEEDED:
00097 rospy.logerr('Failed to return plug to location where the plug was found when fetching it.')
00098 server.set_aborted()
00099 return
00100
00101
00102 pose_base_gripper_measured = fromMsg(TFUtil.wait_and_lookup('base_link', 'r_gripper_tool_frame', rospy.Time.now()).pose)
00103 pose_base_gripper_desired = pose_base_plug * pose_plug_gripper
00104 diff = pose_base_gripper_measured.Inverse() * pose_base_gripper_desired
00105 error = diff.p.Norm()
00106 (r, p, y) = diff.M.GetRPY()
00107 error += (r + p + y)/10.0
00108 rospy.loginfo("Diff between desired and actual plug storing poses = %f"%error)
00109
00110
00111 rospy.loginfo("Open gripper...")
00112 gripper_goal.command.position = 0.07
00113 gripper_goal.command.max_effort = 99999
00114 if gripper_client.send_goal_and_wait(gripper_goal, rospy.Duration(20.0), preempt_timeout) != GoalStatus.SUCCEEDED:
00115 rospy.logerr('Open gripper failed')
00116 server.set_aborted()
00117 return
00118
00119
00120 rospy.loginfo("Releasing plug...")
00121 pose_plug_approach = PyKDL.Frame(PyKDL.Vector(0, 0.05, 0))
00122 cart_space_goal.pose.pose = toMsg(pose_base_plug * pose_plug_approach * pose_plug_gripper * pose_gripper_wrist)
00123 cart_space_goal.pose.header.stamp = rospy.Time.now()
00124 cart_space_goal.pose.header.frame_id = "base_link"
00125 cart_space_goal.move_duration = rospy.Duration(3.0)
00126 if cart_space_client.send_goal_and_wait(cart_space_goal, rospy.Duration(20.0), preempt_timeout) != GoalStatus.SUCCEEDED:
00127 rospy.logerr('Failed to move arm away from where the plug got released')
00128 server.set_aborted()
00129 return
00130
00131
00132 rospy.loginfo("Detect plug on base...")
00133 start_time = rospy.Time.now()
00134 while detect_plug_on_base_client.send_goal_and_wait(DetectPlugOnBaseGoal(), rospy.Duration(120.0), preempt_timeout) != GoalStatus.SUCCEEDED:
00135 if rospy.Time.now() > start_time + rospy.Duration(60):
00136 rospy.logerr("Can't detect plug on base. It is soo dark in here... Giving up, driving away, living on the edge! But let's take an image to make sure.")
00137 detect_plug_on_base_client.send_goal_and_wait(DetectPlugOnBaseGoal(record_image=True), rospy.Duration(120.0), preempt_timeout)
00138 break
00139 rospy.logerr('Detecting plug on base failed, trying again...')
00140
00141
00142 rospy.loginfo("Moving down spine...")
00143 spine_goal.position = 0.01
00144 spine_client.send_goal(spine_goal)
00145
00146
00147 server.set_succeeded(StowPlugResult())
00148 rospy.loginfo("Action server goal finished")
00149
00150
00151 if __name__ == '__main__':
00152
00153 name = 'stow_plug'
00154 rospy.init_node(name)
00155
00156
00157 TFUtil()
00158
00159
00160 gripper_client = actionlib.SimpleActionClient('r_gripper_controller/gripper_action', Pr2GripperCommandAction)
00161 gripper_client.wait_for_server()
00162 gripper_goal = Pr2GripperCommandGoal()
00163
00164 joint_space_client = actionlib.SimpleActionClient('r_arm_controller/joint_trajectory_generator', JointTrajectoryAction)
00165 joint_space_client.wait_for_server()
00166 joint_space_goal = JointTrajectoryGoal()
00167
00168 cart_space_client = actionlib.SimpleActionClient('r_arm_ik', ArmMoveIKAction)
00169 cart_space_client.wait_for_server()
00170 cart_space_goal = ArmMoveIKGoal()
00171
00172 spine_client = actionlib.SimpleActionClient('torso_controller/position_joint_action', SingleJointPositionAction)
00173 spine_client.wait_for_server()
00174 spine_goal = SingleJointPositionGoal()
00175
00176 detect_plug_on_base_client = actionlib.SimpleActionClient('detect_plug_on_base', DetectPlugOnBaseAction)
00177 detect_plug_on_base_client.wait_for_server()
00178 rospy.loginfo('Connected to action clients')
00179
00180
00181 server = actionlib.simple_action_server.SimpleActionServer(name, StowPlugAction, execute_cb)
00182 rospy.loginfo('%s: Action server running', name)
00183
00184
00185 rospy.spin()