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
00036
00037
00038
00039
00040 from __future__ import division
00041 import roslib; roslib.load_manifest('pr2_gripper_reactive_approach')
00042 import rospy
00043 import pr2_gripper_reactive_approach.reactive_grasp as reactive_grasp
00044 import pr2_gripper_reactive_approach.controller_manager as controller_manager
00045 import sys
00046 import math
00047 from object_manipulation_msgs.msg import ReactiveGraspAction, ReactiveGraspResult, \
00048 ManipulationResult, GripperTranslation, ReactiveLiftAction, ReactiveLiftResult, \
00049 ReactivePlaceAction, ReactivePlaceResult, ReactiveGraspFeedback, \
00050 ReactiveLiftFeedback, ReactivePlaceFeedback, ManipulationPhase
00051 from object_manipulator.convert_functions import *
00052 from std_srvs.srv import Empty, EmptyResponse
00053 import actionlib
00054 import pdb
00055 import time
00056
00057
00058 class Preempted(Exception): pass
00059
00060
00061 class ReactiveGrasperWithPreempt(reactive_grasp.ReactiveGrasper):
00062
00063 def __init__(self, cm, rg_as, lift_as, approach_as, place_as):
00064
00065 reactive_grasp.ReactiveGrasper.__init__(self, cm)
00066
00067
00068 self._rg_as = rg_as
00069 self._lift_as = lift_as
00070 self._approach_as = approach_as
00071 self._place_as = place_as
00072
00073 self.rg_state = "off"
00074
00075 self.pause_for_recording = 0
00076
00077
00078
00079 def check_preempt(self):
00080
00081 if self.rg_state == "rg" and self._rg_as.is_preempt_requested() or \
00082 self.rg_state == "lift" and self._lift_as.is_preempt_requested() or \
00083 self.rg_state == "approach" and self._approach_as.is_preempt_requested() or \
00084 self.rg_state == "place" and self._place_as.is_preempt_requested():
00085
00086 rospy.loginfo("preempt seen, state=%s"%self.rg_state)
00087
00088
00089 rospy.loginfo("switching back to joint controllers")
00090 self.cm.switch_to_joint_mode()
00091
00092 raise Preempted
00093
00094
00095 def broadcast_phase(self, phase, send_feedback = 1):
00096 self._phase_pub.publish(phase)
00097
00098 if self.rg_state == "rg":
00099 feedback = ReactiveGraspFeedback()
00100 feedback.manipulation_phase.phase = phase
00101 self._rg_as.publish_feedback(feedback)
00102 elif self.rg_state == "lift":
00103 feedback = ReactiveLiftFeedback()
00104 feedback.manipulation_phase.phase = phase
00105 self._lift_as.publish_feedback(feedback)
00106 elif self.rg_state == "place":
00107 feedback = ReactivePlaceFeedback()
00108 feedback.manipulation_phase.phase = phase
00109 self._place_as.publish_feedback(feedback)
00110
00111
00112
00113 if self.pause_for_recording and (phase == ManipulationPhase.MOVING_TO_GRASP \
00114 or phase == ManipulationPhase.PLACING):
00115 time.sleep(3)
00116
00117
00118
00119
00120 class ReactiveGraspActionServer(object):
00121 _grasp_result = ReactiveGraspResult()
00122 _lift_result = ReactiveLiftResult()
00123 _place_result = ReactivePlaceResult()
00124
00125 def __init__(self, which_arm):
00126 self.which_arm = which_arm
00127
00128 self._node_name = which_arm+'_reactive_grasp'
00129 if which_arm == 'r':
00130 self._action_name = 'reactive_grasp/right'
00131 self._lift_action_name = 'reactive_lift/right'
00132 self._approach_action_name = 'reactive_approach/right'
00133 self._place_action_name = 'reactive_place/right'
00134 else:
00135 self._action_name = 'reactive_grasp/left'
00136 self._lift_action_name = 'reactive_lift/left'
00137 self._approach_action_name = 'reactive_approach/left'
00138 self._place_action_name = 'reactive_place/left'
00139
00140
00141 self.side_step = rospy.get_param("~side_step", .015)
00142 self.back_step = rospy.get_param("~back_step", .03)
00143 self.approach_num_tries = rospy.get_param("~approach_num_tries", 5)
00144 self.goal_pos_thres = rospy.get_param("~goal_pos_thres", .01)
00145
00146
00147 self.min_contact_row = rospy.get_param("~min_contact_row", 1)
00148 self.min_gripper_opening = rospy.get_param("~min_gripper_opening", .0021)
00149 self.max_gripper_opening = rospy.get_param("~max_gripper_opening", .1)
00150 self.grasp_adjust_x_step = rospy.get_param("~grasp_adjust_x_step", .02)
00151 self.grasp_adjust_z_step = rospy.get_param("~grasp_adjust_z_step", .015)
00152 self.grasp_adjust_num_tries = rospy.get_param("~grasp_adjust_num_tries", 3)
00153
00154
00155 self.grasp_num_tries = rospy.get_param("~grasp_num_tries", 2)
00156 self.forward_step = rospy.get_param("~forward_step", 0)
00157 self.close_force = rospy.get_param("~close_force", 100)
00158 self.use_slip_controller = rospy.get_param("~use_slip_controller", 0)
00159 self.use_slip_detection = rospy.get_param("~use_slip_detection", 0)
00160
00161
00162 self.place_overshoot = rospy.get_param("~place_overshoot", .01)
00163 rospy.loginfo("place_overshoot:%f"%self.place_overshoot)
00164
00165
00166 self.shake_object = rospy.get_param("~shake_object", 0)
00167
00168 rospy.loginfo("reactive_grasp_server: using_slip_controller:"+str(self.use_slip_controller))
00169 rospy.loginfo("reactive_grasp_server: using_slip_detection:"+str(self.use_slip_detection))
00170
00171
00172 self.pause_for_recording = rospy.get_param("~pause_for_recording", 0)
00173
00174 if self.pause_for_recording:
00175 rospy.loginfo("pausing for recording is turned on")
00176
00177
00178 self._as = actionlib.SimpleActionServer(self._action_name, ReactiveGraspAction, \
00179 execute_cb=self.reactive_grasp_cb)
00180 self._lift_as = actionlib.SimpleActionServer(self._lift_action_name, ReactiveLiftAction, \
00181 execute_cb=self.reactive_lift_cb)
00182 self._approach_as = actionlib.SimpleActionServer(self._approach_action_name, ReactiveGraspAction, \
00183 execute_cb = self.reactive_approach_cb)
00184 self._place_as = actionlib.SimpleActionServer(self._place_action_name, ReactivePlaceAction, \
00185 execute_cb = self.reactive_place_cb)
00186
00187
00188 rospy.Service(self._node_name+'/compliant_close', \
00189 Empty, self.compliant_close_callback)
00190 rospy.Service(self._node_name+'/grasp_adjustment', \
00191 Empty, self.grasp_adjustment_callback)
00192
00193
00194 self.cm = controller_manager.ControllerManager(which_arm, \
00195 using_slip_controller = self.use_slip_controller, \
00196 using_slip_detection = self.use_slip_detection)
00197 self.rg = ReactiveGrasperWithPreempt(self.cm, self._as, self._lift_as, self._approach_as, self._place_as)
00198
00199
00200 self.rg.pause_for_recording = self.pause_for_recording
00201
00202
00203
00204
00205
00206 def reactive_grasp_cb(self, goal):
00207
00208 rospy.loginfo("got reactive grasp request")
00209 try:
00210 self.rg_state = "rg"
00211 (trajectory, object_name, table_name, forward_step) = self.init_reactive_grasp(goal)
00212
00213
00214 self.cm.switch_to_cartesian_mode()
00215 result = self.rg.reactive_grasp(None, goal.final_grasp_pose, trajectory, \
00216 self.side_step, self.back_step, \
00217 self.approach_num_tries, self.goal_pos_thres, \
00218 self.min_gripper_opening, self.max_gripper_opening, \
00219 self.grasp_num_tries, forward_step, self.min_contact_row, \
00220 object_name, table_name, \
00221 self.grasp_adjust_x_step, self.grasp_adjust_z_step, self.grasp_adjust_num_tries)
00222 self.rg.check_preempt()
00223
00224 rospy.loginfo("switching back to joint controllers")
00225 self.cm.switch_to_joint_mode()
00226 self.rg_state = "off"
00227
00228 if result == 0:
00229 self.rg.broadcast_phase(ManipulationPhase.SUCCEEDED, send_feedback = 0)
00230 self._grasp_result.manipulation_result.value = ManipulationResult.SUCCESS
00231 self._as.set_succeeded(self._grasp_result)
00232 else:
00233 self.rg.broadcast_phase(ManipulationPhase.FAILED, send_feedback = 0)
00234 self._grasp_result.manipulation_result.value = ManipulationResult.FAILED
00235 self._as.set_aborted(self._grasp_result)
00236
00237 except Preempted:
00238 rospy.loginfo("reactive grasp preempted, returning")
00239 self.rg.broadcast_phase(ManipulationPhase.ABORTED, send_feedback = 0)
00240 self._grasp_result.manipulation_result.value = ManipulationResult.FAILED
00241 self._as.set_preempted(self._grasp_result)
00242
00243 except reactive_grasp.Aborted:
00244 rospy.loginfo("reactive grasp saw a serious error! Aborting")
00245 self.rg.broadcast_phase(ManipulationPhase.ABORTED, send_feedback = 0)
00246 self._grasp_result.manipulation_result.value = ManipulationResult.ERROR
00247 self._as.set_aborted(self._grasp_result)
00248
00249
00250
00251 def init_reactive_grasp(self, goal):
00252
00253 self.rg.check_preempt()
00254
00255 self.rg.pressure_listener.set_thresholds()
00256
00257 self.rg.check_preempt()
00258
00259
00260 self.close_force = rospy.get_param("~close_force", 100)
00261 self.rg.close_force = self.close_force
00262 rospy.loginfo("using a close_force of %d"%self.close_force)
00263
00264
00265 if len(goal.trajectory.points) > 0:
00266 trajectory = [goal.trajectory.points[i].positions for i in range(len(goal.trajectory.points))]
00267 print "trajectory:"
00268 for angles in trajectory:
00269 print pplist(angles)
00270 else:
00271 trajectory = None
00272
00273 object_name = "points"
00274 table_name = goal.collision_support_surface_name
00275
00276
00277
00278 if self.forward_step == 0:
00279 forward_step = .06
00280
00281
00282 bl_pose = change_pose_stamped_frame(self.rg.cm.tf_listener, goal.final_grasp_pose, 'base_link')
00283 palm_mat = pose_to_mat(bl_pose.pose)
00284 if palm_mat[2,0] < -math.cos(math.pi/3):
00285 rospy.loginfo("palm_mat[2,0] = %0.3f, top grasp"%palm_mat[2,0])
00286
00287
00288 forward_step = .03
00289 else:
00290 rospy.loginfo("side grasp")
00291 else:
00292 forward_step = self.forward_step
00293
00294 self.rg.check_preempt()
00295
00296 return (trajectory, object_name, table_name, forward_step)
00297
00298
00299
00300
00301 def reactive_approach_cb(self, goal):
00302
00303 rospy.loginfo("got reactive approach request")
00304 try:
00305 self.rg_state = "approach"
00306 (trajectory, object_name, table_name, forward_step) = self.init_reactive_grasp(goal)
00307
00308
00309 current_wrist_pose = self.rg.cm.get_current_wrist_pose_stamped()
00310 approach_dir = self.rg.compute_approach_dir(current_wrist_pose, goal.final_grasp_pose)
00311
00312
00313 self.cm.switch_to_cartesian_mode()
00314 result = self.rg.reactive_approach(approach_dir, goal.final_grasp_pose, trajectory, \
00315 self.side_step, self.back_step, \
00316 self.approach_num_tries, self.goal_pos_thres)
00317 self.rg_state = "off"
00318 self.rg.check_preempt()
00319
00320 rospy.loginfo("switching back to joint controllers")
00321 self.cm.switch_to_joint_mode()
00322
00323 if result == 0:
00324 self.rg.broadcast_phase(ManipulationPhase.SUCCEEDED, send_feedback = 0)
00325 self._grasp_result.manipulation_result.value = ManipulationResult.SUCCESS
00326 self._approach_as.set_succeeded(self._grasp_result)
00327 else:
00328 self.rg.broadcast_phase(ManipulationPhase.FAILED, send_feedback = 0)
00329 self._grasp_result.manipulation_result.value = ManipulationResult.FAILED
00330 self._approach_as.set_aborted(self._grasp_result)
00331
00332 except Preempted:
00333 rospy.loginfo("reactive grasp preempted, returning")
00334 self.rg.broadcast_phase(ManipulationPhase.ABORTED, send_feedback = 0)
00335 self._grasp_result.manipulation_result.value = ManipulationResult.FAILED
00336 self._approach_as.set_preempted(self._grasp_result)
00337
00338 except reactive_grasp.Aborted:
00339 rospy.loginfo("reactive grasp saw a serious error! Aborting")
00340 self.rg.broadcast_phase(ManipulationPhase.ABORTED, send_feedback = 0)
00341 self._grasp_result.manipulation_result.value = ManipulationResult.ERROR
00342 self._approach_as.set_aborted(self._grasp_result)
00343
00344
00345
00346 def reactive_lift_cb(self, goal):
00347
00348 try:
00349 rospy.loginfo("got reactive lift request")
00350 self.cm.switch_to_cartesian_mode()
00351
00352
00353 self.rg_state = "lift"
00354 success = self.rg.lift_carefully(goal.lift, self.min_gripper_opening, self.max_gripper_opening)
00355
00356
00357 if success and self.shake_object:
00358
00359
00360 success = self.rg.shake_object(None, self.min_gripper_opening,
00361 self.max_gripper_opening,
00362 wrist_roll_shake_time = 1.5,
00363 wrist_flex_shake_time = 1.5,
00364 arm_pan_shake_time = 0.25)
00365
00366
00367
00368
00369
00370
00371
00372
00373
00374 self.rg_state = "off"
00375
00376 rospy.loginfo("switching back to joint controllers")
00377 self.cm.switch_to_joint_mode()
00378
00379 if success:
00380 self.rg.broadcast_phase(ManipulationPhase.SUCCEEDED, send_feedback = 0)
00381 self._lift_result.manipulation_result.value = ManipulationResult.SUCCESS
00382 self._lift_as.set_succeeded(self._lift_result)
00383 else:
00384 self.rg.broadcast_phase(ManipulationPhase.FAILED, send_feedback = 0)
00385 self._lift_result.manipulation_result.value = ManipulationResult.FAILED
00386 self._lift_as.set_aborted(self._lift_result)
00387
00388 except Preempted:
00389 rospy.loginfo("reactive lift preempted, returning")
00390 self.rg.broadcast_phase(ManipulationPhase.ABORTED, send_feedback = 0)
00391 self._lift_result.manipulation_result.value = ManipulationResult.FAILED
00392 self._lift_as.set_preempted(self._lift_result)
00393
00394 except reactive_grasp.Aborted:
00395 rospy.loginfo("reactive lift saw a serious error! Aborting")
00396 self.rg.broadcast_phase(ManipulationPhase.ABORTED, send_feedback = 0)
00397 self._lift_result.manipulation_result.value = ManipulationResult.ERROR
00398 self._lift_as.set_aborted(self._lift_result)
00399
00400
00401
00402
00403
00404 def reactive_place_cb(self, goal):
00405
00406 try:
00407 rospy.loginfo("got reactive place request")
00408 self.cm.switch_to_cartesian_mode()
00409
00410
00411 self.rg_state = "place"
00412 result = self.rg.place_carefully(goal.final_place_pose, self.place_overshoot, \
00413 self.min_gripper_opening, self.max_gripper_opening)
00414
00415 self._place_result.manipulation_result.value = ManipulationResult.SUCCESS
00416 if result == 1:
00417 self.rg.broadcast_phase(ManipulationPhase.SUCCEEDED, send_feedback = 0)
00418 self._place_as.set_succeeded(self._place_result)
00419
00420 except Preempted:
00421 rospy.loginfo("reactive place preempted, returning")
00422 self.rg.broadcast_phase(ManipulationPhase.ABORTED, send_feedback = 0)
00423 self._place_result.manipulation_result.value = ManipulationResult.FAILED
00424 self._place_as.set_preempted(self._place_result)
00425
00426 except reactive_grasp.Aborted:
00427 rospy.loginfo("reactive place saw a serious error! Aborting")
00428 self.rg.broadcast_phase(ManipulationPhase.ABORTED, send_feedback = 0)
00429 self._place_result.manipulation_result.value = ManipulationResult.ERROR
00430 self._place_as.set_aborted(self._place_result)
00431
00432
00433
00434
00435 def compliant_close_callback(self, req):
00436 rospy.loginfo("executing compliant grasp--switching to Cartesian controllers")
00437 self.cm.switch_to_cartesian_mode()
00438
00439 self.rg.compliant_close()
00440
00441 rospy.loginfo("switching back to joint controllers")
00442 self.cm.switch_to_joint_mode()
00443
00444 return EmptyResponse()
00445
00446
00447
00448
00449 def grasp_adjustment_callback(self, req):
00450 rospy.loginfo("executing grasp adjustment--switching to Cartesian controllers")
00451 self.cm.switch_to_cartesian_mode()
00452
00453
00454
00455 self.rg.open_and_reset_fingertips()
00456 (initial_l_readings, initial_r_readings) = self.rg.compliant_close()
00457
00458
00459 current_wrist_pose = self.cm.get_current_wrist_pose_stamped()
00460
00461
00462 (adjust_result, current_goal_pose) = self.rg.adjust_grasp(current_wrist_pose, \
00463 initial_l_readings, initial_r_readings, \
00464 z_step = self.grasp_adjust_z_step, x_step = self.grasp_adjust_x_step, \
00465 min_gripper_opening = self.min_gripper_opening, \
00466 max_gripper_opening = self.max_gripper_opening, \
00467 min_contact_row = self.min_contact_row,
00468 num_tries = self.grasp_adjust_num_tries)
00469
00470 rospy.loginfo("switching back to joint controllers")
00471 self.cm.switch_to_joint_mode()
00472
00473 return EmptyResponse()
00474
00475
00476 if __name__ == "__main__":
00477
00478 if len(sys.argv) < 2 or sys.argv[1] != 'r' and sys.argv[1] != 'l':
00479 rospy.logerr("usage: reactive_grasp_server.py which_arm (which_arm is r or l)")
00480 sys.exit(1)
00481
00482 which_arm = sys.argv[1]
00483
00484 node_name = which_arm+'_reactive_grasp'
00485 rospy.init_node(node_name, anonymous=True)
00486
00487 reactive_grasp_services = ReactiveGraspActionServer(which_arm)
00488 rospy.loginfo("Reactive grasp action ready")
00489
00490 rospy.spin()