00001
00002
00003 import roslib
00004 roslib.load_manifest('pr2_plugs_actions')
00005
00006 import rospy
00007
00008 import os,sys,time
00009 import math
00010 import PyKDL
00011
00012 from actionlib_msgs.msg import *
00013 from pr2_common_action_msgs.msg import *
00014 from pr2_plugs_msgs.msg import *
00015 from pr2_controllers_msgs.msg import *
00016 from geometry_msgs.msg import *
00017 from trajectory_msgs.msg import *
00018 from move_base_msgs.msg import *
00019 from sensor_msgs.msg import *
00020
00021 from pr2_arm_move_ik.tools import *
00022 from tf_conversions.posemath import fromMsg, toMsg
00023 from joint_trajectory_action_tools.tools import get_action_goal as get_generator_goal
00024
00025
00026 import smach
00027 from smach import *
00028 from smach_ros import *
00029 from pr2_plugs_actions.tf_util import TFUtil
00030
00031 import actionlib
00032
00033 def drange(start, stop, step):
00034 r = start
00035 while r < stop:
00036 yield r
00037 r += step
00038
00039 def get_outlet_to_plug(pose_base_outlet, pose_plug_gripper):
00040 """Get the pose from the outlet to the plug."""
00041 pose_base_gripper = fromMsg(TFUtil.wait_and_lookup("base_link","r_gripper_tool_frame",
00042 rospy.Time.now(), rospy.Duration(2.0)).pose)
00043
00044 outlet_to_plug = pose_base_outlet.Inverse() * pose_base_gripper * pose_plug_gripper.Inverse()
00045
00046 return outlet_to_plug
00047
00048 @smach.cb_interface(input_keys=['base_to_outlet','gripper_to_plug'])
00049 def get_outlet_to_plug_ik_goal(ud, pose):
00050 """Get an IK goal for a pose in the frame of the outlet"""
00051 pose_gripper_wrist = fromMsg(TFUtil.wait_and_lookup("r_gripper_tool_frame", "r_wrist_roll_link",
00052 rospy.Time.now(), rospy.Duration(2.0)).pose)
00053
00054 goal = ArmMoveIKGoal()
00055 goal.ik_seed = get_action_seed('pr2_plugs_configuration/approach_outlet_seed')
00056 goal.pose.pose = toMsg(fromMsg(ud.base_to_outlet) * pose * fromMsg(ud.gripper_to_plug).Inverse() * pose_gripper_wrist)
00057 goal.pose.header.stamp = rospy.Time.now()
00058 goal.pose.header.frame_id = 'base_link'
00059
00060 return goal
00061
00062 @smach.cb_interface(input_keys=['gripper_to_plug','base_to_outlet'])
00063 def get_wiggle_goal(ud,goal):
00064 goal = WigglePlugGoal()
00065 goal.gripper_to_plug = ud.gripper_to_plug
00066 goal.base_to_outlet = ud.base_to_outlet
00067 goal.wiggle_period = rospy.Duration(0.5)
00068 goal.insert = 1
00069 return goal
00070
00071 def construct_sm():
00072 TFUtil()
00073
00074
00075 sm = StateMachine(
00076 ['succeeded','aborted','preempted'],
00077 input_keys = ['base_to_outlet'],
00078 output_keys = ['gripper_to_plug'])
00079
00080
00081 with sm:
00082
00083
00084 @smach.cb_interface(output_keys=['gripper_to_plug'])
00085 def store_detect_plug_result(ud, result_state, result):
00086 if result_state == GoalStatus.SUCCEEDED:
00087 ud.gripper_to_plug = TFUtil.wait_and_transform('r_gripper_tool_frame',result.plug_pose).pose
00088 print 'gripper_to_plug'
00089 print TFUtil.wait_and_transform('r_gripper_tool_frame',result.plug_pose).pose
00090
00091 StateMachine.add('DETECT_PLUG_IN_GRIPPER',
00092 SimpleActionState('detect_plug',
00093 DetectPlugInGripperAction,
00094 goal = DetectPlugInGripperGoal(),
00095 result_cb = store_detect_plug_result),
00096 {'succeeded':'LOWER_SPINE'})
00097
00098 StateMachine.add('LOWER_SPINE',
00099 SimpleActionState('torso_controller/position_joint_action', SingleJointPositionAction,
00100 goal = SingleJointPositionGoal(position=0.01)),
00101 {'succeeded':'APPROACH_OUTLET_ITER'})
00102
00103
00104 approach_it = Iterator(
00105 ['succeeded','preempted','aborted'],
00106 input_keys = ['base_to_outlet','gripper_to_plug'],
00107 output_keys = ['outlet_to_plug_contact'],
00108 it = lambda: drange(-0.07, 0.09, 0.005),
00109 it_label = 'approach_offset',
00110 exhausted_outcome = 'aborted')
00111 StateMachine.add('APPROACH_OUTLET_ITER',approach_it,
00112 {'succeeded':'TWIST_PLUG_ITER',
00113 'aborted':'FAIL_PULL_BACK_FROM_WALL'})
00114 with approach_it:
00115 approach_sm = StateMachine(
00116 ['succeeded','preempted','aborted','keep_moving'],
00117 input_keys=['base_to_outlet','approach_offset','gripper_to_plug'],
00118 output_keys=['outlet_to_plug_contact'])
00119 Iterator.set_contained_state('APPROACH',approach_sm,
00120 loop_outcomes=['keep_moving'])
00121
00122 with approach_sm:
00123 @smach.cb_interface(
00124 input_keys=['base_to_outlet','approach_offset','gripper_to_plug'])
00125 def get_move_closer_goal(ud, goal):
00126 """Generate an ik goal to move along the local x axis of the outlet."""
00127
00128 pose_outlet_plug = PyKDL.Frame(PyKDL.Vector(ud.approach_offset, 0, 0))
00129 pose_gripper_wrist = fromMsg(TFUtil.wait_and_lookup('r_gripper_tool_frame', 'r_wrist_roll_link').pose)
00130 base_to_outlet = fromMsg(ud.base_to_outlet)
00131 gripper_to_plug = fromMsg(ud.gripper_to_plug)
00132
00133 pose_base_wrist = base_to_outlet * pose_outlet_plug * gripper_to_plug.Inverse() * pose_gripper_wrist
00134
00135 goal = ArmMoveIKGoal()
00136 goal.pose.pose = toMsg(pose_base_wrist)
00137 goal.pose.header.stamp = rospy.Time.now()
00138 goal.pose.header.frame_id = 'base_link'
00139 goal.ik_seed = get_action_seed('pr2_plugs_configuration/approach_outlet_seed')
00140 goal.move_duration = rospy.Duration(1.0)
00141 return goal
00142
00143 StateMachine.add('MOVE_CLOSER',
00144 SimpleActionState('r_arm_ik', ArmMoveIKAction, goal_cb = get_move_closer_goal),
00145 {'succeeded':'CHECK_FOR_CONTACT','aborted':'CHECK_FOR_CONTACT'})
00146
00147 @smach.cb_interface(
00148 input_keys=['base_to_outlet','approach_offset','gripper_to_plug'],
00149 output_keys=['outlet_to_plug_contact'])
00150 def plug_in_contact(ud):
00151 """Returns true if the plug is in contact with something."""
00152
00153 pose_base_gripper = fromMsg(TFUtil.wait_and_lookup('base_link', 'r_gripper_tool_frame').pose)
00154 pose_outlet_plug = fromMsg(ud.base_to_outlet).Inverse() * pose_base_gripper * fromMsg(ud.gripper_to_plug)
00155
00156
00157 ud.outlet_to_plug_contact = toMsg(pose_outlet_plug)
00158 if math.fabs(pose_outlet_plug.p[0] - ud.approach_offset) > 0.01:
00159 return True
00160 return False
00161
00162 StateMachine.add('CHECK_FOR_CONTACT',
00163 ConditionState(cond_cb = plug_in_contact),
00164 {'true':'succeeded','false':'keep_moving'})
00165
00166
00167
00168 twist_it = Iterator(
00169 ['succeeded','preempted','aborted'],
00170 input_keys = ['base_to_outlet','gripper_to_plug','outlet_to_plug_contact'],
00171 it = lambda: drange(0.0, 0.25, 0.025),
00172 output_keys = [],
00173 it_label = 'twist_angle',
00174 exhausted_outcome = 'aborted')
00175 with twist_it:
00176 twist_sm = StateMachine(
00177 ['succeeded','preempted','aborted','keep_moving'],
00178 input_keys = ['base_to_outlet','gripper_to_plug','twist_angle', 'outlet_to_plug_contact'])
00179 with twist_sm:
00180 @smach.cb_interface(
00181 input_keys=['base_to_outlet','gripper_to_plug','twist_angle', 'outlet_to_plug_contact'])
00182 def get_twist_goal(ud, goal):
00183 """Generate an ik goal to rotate the plug"""
00184 pose_contact_plug = PyKDL.Frame(PyKDL.Rotation.RPY(ud.twist_angle, 0, 0))
00185 pose_gripper_wrist = fromMsg(TFUtil.wait_and_lookup('r_gripper_tool_frame', 'r_wrist_roll_link').pose)
00186
00187 pose_base_wrist = fromMsg(ud.base_to_outlet) * fromMsg(ud.outlet_to_plug_contact) * pose_contact_plug * fromMsg(ud.gripper_to_plug).Inverse() * pose_gripper_wrist
00188
00189 goal = ArmMoveIKGoal()
00190 goal.pose.pose = toMsg(pose_base_wrist)
00191 goal.pose.header.stamp = rospy.Time.now()
00192 goal.pose.header.frame_id = 'base_link'
00193 goal.ik_seed = get_action_seed('pr2_plugs_configuration/approach_outlet_seed')
00194 goal.move_duration = rospy.Duration(1.0)
00195 return goal
00196
00197 StateMachine.add('TWIST_PLUG',
00198 SimpleActionState('r_arm_ik', ArmMoveIKAction, goal_cb = get_twist_goal),
00199 {'succeeded':'CHECK_PLUG_IN_SOCKET','aborted':'CHECK_PLUG_IN_SOCKET'})
00200
00201
00202 @smach.cb_interface(input_keys=['roll_effort'],output_keys=['roll_effort'])
00203 def plug_in_socket(ud):
00204 """Determine if the plug is in the socket yet"""
00205
00206 MIN_EFFORT = 1.0
00207 ud.roll_effort = None
00208
00209
00210 def joint_states_cb(msg, ud):
00211 ud.roll_effort = dict(zip(msg.name, msg.effort))['r_wrist_roll_joint']
00212
00213
00214 joint_sub = rospy.Subscriber("joint_states", JointState, joint_states_cb, ud)
00215
00216
00217 while ud.roll_effort is None:
00218 rospy.sleep(0.05)
00219
00220 joint_sub.unregister()
00221
00222 if ud.roll_effort > MIN_EFFORT:
00223 return True
00224
00225 return False
00226
00227 StateMachine.add('CHECK_PLUG_IN_SOCKET',
00228 ConditionState(cond_cb = plug_in_socket),
00229 {'true':'succeeded','false':'keep_moving'})
00230
00231 Iterator.set_contained_state('TWIST',
00232 twist_sm,
00233 loop_outcomes=['keep_moving'])
00234
00235 StateMachine.add('TWIST_PLUG_ITER',twist_it,
00236 {'succeeded':'STRAIGHTEN_PLUG',
00237 'aborted':'FAIL_PULL_BACK_FROM_WALL'})
00238
00239 @smach.cb_interface(input_keys=['base_to_outlet','outlet_to_plug_contact','gripper_to_plug'])
00240 def get_straighten_goal(ud, goal):
00241 """Generate an ik goal to straighten the plug in the outlet."""
00242 pose_gripper_wrist = fromMsg(TFUtil.wait_and_lookup('r_gripper_tool_frame', 'r_wrist_roll_link').pose)
00243
00244 pose_base_wrist = fromMsg(ud.base_to_outlet) * fromMsg(ud.outlet_to_plug_contact) * fromMsg(ud.gripper_to_plug).Inverse() * pose_gripper_wrist
00245
00246 goal = ArmMoveIKGoal()
00247 goal.pose.pose = toMsg(pose_base_wrist)
00248 goal.pose.header.stamp = rospy.Time.now()
00249 goal.pose.header.frame_id = 'base_link'
00250 goal.ik_seed = get_action_seed('pr2_plugs_configuration/approach_outlet_seed')
00251 goal.move_duration = rospy.Duration(0.5)
00252 return goal
00253
00254 StateMachine.add('STRAIGHTEN_PLUG',
00255 SimpleActionState('r_arm_ik', ArmMoveIKAction, goal_cb = get_straighten_goal),
00256 {'succeeded':'WIGGLE_IN',
00257 'aborted':'FAIL_PULL_BACK_FROM_WALL'})
00258
00259
00260 StateMachine.add('WIGGLE_IN',
00261 SimpleActionState('wiggle_plug',
00262 WigglePlugAction,
00263 goal_cb = get_wiggle_goal),
00264 {'succeeded':'succeeded',
00265 'aborted':'FAIL_PULL_BACK_FROM_WALL'})
00266
00267
00268 @smach.cb_interface(input_keys=['base_to_outlet','gripper_to_plug'])
00269 def get_pull_back_goal(ud, goal):
00270 """Generate an ik goal to move along the local x axis of the outlet."""
00271 pose_outlet_plug = PyKDL.Frame(PyKDL.Vector(-0.10, 0, 0))
00272 pose_gripper_wrist = fromMsg(TFUtil.wait_and_lookup('r_gripper_tool_frame', 'r_wrist_roll_link').pose)
00273
00274 pose_base_wrist = fromMsg(ud.base_to_outlet) * pose_outlet_plug * fromMsg(ud.gripper_to_plug).Inverse() * pose_gripper_wrist
00275
00276 goal = ArmMoveIKGoal()
00277 goal.pose.pose = toMsg(pose_base_wrist)
00278 goal.pose.header.stamp = rospy.Time.now()
00279 goal.pose.header.frame_id = 'base_link'
00280 goal.ik_seed = get_action_seed('pr2_plugs_configuration/approach_outlet_seed')
00281 goal.move_duration = rospy.Duration(3.0)
00282 return goal
00283
00284 StateMachine.add('FAIL_PULL_BACK_FROM_WALL',
00285 SimpleActionState('r_arm_ik', ArmMoveIKAction, goal_cb = get_pull_back_goal),
00286 {'succeeded':'aborted',
00287 'aborted':'FAIL_PULL_BACK_FROM_WALL'})
00288 return sm
00289
00290
00291 if __name__ == "__main__":
00292 rospy.init_node("plug_in")
00293 TFUtil()
00294
00295 sm_plug_in = construct_sm()
00296
00297
00298 intro_server = IntrospectionServer('plug_in',sm_plug_in,'/RECHARGE/PLUG_IN')
00299 intro_server.start()
00300
00301
00302 asw = ActionServerWrapper(
00303 'plug_in', PlugInAction, sm_plug_in,
00304 succeeded_outcomes = ['succeeded'],
00305 aborted_outcomes = ['aborted'],
00306 preempted_outcomes = ['preempted'],
00307 expand_goal_slots = True,
00308 pack_result_slots = True)
00309 asw.run_server()
00310
00311 rospy.spin()
00312
00313 intro_server.stop()