pick_and_place_manager.py
Go to the documentation of this file.
00001 #!/usr/bin/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 # author: Kaijen Hsiao
00035 
00036 ## @package pick_and_place_manager
00037 # Functions to grasp objects off flat tables and place them down in 
00038 # specified rectangular regions in space
00039 
00040 import roslib
00041 roslib.load_manifest('pr2_pick_and_place_demos')
00042 import rospy
00043 from object_manipulation_msgs.msg import PickupAction, PickupGoal, PlaceAction, PlaceGoal, GripperTranslation
00044 from object_manipulation_msgs.srv import FindClusterBoundingBox, FindClusterBoundingBoxRequest
00045 from object_manipulation_msgs.msg import ManipulationResult, GraspableObject
00046 from tabletop_object_detector.srv import TabletopDetection, TabletopDetectionRequest
00047 from tabletop_object_detector.msg import TabletopDetectionResult
00048 from tabletop_collision_map_processing.srv import TabletopCollisionMapProcessing, TabletopCollisionMapProcessingRequest
00049 from pr2_controllers_msgs.msg import PointHeadAction, PointHeadGoal
00050 import tf
00051 import actionlib
00052 import scipy
00053 import time
00054 import copy
00055 import math
00056 import pdb
00057 import threading
00058 import sys
00059 import pr2_gripper_reactive_approach.controller_manager as controller_manager
00060 import tabletop_collision_map_processing.collision_map_interface as collision_map_interface
00061 import pr2_gripper_reactive_approach.reactive_grasp as reactive_grasp
00062 import object_manipulator.draw_functions as draw_functions
00063 from object_manipulator.convert_functions import *
00064 
00065 ##saved info about one object
00066 class ObjectInfo():
00067     def __init__(self, object, box_dims, pose, tf_listener, height_above_table, collision_name):
00068         self.object = object      #the original GraspableObject message
00069         self.box_dims = box_dims  #bounding box dims (only for point clusters)
00070         self.pose = pose          #the original pose on the table when detected (PoseStamped) (of bounding box if point cluster) 
00071         self.grasp = None         #the Grasp object returned by the Pickup service, once the service is called
00072         self.grasp_pose = None    #where it was grasped, once it is grasped
00073         self.grasp_type = 'normal' #whether the grasp was normal ('normal') or a slid-off-table grasp ('flat')
00074         self.collision_name = collision_name  #the name of the object in the collision space
00075 
00076         #for point clusters, record the transform from the cluster origin to the bounding box pose
00077         #(object bounding box to base_link = pose)**-1 * (cluster to base link) = (cluster origin to bounding box)
00078         if self.object.type == GraspableObject.POINT_CLUSTER:
00079             cluster_to_base_link = get_transform(tf_listener, object.cluster.header.frame_id, 'base_link')
00080             pose_mat = pose_to_mat(pose.pose)
00081             self.cluster_origin_to_bounding_box = pose_mat**-1 * cluster_to_base_link #cluster to bounding box transform
00082         else:
00083             self.cluster_origin_to_bounding_box = None
00084 
00085         #save the height of the object above the current table detection
00086         self.height_above_table = height_above_table
00087 
00088 
00089 ##Manager for pick and place actions
00090 class PickAndPlaceManager():
00091 
00092 
00093     def __init__(self, use_slip_detection = 0):
00094 
00095         #should we use the slip detecting gripper controller?
00096         self.use_slip_detection = use_slip_detection
00097 
00098         #grasp/place action names
00099         self.grasper_grasp_name = 'object_manipulator/object_manipulator_pickup'
00100         self.grasper_place_name = 'object_manipulator/object_manipulator_place'
00101 
00102         #grasp/place action clients
00103         self.grasper_grasp_action_client = actionlib.SimpleActionClient(self.grasper_grasp_name, PickupAction)
00104         rospy.loginfo("grasp_executive: waiting for object_manipulator_pickup action")
00105         self.grasper_grasp_action_client.wait_for_server()
00106         rospy.loginfo("grasp_executive: object_manipulator_pickup action found")
00107         self.grasper_place_action_client = actionlib.SimpleActionClient(self.grasper_place_name, PlaceAction)
00108         rospy.loginfo("grasp_executive: waiting for object_manipulator_place action")
00109         self.grasper_place_action_client.wait_for_server()
00110         rospy.loginfo("grasp_executive: object_manipulator_place action found")
00111 
00112         #service names
00113         self.grasper_detect_name = 'object_detection'
00114         self.collision_map_processing_name = '/tabletop_collision_map_processing/tabletop_collision_map_processing'
00115         #self.grasper_transfer_name = '/grasping_app_transfer'
00116         self.find_bounding_box_name = '/find_cluster_bounding_box'
00117 
00118         #head action client
00119         self.head_action_client = "not active right now"#\
00120 #            actionlib.SimpleActionClient('/head_traj_controller/point_head_action', PointHeadAction)
00121 #        rospy.loginfo("grasp_executive: waiting for point_head_action client")
00122 #        self.head_action_client.wait_for_server()
00123 #        rospy.loginfo("grasp_executive: point_head_action client found")
00124         rospy.loginfo("not ever pointing head!!!! I like it where it is")
00125 
00126         #start tf listener
00127         self.tf_listener = tf.TransformListener()
00128 
00129         #initialize controller managers for both arms
00130         rospy.loginfo("initializing controller managers for both arms")
00131         self.cms = [controller_manager.ControllerManager('r', self.tf_listener, use_slip_detection), controller_manager.ControllerManager('l', self.tf_listener, use_slip_detection)]
00132         rospy.loginfo("done initializing controller managers for both arms")
00133 
00134         #wait for services
00135         rospy.loginfo("grasp_executive: waiting for object_detection service")
00136         rospy.wait_for_service(self.grasper_detect_name)
00137         rospy.loginfo("grasp_executive: object_detection service found")
00138 
00139         rospy.loginfo("grasp_executive: waiting for collision_map_processing service")
00140         rospy.wait_for_service(self.collision_map_processing_name)
00141         rospy.loginfo("grasp_executive: collision_map_processing service found")
00142 
00143         #rospy.loginfo("grasp_executive: waiting for grasping_app_transfer service")
00144         #rospy.wait_for_service(grasper_transfer_name)
00145         #rospy.loginfo("grasp_executive: grasper_transfer service found")
00146 
00147         rospy.loginfo("grasp_executive: waiting for find_cluster_bounding_box service")
00148         rospy.wait_for_service(self.find_bounding_box_name)
00149         rospy.loginfo("grasp_executive: find_cluster_bounding_box service found")
00150 
00151         #service proxies
00152         self.grasper_detect_srv = rospy.ServiceProxy(self.grasper_detect_name, TabletopDetection)
00153         self.collision_map_processing_srv = rospy.ServiceProxy(self.collision_map_processing_name, TabletopCollisionMapProcessing)
00154         #self.grasper_transfer_srv = rospy.ServiceProxy(self.grasper_transfer_name, GraspingAppTransfer)
00155         self.bounding_box_srv = rospy.ServiceProxy(self.find_bounding_box_name, FindClusterBoundingBox)
00156 
00157         #initialize a collision map interface
00158         self.collision_map_interface = collision_map_interface.CollisionMapInterface()
00159 
00160         #initialize a DrawFunctions object
00161         self.draw_functions = draw_functions.DrawFunctions('grasp_markers')
00162 
00163         #the objects held in the each arm (None if no object)
00164         self.held_objects = [None]*2
00165 
00166         #original pose of the object in each hand
00167         self.original_poses = [None]*2
00168 
00169         #temporary height and dist until we get a table detection
00170         self.table_front_edge_x = .33
00171         #self.table_height = .685
00172         self.table_height = .885
00173         
00174         #rectangle where we can put objects down (defaults to just in front of the robot, on the table)
00175         self.place_rect_dims = [.3, .6]
00176         place_rect_pose_mat = scipy.matrix([[1.,0.,0.,self.table_front_edge_x+self.place_rect_dims[0]/2.+.1],
00177                                             [0.,1.,0.,0.],
00178                                             [0.,0.,1.,self.table_height],
00179                                             [0.,0.,0.,1.]])
00180         self.place_rect_pose_stamped = stamp_pose(mat_to_pose(place_rect_pose_mat), 'base_link')
00181 
00182         #occupancy grid of places to put down an object
00183         self.place_grid_resolution = 5
00184         self.place_grid = [[0]*self.place_grid_resolution for i in range(self.place_grid_resolution)]
00185 
00186         #saved table and object detections
00187         self.detected_table = None
00188         self.additional_tables = []
00189         self.detected_objects = []
00190 
00191         #dictionary of which arm is which
00192         self.arm_dict = {0:'r', 1:'l'}
00193 
00194         #arm-away joint angles
00195         self.arm_above_and_to_side_angles = [[-0.968, 0.729, -0.554, -1.891, -1.786, -1.127, 0.501],
00196                                         [0.968, 0.729, 0.554, -1.891, 1.786, -1.127, 0.501]]
00197 
00198         self.arm_above_and_out_of_way = [[-0.54, -0.3, -1.4, -1.05, -1.4, -1.85, 0.501],
00199                                         [0.54, -0.3, 1.4, -1.05, 1.4, -1.85, 0.501]]
00200 
00201         self.arm_to_side_angles = [[-2.135, 0.803, -1.732, -1.905, -2.369, -1.680, 1.398],
00202                               [2.135, 0.803, 1.732, -1.905, 2.369, -1.680, 1.398]]
00203 
00204         #dictionary of grasp/place error codes 
00205         #(SUCCESS, UNFEASIBLE, FAILED, ERROR, MOVE_ARM_STUCK, LIFT_FAILED)
00206         self.result_code_dict = {}
00207         for element in dir(ManipulationResult):
00208             if element[0].isupper():
00209                 self.result_code_dict[eval('ManipulationResult.'+element)] = element
00210 
00211         #dictionary of tabletop_object_detector error codes 
00212         #(NO_CLOUD_RECEIVED, NO_TABLE, OTHER_ERROR, SUCCESS)
00213         self.tabletop_detection_result_dict = {}
00214         for element in dir(TabletopDetectionResult):
00215             if element[0].isupper():
00216                 self.tabletop_detection_result_dict[eval('TabletopDetectionResult.'+element)] = element
00217 
00218         #name of the support surface's collision object
00219         self.collision_support_surface_name = "table"
00220 
00221         #offset for place override approach (where to come in from when dropping open-loop in base_link frame; z is separate)
00222         self.place_override_approach_offset = [-.15, 0, 0]
00223 
00224 
00225     ##shift a place pose to be above the current table plane
00226     def shift_place_pose_height(self, object, place_pose, table, z_offset):
00227         
00228         #find the height of the place_pose above the current table
00229         new_height = self.find_height_above_table(place_pose, table)
00230 
00231         #figure out the desired offset to make it the same height as when it was grasped
00232         #plus the desired z_offset
00233         height_diff = object.height_above_table +z_offset - new_height
00234 
00235         #don't move down (which would probably make the desired pose into the actual table)
00236         if height_diff <= 0:
00237             height_diff = 0
00238         
00239         #add that offset to the place_pose plus a tiny offset
00240         place_pose.pose.position.z += height_diff + .001
00241 
00242         rospy.loginfo("shifting place pose height, height_diff=%5.3f"%height_diff)
00243 
00244 
00245     ##find the height of an object pose above a detected table plane
00246     def find_height_above_table(self, pose, table):
00247         
00248         #shift the pose into the table's header frame
00249         (pos, rot) = pose_stamped_to_lists(self.tf_listener, pose, table.pose.header.frame_id)
00250        
00251         #find the pose's location in the table pose frame
00252         pos_mat = scipy.matrix(pos+[1]).T
00253         table_mat = pose_to_mat(table.pose.pose)
00254         pos_in_table_frame = table_mat**-1 * pos_mat
00255 
00256         #return the z-position
00257         #rospy.loginfo("height above table: %5.3f"%pos_in_table_frame[2,0])
00258         return pos_in_table_frame[2,0]
00259 
00260 
00261     ##point the head to find the front edge of the table and detect
00262     def find_table(self, point = None):
00263         if point == None:
00264             point = [self.table_front_edge_x, 0, self.table_height]
00265         self.point_head(point, 'base_link')
00266         self.call_tabletop_detection(take_static_collision_map = 0, update_table = 1, update_place_rectangle = 1)
00267 
00268 
00269     ##call find_cluster_bounding_box to get the bounding box for a cluster
00270     def call_find_cluster_bounding_box(self, cluster):
00271 
00272         req = FindClusterBoundingBoxRequest()
00273         req.cluster = cluster
00274         try:
00275             res = self.bounding_box_srv(req)
00276         except rospy.ServiceException, e:
00277             rospy.logerr("error when calling %s: %s"%(self.find_bounding_box_name, e))  
00278             self.throw_exception()
00279             return 0
00280         return (res.pose, [res.box_dims.x, res.box_dims.y, res.box_dims.z])
00281 
00282         
00283     ##call tabletop object detection and collision_map_processing (detects table/objects and adds them to collision map)
00284     def call_tabletop_detection(self, take_static_collision_map = 0, update_table = 0, clear_attached_objects = 1, \
00285                             store_detected_objects = 1, replace_table_in_collision_map = 1, update_place_rectangle = 0):
00286 
00287         rospy.loginfo("calling tabletop detection")
00288 
00289         det_req = TabletopDetectionRequest()
00290         det_req.return_clusters = 1
00291         det_req.return_models = 1
00292 
00293         #call tabletop detection, get a detection result
00294         for try_num in range(3):
00295             try:
00296                 det_res = self.grasper_detect_srv(det_req)
00297             except rospy.ServiceException, e:
00298                 rospy.logerr("error when calling %s: %s"%(self.grasper_detect_name, e))
00299                 self.throw_exception()
00300                 return ([], None)        
00301             if det_res.detection.result == det_res.detection.SUCCESS:
00302                 rospy.loginfo("tabletop detection reports success")
00303                 break
00304             else:
00305                 rospy.logerr("tabletop detection failed with error %s, trying again"%self.tabletop_detection_result_dict[det_res.detection.result])
00306         else:
00307             rospy.logerr("tabletop detection failed too many times.  Returning.")
00308             return ([], None)
00309 
00310         col_req = TabletopCollisionMapProcessingRequest()
00311         col_req.reset_collision_models = 1
00312         col_req.reset_attached_models = clear_attached_objects
00313         col_req.reset_static_map = take_static_collision_map
00314         col_req.take_static_collision_map = take_static_collision_map
00315         col_req.detection_result = det_res.detection
00316         col_req.desired_frame = 'base_link'
00317 
00318         #call collision map processing to add the detected objects to the collision map and get back a list of GraspableObjects
00319         try:
00320             col_res = self.collision_map_processing_srv(col_req)
00321         except rospy.ServiceException, e:
00322             rospy.logerr("error when calling %s: %s"%(self.collision_map_processing_name, e))
00323             self.throw_exception()
00324             return ([], None)
00325 
00326         table = det_res.detection.table
00327         self.collision_support_surface_name = col_res.collision_support_surface_name
00328 
00329         #combine the old table with the new detected table 
00330         if take_static_collision_map and not replace_table_in_collision_map:
00331             self.additional_tables.append(table)
00332             self.collision_map_interface.process_collision_geometry_for_table(self.detected_table, self.additional_tables)
00333 
00334         #save the new detected table (already in collision map)
00335         if update_table:
00336             self.detected_table = table
00337             self.update_table_info(update_place_rectangle)
00338 
00339         #sort objects by distance from the edge of the table 
00340         rospy.loginfo("detection finished, finding bounding boxes for clusters and sorting objects")
00341         dists = []
00342         object_box_dims = []
00343         object_poses = []
00344         heights_above_table = []
00345         for (ind, object) in enumerate(col_res.graspable_objects):
00346 
00347             #convert the pose for database objects into the base_link frame and replace the original
00348             if object.type == GraspableObject.DATABASE_MODEL:
00349                 pose_stamped = object.model_pose.pose
00350                 (pos, rot) = pose_stamped_to_lists(self.tf_listener, pose_stamped, 'base_link')
00351                 base_link_pose_stamped = create_pose_stamped(pos+rot, 'base_link')
00352                 object.model_pose.pose = base_link_pose_stamped
00353                 object_box_dims.append([.1, .1, .01])
00354                 object_poses.append(base_link_pose_stamped)
00355                 dists.append(pos[0])
00356 
00357             #find the bounding box for point clusters and store the box pose (should already be in base_link frame)
00358             if object.type == GraspableObject.POINT_CLUSTER:
00359                 (pose_stamped, box_dims) = self.call_find_cluster_bounding_box(object.cluster)
00360                 object.model_pose.pose = pose_stamped
00361                 object_box_dims.append(box_dims)
00362                 object_poses.append(pose_stamped)
00363                 dists.append(pose_stamped.pose.position.x)
00364 
00365             #find the heights of the objects above the detected table plane
00366             heights_above_table.append(self.find_height_above_table(pose_stamped, table))
00367 
00368             #print "new pose stamped:\n", object.model_pose.pose
00369 
00370         indices = scipy.array(dists).argsort()
00371 
00372         detected_objects = [ObjectInfo(col_res.graspable_objects[indices[i]], object_box_dims[indices[i]], \
00373                                            object_poses[indices[i]], self.tf_listener, heights_above_table[indices[i]], \
00374                                            col_res.collision_object_names[indices[i]]) for i in range(len(indices))]
00375 
00376         if store_detected_objects:
00377             self.detected_objects = detected_objects
00378 
00379         #print out the new object list
00380         self.print_object_list()
00381 
00382         return (detected_objects, table)
00383 
00384     
00385     ##make sure the joint controllers are on
00386     def check_joint_controllers(self, whicharm = None):
00387 
00388         if whicharm:
00389             self.cms[whicharm].check_controllers_ok('joint')
00390         else:
00391             for arm in [0,1]:
00392                 self.cms[arm].check_controllers_ok('joint')
00393 
00394 
00395     ##tell the grasp action to grasp an object (whicharm: right = 0, left = 1)
00396     def grasp_object(self, object, whicharm = None, use_reactive_grasp = 1, use_slip_detection = 0):
00397         rospy.loginfo("attempting to grasp an object, whicharm = %s"%str(whicharm))
00398 
00399         #make sure the joint controllers are on
00400         self.check_joint_controllers(whicharm)
00401 
00402         #open the gripper
00403         self.open_gripper(whicharm)
00404 
00405         #tell reactive grasping not to close too hard
00406         if whicharm == 0:
00407             rospy.set_param('reactive_grasp/right/close_force', 20)
00408         else:
00409             rospy.set_param('reactive_grasp/left/close_force', 20)
00410 
00411         #put together the grasp goal
00412         goal = PickupGoal()
00413 
00414         #tell the grasp action how to lift
00415         goal.lift = GripperTranslation()
00416         goal.lift.desired_distance = .1
00417         goal.lift.min_distance = 0.05
00418         goal.lift.direction = create_vector3_stamped([0.,0.,1.], 'base_link')
00419 
00420         goal.target = object.object
00421         goal.use_reactive_execution = use_reactive_grasp
00422         goal.use_reactive_lift = use_slip_detection
00423         goal.collision_object_name = object.collision_name
00424         goal.desired_approach_distance = 0.1
00425         goal.min_approach_distance = 0.05
00426         goal.collision_support_surface_name = self.collision_support_surface_name
00427         print "sending object collision name of:", object.collision_name
00428         if whicharm == 0:  
00429             goal.arm_name = "right_arm"
00430         else:
00431             goal.arm_name = "left_arm"
00432 
00433         #send the goal
00434         try:
00435             self.grasper_grasp_action_client.send_goal(goal)
00436         except rospy.ServiceException, e:
00437             rospy.logerr("error when calling %s: %e"(self.grasper_grasp_name, e))
00438             self.throw_exception()
00439             return ("ERROR", None, None)
00440 
00441         #wait for result
00442         finished_within_time = self.grasper_grasp_action_client.wait_for_result(rospy.Duration(240))
00443         if not finished_within_time:
00444             self.grasper_grasp_action_client.cancel_goal()
00445             rospy.logerr("timed out when asking the grasp action client to grasp")
00446             return (0, None, None)
00447 
00448         #return the result
00449         result = self.grasper_grasp_action_client.get_result()
00450         resultval = self.result_code_dict[result.manipulation_result.value]
00451         rospy.loginfo("grasp result: %s"%resultval)
00452 
00453         return (resultval, whicharm, result.grasp)
00454                 
00455         
00456     ##distance from a point (2-list) to a bounding box (projected onto table plane)
00457     #returns 0 if the point is inside; positive if it's outside
00458     def point_to_box_dist(self, point, box_pose, box_dims):
00459         
00460         #convert point to the object (pose) frame
00461         box_mat = pose_to_mat(box_pose.pose)
00462         box_mat[2, 3] = 0.
00463         point4 = scipy.matrix([point[0], point[1], 0, 1]).T
00464         box_frame_point = (box_mat**-1 * point4).T.tolist()[0]        
00465 
00466         #find the distance from the rectangle in 2-D (inside rectangle has dist of 0)
00467         dist = 0
00468         for dim in range(2):
00469             if box_frame_point[dim] < -box_dims[dim]/2:
00470                 dist += (-box_dims[dim]/2 - box_frame_point[dim])**2
00471             elif box_frame_point[dim] > box_dims[dim]/2:
00472                 dist += (box_frame_point[dim] - box_dims[dim]/2)**2
00473         dist = dist**.5
00474 
00475         return dist
00476         
00477 
00478     ##fills in place grid spots that are already taken by objects seen by the last tabletop detection
00479     def fill_in_taken_place_grid_spots(self, buffer = .05):
00480 
00481         #go through each grid point
00482         for i in range(self.place_grid_resolution):
00483             for j in range(self.place_grid_resolution):
00484                 
00485                 self.place_grid[i][j] = 0
00486 
00487                 #2-D location of the grid point
00488                 point = self.place_grid_location(i, j)
00489 
00490                 #check if it's within buffer distance of a detected object's bounding box
00491                 for (ind, object) in enumerate(self.detected_objects):
00492                     dist = self.point_to_box_dist(point, object.pose, object.box_dims)
00493 
00494                     #if so, mark that spot as taken
00495                     if dist < buffer:
00496                         rospy.loginfo("grid point %d %d is within %4.2f of detected object %d, dist=%4.2f" %(i, j, buffer, ind, dist))
00497                         self.place_grid[i][j] = 1
00498 #                     else:
00499 #                         rospy.loginfo("grid point %d %d is clear of object %d, dist=%4.2f" %(i, j, ind, dist))
00500                         
00501 
00502     ##tell the place service to place an object held by whicharm at a particular location (right = 0, left = 1)
00503     #expressed as a PoseStamped
00504     def place_object(self, whicharm, pose, padding = .05):
00505         rospy.loginfo("attempting to place object")
00506 
00507         #print "requested pose:", pose
00508 
00509         #recognized object, just send the object pose
00510         if self.held_objects[whicharm].object.type == 1:
00511             msg_pose = pose
00512 
00513         #point cluster, send back the cluster frame origin relative to the new desired pose
00514         #(cluster origin to base_link) = (new object to base_link) * (cluster to object)
00515         else:
00516             pose_mat = pose_to_mat(pose.pose)
00517             cluster_to_base_link_mat = pose_mat * self.held_objects[whicharm].cluster_origin_to_bounding_box
00518             cluster_to_base_link_pose = mat_to_pose(cluster_to_base_link_mat)
00519             msg_pose = stamp_pose(cluster_to_base_link_pose, 'base_link')
00520 #             print "cluster_origin_to_bounding_box:\n", ppmat(self.held_objects[whicharm].cluster_origin_to_bounding_box)
00521 #             print "pose_mat:\n", ppmat(pose_mat)
00522 #             print "cluster_to_base_link_mat:\n", ppmat(cluster_to_base_link_mat)
00523 
00524         #re-stamp the pose
00525         msg_pose.header.stamp = rospy.Time.now()
00526 
00527         goal = PlaceGoal()
00528         if whicharm == 0:  
00529             goal.arm_name = "right_arm"
00530             rospy.loginfo("asking the right arm to place")
00531 
00532         elif whicharm == 1:
00533             goal.arm_name = "left_arm"
00534             rospy.loginfo("asking the left arm to place")
00535 
00536         goal.place_pose = msg_pose
00537         goal.grasp = self.held_objects[whicharm].grasp
00538         goal.desired_retreat_distance = 0.1
00539         goal.min_retreat_distance = 0.05
00540 
00541         goal.approach = GripperTranslation()
00542         goal.approach.desired_distance = .1
00543         goal.approach.min_distance = 0.05
00544         goal.approach.direction = create_vector3_stamped([0.,0.,-1.], 'base_link')
00545 
00546         goal.collision_object_name = self.held_objects[whicharm].collision_name
00547         goal.collision_support_surface_name = self.collision_support_surface_name
00548         goal.place_padding = padding
00549         #goal.use_reactive_place = False
00550         goal.use_reactive_place = self.use_slip_detection
00551 
00552         #send the goal
00553         try:
00554             self.grasper_place_action_client.send_goal(goal)
00555         except rospy.ServiceException, e:
00556             rospy.logerr("error when calling %s: %e"(self.grasper_place_name, e))
00557             self.throw_exception()
00558             return "ERROR"
00559 
00560         #wait for result
00561         finished_within_time = self.grasper_place_action_client.wait_for_result(rospy.Duration(240))
00562         if not finished_within_time:
00563             self.grasper_place_action_client.cancel_goal()
00564             rospy.logerr("timed out when asking the place action client to place")
00565             return "FAILED"
00566 
00567         #return the result
00568         result = self.grasper_place_action_client.get_result()
00569         resultval = self.result_code_dict[result.manipulation_result.value]
00570         rospy.loginfo("place result: %s"%resultval)
00571         return resultval
00572 
00573 
00574     ##find an IK solution for a pose mat
00575     def find_IK_solution(self, whicharm, pose_mat, start_angles, collision_aware = 1):
00576         pose_stamped = stamp_pose(mat_to_pose(pose_mat), 'base_link')
00577         (joint_angles, error_code) = self.cms[whicharm].ik_utilities.run_ik(pose_stamped, \
00578                                   start_angles, self.cms[whicharm].ik_utilities.link_name, \
00579                                   collision_aware = collision_aware)
00580         return (joint_angles, error_code)
00581 
00582 
00583     ##place the object open-loop, shoving other objects aside
00584     def place_object_override(self, whicharm, pose, z_dist = .1, use_joint_open_loop = 0):
00585         rospy.loginfo("last-resort place")
00586 
00587         #figure out where the wrist has to be to make the object be at pose
00588         if self.held_objects[whicharm] and not self.held_objects[whicharm].grasp_type == 'flat':
00589 
00590             #recognized object, saved grasp pose is wrist pose in object frame
00591             if self.held_objects[whicharm].object.type == 1:
00592                 
00593                 #(wrist to base_link) = (object to base_link) * (wrist to object) 
00594                 wrist_to_object_mat = pose_to_mat(self.held_objects[whicharm].grasp_pose)
00595                 object_to_base_link_mat = pose_to_mat(pose.pose)
00596                 wrist_to_base_link_mat = object_to_base_link_mat * wrist_to_object_mat
00597 
00598             #point cluster, saved grasp pose is wrist pose in cluster frame
00599             else:
00600                 #(wrist to base link) = (object to base_link) * (cluster origin to object) * (wrist to cluster)
00601                 wrist_to_cluster_mat = pose_to_mat(self.held_objects[whicharm].grasp_pose)
00602                 cluster_to_object_mat = self.held_objects[whicharm].cluster_origin_to_bounding_box
00603                 object_to_base_link_mat = pose_to_mat(pose.pose)
00604                 wrist_to_base_link_mat = object_to_base_link_mat * cluster_to_object_mat * wrist_to_cluster_mat
00605             
00606             wrist_pose = stamp_pose(mat_to_pose(wrist_to_base_link_mat), 'base_link')
00607 
00608             #draw the wrist pose
00609             self.draw_functions.draw_rviz_axes(wrist_to_base_link_mat, 'base_link', id = 0, duration = 60.)
00610 
00611 
00612         #if we don't think there's an object in the hand (or if we're dropping a flat object), assume the gripper orientation should be held fixed
00613         #and let go of the object above pose (pose orientation should contain the current gripper orientation already)
00614         else:
00615             #figure out how high to raise the gripper to put the middle of the fingertips just above the loc            
00616             if self.held_objects[whicharm] and self.held_objects[whicharm].grasp_type == 'flat':
00617 
00618                 #use the longest box dim plus a bit for flat objects, and rotate the gripper by 90 degrees
00619                 pose.pose.position.z += self.held_objects[whicharm].box_dims[0]+.05
00620                 pose = stamp_pose(mat_to_pose(pose_to_mat(pose.pose) * scipy.matrix(tf.transformations.rotation_matrix(math.pi/2, [1,0,0]))), 'base_link')
00621             else:
00622                 pose.pose.position.z += .1
00623             fingertip_to_base_link_mat = pose_to_mat(pose.pose)
00624             wrist_to_fingertip_mat = scipy.matrix(tf.transformations.translation_matrix([-.167, 0, 0]))
00625             wrist_to_base_link_mat = fingertip_to_base_link_mat * wrist_to_fingertip_mat
00626             wrist_pose = pose
00627             set_xyz(wrist_pose.pose.position, wrist_to_base_link_mat[0:3, 3].T.tolist()[0])
00628 
00629 #             #attach a medium-sized box to the gripper so the object isn't guaranteed to hit the table
00630 #             box_dims = [.15]*3
00631 #             current_wrist_pose = self.cms[whicharm].get_current_wrist_pose_stamped('base_link')
00632 #             box_to_wrist = scipy.matrix(tf.transformations.translation_matrix([.12+box_dims[0], 0, 0]))
00633 #             box_pose = mat_to_pose(pose_to_mat(current_wrist_pose.pose) * box_to_wrist)
00634 #             self.collision_map_interface.add_collision_box(box_pose, box_dims, 'base_link', 'temporary_box')
00635 #             self.attach_object(whicharm, 'temporary_box')
00636 
00637         #come in from the front, just above the table 
00638         front_above_pose = copy.deepcopy(wrist_pose)
00639 
00640         #temporary, while deepcopy of rospy.Time is broken
00641         front_above_pose.header.stamp = rospy.Time(wrist_pose.header.stamp.secs)
00642         front_above_pose.pose.position.x += self.place_override_approach_offset[0]
00643         front_above_pose.pose.position.y += self.place_override_approach_offset[1]
00644         front_above_pose.pose.position.z += self.place_override_approach_offset[2] + z_dist
00645 
00646         #draw the wrist_pose and front_above_pose
00647         self.draw_functions.draw_rviz_axes(wrist_to_base_link_mat, 'base_link', id = 0, duration = 60.)
00648         front_above_mat = pose_to_mat(front_above_pose.pose)
00649         self.draw_functions.draw_rviz_axes(front_above_mat, 'base_link', id = 1, duration = 60.)
00650         
00651         #ask move arm to get us there, or move open-loop if move arm fails and we can find an IK solution 
00652         result = self.try_hard_to_move_pose(whicharm, front_above_pose, use_joint_open_loop = use_joint_open_loop, \
00653                                                 use_cartesian = 0, try_constrained = 1)
00654         if not result:
00655             return 0
00656 
00657         #now move to the place pose using the Cartesian controllers
00658         self.cms[whicharm].move_cartesian(wrist_pose, settling_time = rospy.Duration(10))
00659 
00660         #drop the object
00661         self.open_gripper(whicharm)
00662 
00663         #detach the object (and add it back where it was dropped if we knew what object it was)
00664         if self.held_objects[whicharm]:
00665             self.detach_and_add_back_object(whicharm)
00666         else:
00667             self.detach_object(whicharm)
00668 
00669         #lift the arm
00670         wrist_pose.pose.position.z += .2
00671         self.cms[whicharm].move_cartesian(wrist_pose, settling_time = rospy.Duration(10))
00672 
00673         #get out of there
00674         self.move_arm_out_of_way(whicharm)
00675         return 1
00676 
00677 
00678     ##attach the object in the hand to the gripper (right = 0, left = 1)
00679     def attach_object(self, whicharm, object_name):
00680         rospy.loginfo("attaching object %s to gripper %s"%(object_name, self.arm_dict[whicharm]))
00681         self.collision_map_interface.attach_object_to_gripper(object_name, self.arm_dict[whicharm])
00682         
00683 
00684     ##detach the object in the hand from the gripper (right = 0, left = 1)
00685     def detach_object(self, whicharm):
00686         rospy.loginfo("detaching object from %s gripper"%self.arm_dict[whicharm])
00687         self.collision_map_interface.detach_all_objects_from_gripper(self.arm_dict[whicharm])
00688         
00689 
00690     ##detach and add the object back to the collision map
00691     def detach_and_add_back_object(self, whicharm, collision_name = None):
00692         if collision_name == None:
00693             if self.held_objects[whicharm]:
00694                 rospy.loginfo("detaching object %s from %s gripper and adding it back to the collision map" \
00695                                  %(self.held_objects[whicharm].collision_name, self.arm_dict[whicharm]))
00696                 self.collision_map_interface.detach_and_add_back_objects_attached_to_gripper(self.arm_dict[whicharm], \
00697                                                             self.held_objects[whicharm].collision_name)
00698             else:
00699                 rospy.loginfo("gripper doesn't think it's holding any objects; detaching all objects without re-adding")
00700                 self.collision_map_interface.detach_all_objects_from_gripper(self.arm_dict[whicharm])
00701         else:
00702             self.collision_map_interface.detach_and_add_back_objects_attached_to_gripper(self.arm_dict[whicharm], collision_name)
00703 
00704 
00705     ##remove an object from the collision map
00706     def remove_object(self, collision_name):
00707         rospy.loginfo("removing object %s from the collision map"%collision_name)
00708         self.collision_map_interface.remove_collision_object(collision_name)
00709 
00710 
00711     ##remove an object and add it back in as the current bounding box
00712     def update_object_box(self, object_info):
00713         
00714         self.remove_object(object_info.collision_name)
00715         self.collision_map_interface.add_collision_box(object_info.pose, object_info.box_dims, \
00716                                                            'base_link', object_info.collision_name)
00717 
00718 
00719     ##point the head (really the narrow-stereo camera frame) at a location
00720     def point_head(self, point, frame):
00721         goal = PointHeadGoal()
00722         goal.target = create_point_stamped(point, frame)
00723         goal.pointing_frame = "/narrow_stereo_optical_frame"
00724         goal.max_velocity = 1.0
00725 
00726         print "I won't move my head, I won't, I won't, I won't .... "
00727         # self.head_action_client.send_goal(goal)
00728         # finished_within_time = self.head_action_client.wait_for_result(rospy.Duration(20))
00729         # if not finished_within_time:
00730         #     self.head_action_client.cancel_goal()
00731         #     rospy.logerr("timed out when asking the head to point to a new goal")
00732         #     return 0
00733 
00734         #sleep a bit so a new point cloud has time to be generated
00735         time.sleep(1.0)
00736         return 1
00737 
00738 
00739     ##use the table detection to update the table information
00740     #if adjust_place_rectangle is 1, adjusts a place rectangle on the table (assumed base_link frame) 
00741     #with the new table params
00742     def update_table_info(self, adjust_place_rectangle = 0):
00743 
00744         #subtract the old table params if adjusting the place rectangle
00745         if adjust_place_rectangle:
00746             print "self.table_height before update:", self.table_height
00747             place_rect_pose_mat = pose_to_mat(self.transform_place_rect_pose())
00748             place_rect_pose_mat[0, 3] -= self.table_front_edge_x
00749             place_rect_pose_mat[2, 3] -= self.table_height
00750 
00751         #find the table's front edge and height
00752         base_link_pose_stamped = change_pose_stamped_frame(self.tf_listener, self.detected_table.pose, 'base_link')
00753         table_mat = pose_to_mat(base_link_pose_stamped.pose)
00754         corners = scipy.matrix([[self.detected_table.x_min, self.detected_table.y_min,0,1],
00755                                 [self.detected_table.x_min, self.detected_table.y_max,0,1],
00756                                 [self.detected_table.x_max, self.detected_table.y_min,0,1],
00757                                 [self.detected_table.x_max, self.detected_table.y_max,0,1]]).T
00758         transformed_corners = table_mat * corners
00759         front_edge_x = transformed_corners[0,:].min()
00760         height = transformed_corners[2,:].max()
00761         self.table_front_edge_x = front_edge_x
00762         self.table_height = height
00763         rospy.loginfo("table front edge x: %5.3f"%front_edge_x)
00764         rospy.loginfo("table height: %5.3f"%height)
00765 
00766         #adjust the place rectangle with the new table params
00767         if adjust_place_rectangle:
00768             print "place_rect_pose_mat before update:\n", ppmat(place_rect_pose_mat)
00769             place_rect_pose_mat[0, 3] += self.table_front_edge_x
00770             place_rect_pose_mat[2, 3] += self.table_height
00771             self.place_rect_pose_stamped = stamp_pose(mat_to_pose(place_rect_pose_mat), 'base_link')
00772             print "place_rect_pose_mat:\n", ppmat(place_rect_pose_mat)
00773 
00774             #draw the new place grid
00775             self.set_place_area(self.place_rect_pose_stamped, self.place_rect_dims)
00776 
00777 
00778     ##convert the place rectangle pose to base_link frame if it isn't already (returns pose, not pose_stamped)
00779     def transform_place_rect_pose(self):
00780         if self.place_rect_pose_stamped.header.frame_id != 'base_link':
00781             transformed_rect_pose = change_pose_stamped_frame(self.tf_listener, \
00782                            self.place_rect_pose_stamped.pose, self.place_rect_pose_stamped.header.frame_id).pose
00783         else:
00784             transformed_rect_pose = self.place_rect_pose_stamped.pose
00785         return transformed_rect_pose
00786 
00787 
00788     ##set a rectangle centered at rect_pose_stamped of dims (x, y) to be the desired place area
00789     def set_place_area(self, rect_pose_stamped, dims):
00790         self.place_rect_dims = dims
00791         self.place_rect_pose_stamped = rect_pose_stamped
00792 
00793         self.draw_place_area()
00794 
00795 
00796     ##draw the current place area as a set of boxes
00797     def draw_place_area(self):
00798         #convert the place rectangle pose to base_link frame if it isn't already (just for drawing)
00799         transformed_rect_pose = self.transform_place_rect_pose()
00800         place_grid_loc_mat = pose_to_mat(transformed_rect_pose)
00801         self.draw_functions.draw_rviz_box(place_grid_loc_mat, [.01, .01, .01], duration = 0,\
00802                                               frame = 'base_link', \
00803                                               color = [1,0,0], id=101)
00804 
00805         #draw boxes at each place location
00806         for i in range(self.place_grid_resolution):
00807             for j in range(self.place_grid_resolution):
00808                 location = self.place_grid_location(i,j)
00809                 place_grid_loc_mat[0,3] = location[0]
00810                 place_grid_loc_mat[1,3] = location[1]
00811                 self.draw_functions.draw_rviz_box(place_grid_loc_mat, [.01, .01, .01], duration = 0,\
00812                                     frame = 'base_link', color = [0,0,1], id=1000+self.place_grid_resolution*i+j)
00813 
00814 
00815     ##return the location of a point in the place grid
00816     def place_grid_location(self, xind, yind):
00817 
00818         grid_x_size = self.place_rect_dims[0]/self.place_grid_resolution
00819         grid_y_size = self.place_rect_dims[1]/self.place_grid_resolution
00820         grid_center = int(math.floor(self.place_grid_resolution/2.))  #make place_grid_resolution odd for now
00821 
00822         #convert the place rectangle pose to base_link frame if it isn't already
00823         transformed_rect_pose = self.transform_place_rect_pose()
00824 
00825         #convert the place grid relative location to a location in the base_link frame (returned as list)
00826         rel_location = scipy.matrix([(grid_center-xind)*grid_x_size, (grid_center-yind)*grid_y_size, 0, 1]).T
00827         location = pose_to_mat(transformed_rect_pose) * rel_location
00828         location = location.T.tolist()[0]  
00829         return location
00830 
00831                 
00832     ##return the pose of the object at a place grid location
00833     def place_grid_pose(self, xind, yind, whicharm, add_noise = 0):
00834 
00835         #find the place grid location for xind, yind
00836         location = self.place_grid_location(xind, yind)
00837         rospy.loginfo("proposed place location: %5.3f, %5.3f"%(location[0], location[1]))
00838 
00839         #create a pose_stamped for the object at that location based on its original pose
00840         if self.held_objects[whicharm] and not self.held_objects[whicharm].grasp_type == 'flat':
00841             place_pose = copy.deepcopy(self.held_objects[whicharm].pose)
00842             
00843             #temporary, while deepcopy of rospy.Time is broken
00844             place_pose.header.stamp = rospy.Time(self.held_objects[whicharm].pose.header.stamp.secs)
00845 
00846         #no object in the hand, use the current wrist orientation and change the location
00847         else:
00848             place_pose = self.cms[whicharm].get_current_wrist_pose_stamped('base_link')
00849             
00850         #set the place_pose z to be the place grid center z
00851         transformed_rect_pose = self.transform_place_rect_pose()
00852         place_pose.pose.position.z = transformed_rect_pose.position.z
00853 
00854         #and the x and y to be the current grid location x and y
00855         place_pose.pose.position.x = location[0]
00856         place_pose.pose.position.y = location[1]
00857 
00858         #add noise to the place pose, if requested
00859         if add_noise:
00860             rospy.loginfo("adding noise to place pose")
00861             place_pose.pose.position.x += scipy.rand()*.05
00862             place_pose.pose.position.y += scipy.rand()*.05
00863 
00864         #draw the object's visualization box (bounding or at-the-base) at the place location
00865         self.draw_object_pose(self.held_objects[whicharm], place_pose, [0,1,1], 100)
00866 
00867         return place_pose
00868 
00869     
00870     ##draw a visualization box (bounding or at-the-base) for an object at a PoseStamped
00871     def draw_object_pose(self, object_info, pose_stamped, color, id, duration = 300.):
00872         pose_mat = pose_to_mat(pose_stamped.pose)
00873         if object_info:
00874             box_dims = object_info.box_dims
00875         else:
00876             box_dims = [.05, .05, .05]
00877         self.draw_functions.draw_rviz_box(pose_mat, box_dims, duration = duration,\
00878                           frame = pose_stamped.header.frame_id, color = color, id = id)         
00879 
00880 
00881     ##choose a new location to try to place an object held by whicharm (right = 0, left = 1)
00882     #if override_pose >=0, then pick an override pose from front to back
00883     def choose_place_location(self, whicharm, override_pose = -1, z_offset = 0):
00884 
00885         #start from the back and work your way to the front
00886         i = j = 0
00887 
00888         #unless this is an open-loop place, in which case start from the front and work your way back
00889         num_poses_to_skip = 0
00890         if override_pose >= 0:
00891             i = self.place_grid_resolution-1
00892             num_poses_to_skip = override_pose
00893 
00894         #go through the grid, looking for a good spot
00895         for grid_ind in range(self.place_grid_resolution**2+num_poses_to_skip):
00896             if self.place_grid[i][j] != 0:
00897 
00898                 #we only want empty/not previously colliding grid spots (=0) 
00899                 #unless it's an override pose, in which case we'll settle for anything that 
00900                 #isn't explictly taken (=1)
00901                 if override_pose < 0 or self.place_grid[i][j] == 1:
00902 
00903                     if num_poses_to_skip == 0:
00904                         rospy.loginfo("place_grid spot %d %d taken with value %d"%(i,j, self.place_grid[i][j]))
00905                     j = j+1
00906                     if j > self.place_grid_resolution - 1:
00907                         j = 0
00908                         if override_pose < 0:
00909                             i = (i+1)%self.place_grid_resolution
00910                         else:
00911                             i = (i-1)%self.place_grid_resolution
00912                     continue
00913 
00914             #for an override pose, skip over good poses that we've tried before
00915             if num_poses_to_skip > 0:
00916                 num_poses_to_skip -= 1
00917                 j = j+1
00918                 if j > self.place_grid_resolution - 1:
00919                     j = 0
00920                     i = (i-1)%self.place_grid_resolution
00921                 continue
00922 
00923             rospy.loginfo("returning grid location %d %d"%(i, j))
00924 
00925             #compute the relevant pose
00926             if override_pose >= 0 or z_offset > 0:
00927                 pose = self.place_grid_pose(i,j, whicharm, add_noise = 0)
00928             else:
00929                 pose = self.place_grid_pose(i,j, whicharm)
00930 
00931             #add the desired z-offset to make sure we're not just grazing the table
00932             pose.pose.position.z += z_offset
00933 
00934             return (i, j, pose, 0)
00935 
00936         rospy.logerr("all grid locations are taken!  Returning")
00937         pose = self.place_grid_pose(i,j, whicharm)
00938         return (i,j, pose, 1)
00939 
00940         
00941     ##reset all the -1s (temporary collision entries) in the place grid
00942     def reset_place_grid_temporary_collisions(self):
00943         for i in range(self.place_grid_resolution):
00944             for j in range(self.place_grid_resolution):
00945                 if self.place_grid[i][j] == -1:
00946                     self.place_grid[i][j] = 0
00947 
00948 
00949     ##rotate the pose_stamped about the base-link z-axis by rotation rad
00950     #but keep the position the same
00951     def rotate_pose(self, pose_stamped, rotation):
00952         if rotation == 0:
00953             return pose_stamped
00954 
00955         rot_mat = scipy.matrix(tf.transformations.rotation_matrix(rotation, [0,0,1]))
00956         rotated_pose_stamped = transform_pose_stamped(pose_stamped, rot_mat, "pre")
00957         rotated_pose_stamped.pose.position = copy.deepcopy(pose_stamped.pose.position)
00958 
00959         return rotated_pose_stamped
00960 
00961 
00962     ##call the grasping_app_transfer service to move the object from hand to hand
00963     def transfer_object_to_other_hand(self, holding_arm, object):
00964 
00965         #fill in the request
00966         req = GraspingAppTransferRequest()
00967         if self.arm_dict[holding_arm] == 'r':
00968             req.into_arm.which_arm = ArmSelection.LEFT_ARM
00969         else:
00970             req.into_arm.which_arm = ArmSelection.RIGHT_ARM
00971         req.grasp_info.object = object.object
00972         req.grasp_info.grasp_pose = object.grasp_pose
00973 
00974         rospy.loginfo("calling grasping app transfer")
00975         try:
00976             res = self.grasper_transfer_srv(req)
00977         except rospy.ServiceException, e:
00978             rospy.logerr("error when calling %s: %s"%(self.grasper_transfer_name, e))
00979             self.throw_exception()
00980             return 0
00981 
00982         result = self.result_code_dict[res.transfer_result.value]
00983 
00984         #transfer succeeded, update the object-in-hand info
00985         if result == "SUCCESS":
00986             rospy.loginfo("transfer reported success, updating the grasp info")
00987 
00988             #switch object to other hand
00989             self.held_objects[(1-holding_arm)] = self.held_objects[holding_arm]
00990             self.held_objects[holding_arm] = 0
00991 
00992             #update the grasp position
00993             self.held_objects[(1-holding_arm)].grasp_pose = res.grasp_pose
00994 
00995         #move both arms back to the side
00996         self.move_arm_out_of_way(holding_arm)
00997         self.move_arm_out_of_way(1-holding_arm)
00998         
00999         #return the result regardless of whether the transfer occurred
01000         if result == "SUCCESS":
01001             return 1
01002         return 0
01003 
01004 
01005     ##point the head at the place rectangle
01006     def point_head_at_place_rect(self, offset = 1):
01007 
01008         rospy.loginfo("pointing the head at the place rectangle")
01009 
01010         #convert the place rect pose to base_link if it isn't there already
01011         transformed_rect_pose = self.transform_place_rect_pose()
01012 
01013         #grab the center 
01014         (x,y,z) = get_xyz(transformed_rect_pose.position)
01015         
01016         #point the head just off of that position
01017         if offset:
01018             self.point_head([x-.15, y*.7, z], 'base_link')
01019         else:
01020             self.point_head([x,y,z], 'base_link')
01021 
01022 
01023     ##put down an object held in whicharm (right = 0, left = 1)
01024     def put_down_object(self, whicharm, max_place_tries = None, use_place_override = 0, move_to_side = True):
01025         
01026         padding = .05  #initial padding around recognized objects (cm)
01027 
01028         #make sure the joint controllers are on
01029         self.check_joint_controllers(whicharm)
01030 
01031         #check if there's actually something still in the gripper (if not, give up)
01032         if not self.check_grasp_successful(whicharm):
01033             rospy.loginfo("no object in gripper!  Stopping put-down")
01034             
01035             #detach the object and zero out held objects
01036             self.held_objects[whicharm] = 0
01037             self.detach_object(whicharm)
01038             return 1
01039    
01040         self.check_preempted()
01041 
01042         #point head at the place rectangle
01043         self.point_head_at_place_rect()
01044         
01045         self.check_preempted()
01046 
01047         #detect objects and table (and clear out extra collision points)
01048         (objects, table) = self.call_tabletop_detection(take_static_collision_map = 1, update_table = 0, clear_attached_objects = 0)
01049         
01050         self.check_preempted()
01051 
01052         #mark spots that are too close to detected objects as taken
01053         if self.held_objects[whicharm]:
01054             self.fill_in_taken_place_grid_spots(buffer = min(self.held_objects[whicharm].box_dims[0:2])+.03)
01055         else:
01056             self.fill_in_taken_place_grid_spots(buffer = padding)
01057 
01058         self.check_preempted()
01059 
01060         #how many times to do a regular place before trying the override place
01061         if max_place_tries == None and self.held_objects[whicharm] and not self.held_objects[whicharm].grasp_type == 'flat':
01062             place_tries_left = self.place_grid_resolution**2*2
01063         elif not self.held_objects[whicharm] or self.held_objects[whicharm].grasp_type == 'flat':
01064             place_tries_left = 0 #no object in the hand, or flat object, go directly to override place 
01065         else:
01066             place_tries_left = max_place_tries
01067 
01068         #try a bunch of times to place carefully
01069         success = 0
01070         z_offset = 0
01071         max_z_offset = .01
01072         while(place_tries_left > 0):
01073             rospy.loginfo("place_tries_left: %d"%place_tries_left)
01074             place_tries_left -= 1
01075 
01076             self.check_preempted()
01077 
01078             #check to make sure there's still something in the gripper (if not, give up)
01079             if not self.check_grasp_successful(whicharm):
01080                 rospy.loginfo("no object in gripper!  Stopping put-down")
01081 
01082                 #detach the object and zero out held objects
01083                 self.held_objects[whicharm] = 0
01084                 self.detach_object(whicharm)
01085                 return 1
01086 
01087             #search for a place to put the object
01088             (i, j, pose, full) = self.choose_place_location(whicharm, -1, z_offset)
01089 
01090             #choose_place_location didn't find any suitable place locations, so raise z_offset (quit if already too high)
01091             if full == 1:
01092                 if z_offset >= max_z_offset:
01093                     break
01094 
01095                 #raise the z-offset and try again
01096                 else:
01097                     z_offset += .01
01098                     padding = .02
01099                     rospy.loginfo("grid was full, raising the z_offset to %5.3f and lowering the padding"%z_offset)
01100                     self.fill_in_taken_place_grid_spots(buffer = padding)
01101                     (i, j, pose, full) = self.choose_place_location(whicharm, -1, z_offset)
01102                     
01103                     #all grid locations were 1, never mind
01104                     if full == 1:
01105                         rospy.loginfo("all grid locations were 1, moving on to last-resort place")
01106                         break
01107 
01108             self.check_preempted()
01109 
01110             #shift the object to be above the current detected table, if there is one
01111             if table:
01112                 self.shift_place_pose_height(self.held_objects[whicharm], pose, table, z_offset)
01113             
01114             self.check_preempted()
01115 
01116             #try to place it there at one of several rotations
01117             inc = math.pi/4.
01118             rotationlist = [0.,]
01119             for mult in range(1, int(math.floor(math.pi/inc))+1):
01120                 rotationlist.append(mult*inc)
01121                 rotationlist.append(-mult*inc)
01122 
01123             success = 0
01124             for rotation in rotationlist:
01125                 rotated_pose = self.rotate_pose(pose, rotation)
01126                 self.draw_object_pose(self.held_objects[whicharm], rotated_pose, [0,1,1], 100)
01127 
01128                 #call the place object service
01129                 result = self.place_object(whicharm, rotated_pose, padding)
01130                 if result == "SUCCESS":
01131                     success = 1
01132                     break
01133                 elif result == "ERROR":
01134                     self.throw_exception()
01135                     break
01136                 elif result == "FAILED":
01137                     rospy.logerr("place object returned failed, arm is probably stuck (opening the gripper, resetting collision map and re-taking before moving back to the side)")
01138                     self.open_gripper(whicharm)
01139                     self.reset_collision_map()
01140                     self.take_static_map()
01141                     success = 1
01142                     break
01143                 elif result == "RETREAT_FAILED":
01144                     rospy.loginfo("place object returned retreat failed; doing an open-loop retreat")
01145                     wrist_pose = self.cms[whicharm].get_current_wrist_pose_stamped(frame = 'base_link')
01146                     wrist_mat = pose_to_mat(wrist_pose.pose)
01147                     shift = scipy.matrix(tf.transformations.translation_matrix([-.1, 0, 0]))
01148                     retreat_mat = wrist_mat * shift
01149                     retreat_pose = stamp_pose(mat_to_pose(retreat_mat), 'base_link')
01150                     self.move_cartesian_step(whicharm, retreat_pose, timeout = 5.0, \
01151                                                  settling_time = 3.0, blocking = 1)
01152                     success = 1
01153                     break
01154                 elif result == "MOVE_ARM_STUCK":
01155                     rospy.loginfo("grasp object returned move arm stuck; taking a new collision map and moving to side before trying next place")
01156                     self.reset_collision_map()
01157                     self.take_static_map()
01158                     self.move_arm_out_of_way(whicharm, try_constrained = 1)
01159 
01160             #succeeded, stop
01161             if success:
01162                 break
01163 
01164             #didn't succeed at any rotation, go on to the next place
01165             else:
01166                 rospy.loginfo("marking place grid spot %d %d as colliding" %(i,j))
01167                 self.place_grid[i][j] = -1
01168 
01169 
01170         #place failed, put it down open-loop at an override position
01171         if not success and use_place_override:
01172             self.check_preempted()
01173 
01174             for tries in range(self.place_grid_resolution**2*2):
01175                 rospy.loginfo("place object override try number:%d"%tries)
01176 
01177                 (i,j,pose,z_offset) = self.choose_place_location(whicharm, override_pose = tries)
01178 
01179                 #try to place it there at one of several rotations
01180                 rotationlist = [0, math.pi/4, -math.pi/4, math.pi/2, -math.pi/2]
01181                 for rotation in rotationlist:
01182                     rotated_pose = self.rotate_pose(pose, rotation)
01183                     if self.held_objects[whicharm]:
01184                         self.draw_object_pose(self.held_objects[whicharm], rotated_pose, [1,0,0], 100)
01185 
01186                     z_dist = .1 * (math.floor(tries/10.)+1)
01187                     success = self.place_object_override(whicharm, rotated_pose, z_dist)
01188                     if success:
01189                         #record that something was placed there
01190                         self.place_grid[i][j] = 1
01191                         break
01192                     else:
01193                         rospy.loginfo("Place object override failed!")
01194                 if success:
01195                     break
01196 
01197 
01198         #if we managed to put it down, record that the hand is empty
01199         if success:
01200             rospy.loginfo("removing object from held_objects for the %s hand"%self.arm_dict[whicharm])
01201             self.held_objects[whicharm] = None
01202             self.reset_place_grid_temporary_collisions()
01203 
01204             #move the arm back out of the way
01205             if move_to_side == True:
01206                 self.move_arm_out_of_way(whicharm)
01207             return 1
01208 
01209         else:
01210             rospy.loginfo("place failed")
01211             return 0
01212 
01213 
01214     ##grasp the object and check if there's something in the hand
01215     def grasp_object_and_check_success(self, object, whicharm = None):
01216 
01217         #try picking it up
01218         (grasp_result, arm_used, executed_grasp) = self.grasp_object(object, whicharm, 1, \
01219                                                       use_slip_detection = self.use_slip_detection)
01220 
01221         self.check_preempted()
01222 
01223         #if succeeded, record that the arm has an object 
01224         if grasp_result == "SUCCESS":
01225 
01226             #check if there's an object in the hand
01227             if self.check_grasp_successful(arm_used):
01228 
01229                 self.held_objects[arm_used] = object
01230                 object.grasp_pose = executed_grasp.grasp_pose
01231                 object.grasp = executed_grasp
01232                 rospy.loginfo("grasp succeeded, adding object to held_objects for the %s arm"%self.arm_dict[arm_used])
01233                 return ("succeeded", arm_used)
01234 
01235             #if failed and we actually tried to grasp, detach the object and return that the attempt failed
01236             else:
01237                 self.detach_object(arm_used)
01238                 rospy.loginfo("grasp attempt failed and probably moved the object, detaching the object and returning")
01239                 self.move_arm_out_of_way(arm_used, try_constrained = 1)                
01240                 return ("attempt failed", None)
01241 
01242         #object grasper failed
01243         elif grasp_result == "FAILED":
01244             self.open_gripper(arm_used)
01245             self.move_arm_out_of_way(arm_used)
01246             return ("attempt failed", None)
01247 
01248         #grasp succeeded, but lift failed, which we can do instead
01249         elif grasp_result == "LIFT_FAILED":
01250 
01251             rospy.loginfo("just lift failed; lifting with Cartesian controllers")
01252             self.held_objects[arm_used] = object
01253             object.grasp_pose = executed_grasp.grasp_pose
01254             object.grasp = executed_grasp
01255             up_goal = self.return_current_pose_as_list(arm_used)
01256             up_goal[2] += .1
01257             self.move_cartesian_step(arm_used, up_goal, blocking = 1)
01258 
01259             #still something in the gripper after lifting, so we succeeded
01260             if self.check_grasp_successful(arm_used):
01261                 rospy.loginfo("grasp succeeded, adding object to held_objects for the %s arm"%self.arm_dict[arm_used])
01262                 return ("succeeded", arm_used)
01263 
01264             #dropped whatever it was, give up
01265             else:
01266                 self.detach_object(arm_used)
01267                 self.open_gripper(arm_used)
01268                 self.move_arm_out_of_way(arm_used)
01269                 rospy.loginfo("lift attempt failed, detaching object and returning to the side")
01270                 return ("attempt failed", None)
01271 
01272         #infeasible grasp, but nothing was disturbed
01273         elif grasp_result == "UNFEASIBLE":
01274             return ("no feasible grasp", None)
01275 
01276         #start state was in collision even after trying to add allowed contact regions, better take a new map
01277         elif grasp_result == "MOVE_ARM_STUCK":
01278             rospy.loginfo("grasp object returned move arm stuck; taking a new collision map and moving to side")
01279             self.reset_collision_map()
01280             self.move_arm_out_of_way(arm_used)
01281             return ("attempt failed", None)
01282 
01283         #grasper returned "ERROR", better ask a human for help
01284         else:
01285             self.throw_exception()
01286             return ("error", None) 
01287 
01288 
01289     ##refine an object detection by pointing the head at it (input the object's position on the table)
01290     def refine_object_detection(self, objectx, objecty):
01291         rospy.loginfo("refining object detection")
01292         self.point_head([objectx-.15, objecty*.7, self.table_height], 'base_link')
01293         (objects, table) = self.call_tabletop_detection(take_static_collision_map = 1, update_table = 0, store_detected_objects = 0)
01294         
01295         #find the object closest to the original location and return it
01296         closest_object = None
01297         closest_object_dist = 1e6
01298         for object in objects:
01299             xdist = object.pose.pose.position.x-objectx
01300             ydist = object.pose.pose.position.y-objecty
01301             if (xdist**2+ydist**2) < closest_object_dist:
01302                 closest_object_dist = xdist**2+ydist**2
01303                 closest_object = object
01304 
01305         return closest_object
01306 
01307 
01308     ##distance between the narrow stereo's center ray and a pose_stamped's center
01309     def pose_to_narrow_stereo_center_dist(self, pose_stamped):
01310         
01311         #convert the pose to the narrow_stereo frame
01312         transformed_pose = change_pose_stamped_frame(self.tf_listener, pose_stamped, 'narrow_stereo_optical_frame')
01313 
01314         #find the distance of the pose from the z-axis (dist in x-y plane)
01315         pose_dist = math.sqrt(transformed_pose.pose.position.x**2 + transformed_pose.pose.position.y**2)
01316 
01317         return pose_dist
01318 
01319     ##refine the view of the object, if it's too far from the center of the narrow stereo center
01320     def refine_if_not_centered(self, object):
01321 
01322         #if the object is too far away from where the head is pointing, point the head at it and re-detect first
01323         dist_from_point = self.pose_to_narrow_stereo_center_dist(object.pose)
01324         object_to_grasp = object
01325         rospy.loginfo("dist_from_point:%5.3f"%dist_from_point) 
01326         if dist_from_point > .1:
01327             refined_object = self.refine_object_detection(object.pose.pose.position.x, object.pose.pose.position.y)
01328             if refined_object != None:
01329                 object_to_grasp = refined_object
01330             else:
01331                 rospy.logerr("refining object detection resulted in no object detections!")
01332         return object_to_grasp
01333 
01334 
01335     ##pick up the object_num-th nearest feasible object (tries each one in turn)
01336     #arms_to_try indicates which arms to try in what order (0=right, 1=left)
01337     def pick_up_nearest_object(self, object_num = 0, arms_to_try = [0,1]):
01338 
01339         #objects are already sorted by distance to edge of table
01340         for object in self.detected_objects[object_num:]:
01341 
01342             object_to_grasp = self.refine_if_not_centered(object)
01343 
01344             #try one arm and then the other
01345             for whicharm in arms_to_try:
01346 
01347                 self.check_preempted()
01348 
01349                 (result, arm_used) = self.grasp_object_and_check_success(object_to_grasp, whicharm)
01350 
01351                 self.check_preempted()
01352 
01353                 if result == "succeeded":
01354                     return (1, arm_used)
01355                 elif result == "attempt failed":
01356                     return (0, None)
01357 
01358                 #if we didn't succeed but didn't try to grasp, just continue
01359                 elif result == "no feasible grasp":
01360                     rospy.loginfo("no feasible grasp for this object with the %s arm, trying the next"%self.arm_dict[whicharm])
01361 
01362         #didn't manage to pick up any object
01363         rospy.loginfo("no feasible grasps found for any object")
01364         return (0, None)
01365 
01366 
01367     ##open the gripper (whicharm is 0 for right, 1 for left)
01368     def open_gripper(self, whicharm):
01369         self.cms[whicharm].command_gripper(.1, -1, 1)
01370 
01371 
01372     ##close the gripper (whicharm is 0 for right, 1 for left)
01373     def close_gripper(self, whicharm):
01374         self.cms[whicharm].command_gripper(0, 100, 1)
01375 
01376 
01377     ##reset the collision map and take a new one (without tabletop or objects)
01378     def reset_collision_map(self):
01379         self.collision_map_interface.reset_collision_map()
01380 
01381 
01382     ##just take a new static collision map, without re-finding table or objects
01383     def take_static_map(self):
01384         self.collision_map_interface.take_static_map()
01385 
01386 
01387     ##try to move to a set of joint angles using move_arm, ignoring current collisions if necessary, and if that fails, 
01388     #move open-loop
01389     def try_hard_to_move_joint(self, whicharm, trajectory, max_tries = 5, use_open_loop = 1):
01390         reset_collision_map = 0
01391         for tries in range(max_tries):
01392             rospy.loginfo("try_hard_to_move_joint try number: %d"%tries)
01393             error_code = self.cms[whicharm].move_arm_joint(trajectory[-1], blocking = 1)
01394 
01395             if error_code == 1:
01396                 rospy.loginfo("move arm reported success")
01397                 return 1
01398             elif error_code == 0:
01399                 if not reset_collision_map:
01400                     rospy.loginfo("problem with collision map!  Resetting collision map and taking a new one")
01401                     self.reset_collision_map()
01402                     self.take_static_map()
01403                     reset_collision_map = 1
01404                 else:
01405                     rospy.loginfo("resetting collision map didn't work, move arm is still stuck!")
01406                     break
01407             rospy.loginfo("move arm reports failure with error code %d"%error_code)
01408 
01409         if use_open_loop:
01410             rospy.loginfo("moving open-loop to desired joint angles")
01411             self.cms[whicharm].command_joint_trajectory(trajectory, blocking = 1)
01412             return 1
01413 
01414         return 0
01415 
01416     ##move open-loop through trajectory
01417     ##move open-loop through trajectory
01418     def try_hard_to_move_joint_open_loop(self, whicharm, trajectory):
01419         rospy.loginfo("moving open-loop to desired joint angles")
01420         self.cms[whicharm].command_joint_trajectory(trajectory, blocking = 1)
01421         return 1
01422 
01423     ##try to move to a pose using move_arm, ignoring current collisions if necessary, and if that fails, 
01424     #move open-loop (either to the IK solution if there is one, or using the Cartesian controllers if there isn't)
01425     def try_hard_to_move_pose(self, whicharm, pose_stamped, max_tries = 3, use_joint_open_loop = 0, use_cartesian = 0, try_constrained = 0):
01426         current_angles = self.cms[whicharm].get_current_arm_angles()
01427         start_angles = current_angles
01428         ik_solution = None
01429 
01430         #try max_tries times to make move_arm get us there
01431         for tries in range(max_tries):
01432             rospy.loginfo("try_hard_to_move_pose try number: %d"%tries)
01433 
01434             #look for a collision-free IK solution at the goal
01435             (solution, error_code) = self.cms[whicharm].ik_utilities.run_ik(pose_stamped, start_angles, \
01436                     self.cms[whicharm].ik_utilities.link_name)
01437             if solution:
01438                 ik_solution = solution
01439             else:
01440                 start_angles = self.cms[whicharm].ik_utilities.start_angles_list[tries]
01441                 continue
01442 
01443 #             #try to keep the gripper approximately level while moving
01444 #             if try_constrained:
01445 #                 location = get_xyz(pose_stamped.pose.position)
01446 #                 result = self.try_to_move_constrained(whicharm, 2, solution, location)
01447 #                 if result == 1:
01448 #                     return 1
01449 
01450             #having found IK goal angles that are not in collision, try hard to get there
01451             success = self.try_hard_to_move_joint(whicharm, [solution,], 2, use_open_loop = 0)
01452             if success:
01453                 rospy.loginfo("try_hard_to_move_joint reported success")
01454                 return 1
01455             rospy.loginfo("try_hard_to_move_joint reported failure")
01456             start_angles = self.cms[whicharm].ik_utilities.start_angles_list[tries]
01457 
01458         #if we found an IK solution, move there open-loop, going to arm_above_and_to_side angles first
01459         if ik_solution and use_joint_open_loop:
01460             rospy.loginfo("ran out of try_hard_to_move_joint tries using move_arm, moving to the joint angles open-loop")
01461             self.cms[whicharm].command_joint_trajectory([self.arm_above_and_to_side_angles[whicharm], ik_solution], blocking = 1)
01462             return 1
01463 
01464         #no collision-free ik solution available, either use the Cartesian controllers or just return
01465         if use_cartesian:
01466             rospy.logerr("no IK solution found for goal pose!  Using Cartesian controllers to move")
01467             self.cms[whicharm].move_cartesian(pose_stamped, settling_time = rospy.Duration(10))
01468 
01469         return 0
01470 
01471 
01472     ##move to a nearby Cartesian pose using the Cartesian controllers
01473     def move_cartesian_step(self, whicharm, pose, timeout = 10.0, settling_time = 3.0, blocking = 0):
01474         if type(pose) == list:
01475             pose = create_pose_stamped(pose, 'base_link')
01476         self.cms[whicharm].move_cartesian(pose, blocking = blocking, \
01477                                    pos_thres = .0025, rot_thres = .05, \
01478                                    timeout = rospy.Duration(timeout), \
01479                                    settling_time = rospy.Duration(settling_time))
01480 
01481 
01482     ##is an object in the hand? (is the gripper not closed all the way?)
01483     def check_grasp_successful(self, whicharm, min_gripper_opening = .0021, max_gripper_opening = .1):
01484         gripper_opening = self.cms[whicharm].get_current_gripper_opening()
01485         if gripper_opening > min_gripper_opening and gripper_opening < max_gripper_opening:
01486             rospy.loginfo("gripper opening acceptable: %5.3f"%gripper_opening)
01487             return 1
01488         rospy.loginfo("gripper opening unacceptable: %5.3f"%gripper_opening)
01489         return 0
01490 
01491 
01492     ##detect objects and try to pick up the nearest one
01493     def detect_and_pick_up_object(self, point_head_loc, frame = 'base_link', arms_to_try = [0,1]):
01494 
01495         #point the head at the desired location
01496         self.point_head(point_head_loc, frame)
01497 
01498         self.check_preempted()
01499 
01500         #detect objects and clear out extra collision points
01501         self.call_tabletop_detection(take_static_collision_map = 1, update_table = 0, clear_attached_objects = 1)
01502 
01503         #no objects left!  Quit
01504         if self.count_objects() == 0:
01505             rospy.loginfo("no objects in view!")
01506             return ("no objects left", None)
01507 
01508         self.check_preempted()
01509 
01510         #try to pick up the nearest object
01511         (success, arm_used) = self.pick_up_nearest_object(arms_to_try = arms_to_try)
01512 
01513         #succeeded, move the arm out of the way with the object
01514         if success:
01515             self.move_arm_out_of_way(arm_used, try_constrained = 1)
01516             return ("succeeded", arm_used)
01517         else:
01518             return ("grasp failed", None)
01519 
01520 
01521     ##how many relevant objects did we detect?  
01522     def count_objects(self):
01523         return len(self.detected_objects)
01524 
01525 
01526 
01527     ##try to move to a location while constraining the gripper to remain approximately level
01528     def try_to_move_constrained(self, whicharm, max_tries = 3, start_angles = None, location = None):
01529         reset_collision_map = 0
01530         for tries in range(max_tries):
01531             rospy.loginfo("constrained move try number: %d"%tries)
01532             error_code = self.cms[whicharm].move_arm_constrained(start_angles, location)
01533             if error_code == 1:
01534                 rospy.loginfo("move arm constrained reported success")
01535                 return 1
01536             rospy.loginfo("move arm constrained reports failure with error code %d"%error_code)
01537         return 0
01538 
01539 
01540     ##move whicharm off to the side
01541     def move_arm_to_side(self, whicharm, try_constrained = 0):
01542 
01543 #         #trying to keep the gripper orientation approximately level
01544 #         if try_constrained:
01545 #             result = self.try_to_move_constrained(whicharm)
01546 #             if result == 1:
01547 #                 return 1
01548 
01549         #either constrained move didn't work or we didn't request a constrained move
01550         result = self.try_hard_to_move_joint(whicharm, [self.arm_above_and_to_side_angles[whicharm], \
01551                                                    self.arm_to_side_angles[whicharm]], use_open_loop = 1)
01552         return result
01553 
01554 
01555     def move_arm_out_of_way(self, whicharm, try_constrained = 0):
01556 
01557         #either constrained move didn't work or we didn't request a constrained move
01558         result = self.try_hard_to_move_joint(whicharm, [self.arm_above_and_out_of_way[whicharm]], use_open_loop = 1)
01559         return result
01560 
01561 
01562 
01563     ##move whicharm off to the side open-loop
01564     def move_arm_to_side_open_loop(self, whicharm, try_constrained = 0):
01565         
01566         result = self.try_hard_to_move_joint_open_loop(whicharm, [self.arm_above_and_to_side_angles[whicharm], \
01567                                                                       self.arm_to_side_angles[whicharm]])
01568         return result
01569 
01570 
01571     ##pick up the object nearest to a PointStamped with whicharm (0=right, 1=left)
01572     def pick_up_object_near_point(self, point_stamped, whicharm):
01573 
01574         #convert point to base_link frame
01575         base_link_point = point_stamped_to_list(self.tf_listener, point_stamped, 'base_link')
01576 
01577         #find the closest object
01578         nearest_dist = 1e6
01579         nearest_object_ind = None
01580         for (ind, object) in enumerate(self.detected_objects):
01581             (object_point, object_rot) = pose_stamped_to_lists(self.tf_listener, object.pose, 'base_link')
01582             dist = sum([(x-y)**2 for (x,y) in list(zip(object_point, base_link_point))])**.5
01583             rospy.loginfo("dist: %0.3f"%dist)
01584             if dist < nearest_dist:
01585                 nearest_dist = dist
01586                 nearest_object_ind = ind
01587 
01588         if nearest_object_ind != None:
01589             rospy.loginfo("nearest object ind: %d"%nearest_object_ind)
01590         else:
01591             rospy.logerr('No nearby objects. Unable to select grasp target')
01592             return 0
01593 
01594         #refine the view of the object if it's too far from the narrow stereo center
01595         object_to_grasp = self.refine_if_not_centered(self.detected_objects[nearest_object_ind])
01596         
01597         #try to pick it up with the requested arm
01598         (result, arm_used) = self.grasp_object_and_check_success(object_to_grasp, whicharm)
01599 
01600         if result == "succeeded":
01601             return 1
01602         elif result == "attempt failed":
01603             return 0
01604 
01605         #if we didn't succeed but didn't try to grasp, just continue
01606         elif result == "no feasible grasp":
01607             rospy.loginfo("no feasible grasp for this object with the %s arm"%self.arm_dict[whicharm])
01608             return 0
01609 
01610 
01611     ##print the list of possible objects to grasp
01612     def print_object_list(self):
01613 
01614         #draw colors on the clusters and objects so we know which one is which, and print out the list of objects and their colors
01615         colors = [[1,0,0],
01616                   [0,1,0],
01617                   [0,0,1],
01618                   [0,1,1],
01619                   [1,0,1],
01620                   [1,1,0],
01621                   [1, 1, 1],
01622                   [.5, .5, .5],
01623                   [0, 0, 0]]
01624         colornames = ["red", "green", "blue", "cyan", "magenta", "yellow", "white", "grey", "black"]
01625 
01626         self.draw_functions.clear_rviz_points('grasp_markers')
01627         color_ind = 0
01628         for (ind, object) in enumerate(self.detected_objects):
01629 
01630             self.draw_object_pose(object, object.pose, colors[color_ind], ind)
01631             if object.object.type == 1:
01632                 rospy.loginfo("object %d, %s: recognized object with id %d"%(ind, colornames[ind], object.object.model_pose.model_id))
01633             else:
01634                 rospy.loginfo("object %d, %s: point cluster with %d points"%(ind, colornames[ind], len(object.object.cluster.points)))
01635 #                 points = self.point_cloud_to_mat(cluster)
01636 #                 self.draw_functions.draw_rviz_points(points, color = colors[color_ind], duration = 0., id = ind)
01637 #                 time.sleep(.05) 
01638                 
01639             color_ind = (color_ind + 1) % len(colors)
01640 
01641 
01642     ##check for a preempt request (overload this for your application)
01643     def check_preempted(self):
01644         pass
01645 
01646 
01647     ##saw a serious error (problem with service call), overload this for your application
01648     def throw_exception(self):
01649         pass
01650 
01651 
01652     ##pause for input
01653     def keypause(self):
01654         print "press enter to continue"
01655         input = raw_input()
01656         return input
01657 
01658 
01659     ##get the number of an object to pick up from the user
01660     def input_object_num(self):
01661 
01662         if not self.detected_objects:
01663             print "no objects detected!"
01664             return -1
01665 
01666         print "which object number?"
01667         input = self.keypause()
01668         try:
01669             object_ind = int(input)
01670         except:
01671             print "bad input: ", input
01672             return -1
01673 
01674         if object_ind > len(self.detected_objects):
01675             print "object number too high"
01676             return -1
01677 
01678         return object_ind
01679 
01680 
01681     ##get which arm/side to use from the user
01682     def input_side(self):
01683         c = raw_input()
01684         if c != 'r' and c != 'l' and c != 'c':
01685             print "bad input: %s"%c
01686             return -1
01687         if c == 'r':
01688             whicharm = 0
01689             print "using right side"
01690         elif c == 'l':
01691             whicharm = 1
01692             print "using left side"
01693         else:
01694             whicharm = None
01695             print "letting the robot choose"
01696         return whicharm
01697 
01698 
01699     ##return the current pos and rot of the wrist for whicharm as a 7-list (pos, quaternion rot)
01700     def return_current_pose_as_list(self, whicharm):
01701         (pos, rot) = self.cms[whicharm].return_cartesian_pose()        
01702         return pos+rot
01703 
01704 
01705     ##print instructions for using extensions to the keyboard interface here
01706     def print_keyboard_extensions(self):
01707         print "pr, pl, or pc to change the place rectangle to be on the robot's right/left/center"
01708 
01709 
01710     ##add extensions to the keyboard interface here, return 1 to continue and 0 to go on down the possibilities
01711     def keyboard_extensions(self, input):
01712         if input == 'pr' or input == 'pl' or input == 'pc':
01713             y = 0
01714             if input == 'pr':
01715                 y = -.3
01716             elif input == 'pl':
01717                 y = .3
01718 
01719             self.place_rect_dims = [.3, .3]
01720             place_rect_pose_mat = scipy.matrix([[1.,0.,0.,self.table_front_edge_x+self.place_rect_dims[0]/2.+.1],
01721                                                 [0.,1.,0.,y],
01722                                                 [0.,0.,1.,self.table_height],
01723                                                 [0.,0.,0.,1.]])
01724             self.place_rect_pose_stamped = stamp_pose(mat_to_pose(place_rect_pose_mat), 'base_link')
01725             self.draw_place_area()
01726 
01727         return 0
01728 
01729 
01730     ##keyboard interface for starting up the demo and overriding with manual commands
01731     def keyboard_interface(self):
01732 
01733         #set the current positions of the wrists as the current 'goals' relative to which Cartesian movements are expressed
01734         currentgoals = [0]*2
01735         for i in range(2):
01736             currentgoals[i] = self.return_current_pose_as_list(i)
01737 
01738         #keyboard loop
01739         while not rospy.is_shutdown():
01740 
01741             print "type:"
01742             self.print_keyboard_extensions()
01743             print "r to control the right arm, l to control the left arm"
01744             print "d to detect objects, dc to detect and take a new static collision map, dca to detect, take a new collision map, and clear attached objects"
01745             print "p to pick up an object"
01746             print "w to place the object in the place rectangle, wo to place the object where it came from"
01747             print "h to point the head at the current place rectangle and draw it"
01748             print "t to find the table"
01749             print "rm to reset the collision map, tm to take a new collision map"
01750             print "det to detach the object in the gripper"
01751             print "q to quit"
01752 
01753             input = self.keypause()
01754 
01755             #extensions to the interface get checked for here
01756             cont = self.keyboard_extensions(input)
01757             if cont:
01758                 continue
01759 
01760             #detect objects
01761             if input == 'd':
01762                 rospy.loginfo("detecting objects")
01763                 self.call_tabletop_detection(take_static_collision_map = 0, update_table = 0, clear_attached_objects = 0)
01764             elif input == 'dc':
01765                 rospy.loginfo("detecting objects and taking a new static collision map")
01766                 self.call_tabletop_detection(take_static_collision_map = 1, update_table = 0, clear_attached_objects = 0)
01767             elif input == 'dca':
01768                 rospy.loginfo("detecting objects, taking a new static collision map, and clearing attached objects")
01769                 self.call_tabletop_detection(take_static_collision_map = 1, update_table = 0, clear_attached_objects = 1)
01770 
01771             #pick up an object
01772             elif input == 'p':
01773 
01774                 self.print_object_list()
01775                 object_num = self.input_object_num()
01776                 if object_num == -1:
01777                     continue
01778 
01779                 print "which arm?  r for right, l for left, c to let the robot choose"
01780                 whicharm = self.input_side()
01781 
01782                 if whicharm == 0 or whicharm == 1:
01783                     (result, arm_used) = self.grasp_object_and_check_success(self.detected_objects[object_num], whicharm)
01784 
01785             #put down an object where it was originally picked up
01786             elif input == 'w' or input == 'wo':
01787 
01788                 #if only one arm is holding the object, that's the one we mean
01789                 if not any(self.held_objects):
01790                     print "the robot doesn't think it's holding any objects!\nPick an arm to do an open-loop place anyway: r for right and l for left"
01791                 if self.held_objects[0] and not self.held_objects[1]:
01792                     whicharm = 0
01793                     print "only holding an object in the right arm, dropping the right arm object"
01794                 elif self.held_objects[1] and not self.held_objects[0]:
01795                     whicharm = 1
01796                     print "only holding an object in the left arm, dropping the left arm object"
01797                 else:
01798                     print "which arm?  r for right and l for left"
01799                     whicharm = self.input_side()
01800 
01801                 if input == 'wo':
01802                     if not self.held_objects[whicharm]:
01803                         print "no recorded pose for an object in that gripper!"
01804                         continue
01805                     self.place_object(whicharm, self.held_objects[whicharm].pose)
01806                 else:
01807                     self.put_down_object(whicharm, use_place_override = 1)
01808 
01809             #point the head at the current place location
01810             elif input == 'h':
01811                 rospy.loginfo("pointing the head at the current place location and drawing the place area")
01812                 self.point_head_at_place_rect()
01813                 self.draw_place_area()
01814 
01815             #find the table
01816             elif input == 't':
01817                 rospy.loginfo("finding the table")
01818                 self.find_table()
01819 
01820             #move an arm
01821             elif input == 'r' or input == 'l':
01822                 if input == 'r':
01823                     whicharm = 0
01824                 else:
01825                     whicharm = 1
01826 
01827                 while not rospy.is_shutdown():
01828                     print "c to close, o to open the gripper"
01829                     print "u to go up, d to go down, rt to go right, lt to go left"
01830                     print "ay to go away from the robot, td to go toward the robot"
01831                     print "jm to go to arm-away-on-the-side angles using move_arm"
01832                     print "jc to go to arm-away-on-the-side angles while trying to constrain the pose"
01833                     print "j to go to arm-away-on-the-side angles open-loop using the joint trajectory action"
01834                     print "e to exit the arm-control menu for this arm (%s)"%input
01835                     c = self.keypause()
01836 
01837                     if c == 'c':
01838                         self.close_gripper(whicharm)
01839                     elif c == 'o':
01840                         self.open_gripper(whicharm)
01841                         if self.held_objects[whicharm]:
01842                             self.detach_object(whicharm)
01843                             self.held_objects[whicharm] = 0
01844 
01845                     elif c == 'jm':
01846                         #try moving collision-free using move_arm
01847                         self.move_arm_to_side(whicharm)
01848                         currentgoals[whicharm] = self.return_current_pose_as_list(whicharm)
01849 
01850                     elif c == 'jc':
01851                         #try moving collision-free using move_arm, keeping the pose constrained
01852                         self.move_arm_to_side(whicharm, try_constrained = 1)
01853                         currentgoals[whicharm] = self.return_current_pose_as_list(whicharm)
01854 
01855                     elif c == 'j':
01856                         #just move the arm open-loop
01857                         self.cms[whicharm].command_joint_trajectory([self.arm_above_and_to_side_angles[whicharm], self.arm_to_side_angles[whicharm]], blocking = 1)
01858                         currentgoals[whicharm] = self.return_current_pose_as_list(whicharm)
01859 
01860                     elif c == 'j2':
01861                         self.cms[whicharm].command_joint_trajectory([self.arm_to_side_angles[whicharm],], blocking = 1)
01862                         currentgoals[whicharm] = self.return_current_pose_as_list(whicharm)
01863 
01864                     elif c == 'u':
01865                         print "going up"
01866                         currentgoals[whicharm][2] += .1
01867                         self.move_cartesian_step(whicharm, currentgoals[whicharm], blocking = 1)
01868                     elif c == 'us':
01869                         print "going up a small amount"
01870                         currentgoals[whicharm][2] += .02
01871                         self.move_cartesian_step(whicharm, currentgoals[whicharm], blocking = 1)
01872                     elif c == 'd':
01873                         print "going down"
01874                         currentgoals[whicharm][2] -= .1
01875                         self.move_cartesian_step(whicharm, currentgoals[whicharm], blocking = 1)
01876                     elif c == 'ds':
01877                         print "going down a small amount"
01878                         currentgoals[whicharm][2] -= .02
01879                         self.move_cartesian_step(whicharm, currentgoals[whicharm], blocking = 1)
01880                     elif c == 'rt':
01881                         print "moving right"
01882                         currentgoals[whicharm][1] -= .02
01883                         self.move_cartesian_step(whicharm, currentgoals[whicharm], blocking = 1)
01884                     elif c == 'lt':
01885                         print "moving left"
01886                         currentgoals[whicharm][1] += .02
01887                         self.move_cartesian_step(whicharm, currentgoals[whicharm], blocking = 1)
01888                     elif c == 'ay':
01889                         print "moving away from robot"
01890                         currentgoals[whicharm][0] += .02
01891                         self.move_cartesian_step(whicharm, currentgoals[whicharm], blocking = 1)
01892                     elif c == 'td':
01893                         print "moving toward the robot"
01894                         currentgoals[whicharm][0] -= .02
01895                         self.move_cartesian_step(whicharm, currentgoals[whicharm], blocking = 1)
01896 
01897                     elif c == 'e':
01898                         break
01899 
01900 
01901             elif input == 'rm':
01902                 rospy.loginfo("resetting the collision map")
01903                 self.reset_collision_map()
01904 
01905             elif input == 'tm':
01906                 rospy.loginfo("taking a new collision map")
01907                 self.take_static_map()
01908 
01909             elif input == 'det':
01910                 print "detach the object in which gripper?  r for right and l for left"
01911                 whicharm = self.input_side()
01912                 if whicharm != None:
01913                     self.detach_object(whicharm)  
01914 
01915             elif input == 'q':
01916                 return
01917 
01918 
01919             #update the current arm goals after each action
01920             for i in range(2):
01921                 currentgoals[i] = self.return_current_pose_as_list(i)
01922 
01923 
01924 if __name__ == '__main__':
01925 
01926     rospy.init_node('pick_and_place_manager', anonymous=True)
01927     pick_and_place_manager = PickAndPlaceManager()
01928     pick_and_place_manager.keyboard_interface()


pr2_playpen
Author(s): Marc Killpack / mkillpack3@gatech.edu, Advisor: Prof. Charlie Kemp, Lab: Healthcare Robotics Lab at Georgia Tech
autogenerated on Wed Nov 27 2013 12:18:32