00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "object_manipulator/grasp_execution/reactive_grasp_executor.h"
00037
00038 #include <object_manipulation_msgs/ReactiveGrasp.h>
00039
00040
00041
00042 #include "object_manipulator/tools/hand_description.h"
00043 #include "object_manipulator/tools/vector_tools.h"
00044
00045 using object_manipulation_msgs::GraspResult;
00046
00047 namespace object_manipulator {
00048
00049 GraspResult
00050 ReactiveGraspExecutor::executeGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal,
00051 const object_manipulation_msgs::Grasp &grasp)
00052 {
00053
00054
00055
00056 if ( !mechInterface().attemptMoveArmToGoal(pickup_goal.arm_name,
00057 interpolated_grasp_trajectory_.points.front().positions,
00058 pickup_goal.additional_collision_operations,
00059 pickup_goal.additional_link_padding) )
00060 {
00061 ROS_DEBUG(" Grasp executor: move_arm to pre-grasp reports failure");
00062 if (marker_publisher_) marker_publisher_->colorGraspMarker(marker_id_, 1.0, 0.5, 0.0);
00063 return Result(GraspResult::MOVE_ARM_FAILED, true);
00064 }
00065
00066 mechInterface().handPostureGraspAction(pickup_goal.arm_name, grasp,
00067 object_manipulation_msgs::GraspHandPostureExecutionGoal::PRE_GRASP);
00068
00069 geometry_msgs::PoseStamped final_grasp_pose_stamped;
00070 final_grasp_pose_stamped.pose = grasp.grasp_pose;
00071 final_grasp_pose_stamped.header.frame_id = pickup_goal.target.reference_frame_id;
00072 final_grasp_pose_stamped.header.stamp = ros::Time(0);
00073
00074 object_manipulation_msgs::ReactiveGraspGoal reactive_grasp_goal;
00075 reactive_grasp_goal.arm_name = pickup_goal.arm_name;
00076 reactive_grasp_goal.target = pickup_goal.target;
00077 reactive_grasp_goal.final_grasp_pose = final_grasp_pose_stamped;
00078 reactive_grasp_goal.trajectory = interpolated_grasp_trajectory_;
00079 reactive_grasp_goal.collision_support_surface_name = pickup_goal.collision_support_surface_name;
00080 reactive_grasp_goal.pre_grasp_posture = grasp.pre_grasp_posture;
00081 reactive_grasp_goal.grasp_posture = grasp.grasp_posture;
00082
00083
00084
00085
00086
00087 ros::Duration timeout = ros::Duration(180.0);
00088 mechInterface().reactive_grasp_action_client_.client(pickup_goal.arm_name).sendGoal(reactive_grasp_goal);
00089 if ( !mechInterface().reactive_grasp_action_client_.client(pickup_goal.arm_name).waitForResult(timeout) )
00090 {
00091 ROS_ERROR(" Reactive grasp timed out");
00092 return Result(GraspResult::GRASP_FAILED, false);
00093 }
00094 object_manipulation_msgs::ReactiveGraspResult reactive_grasp_result =
00095 *mechInterface().reactive_grasp_action_client_.client(pickup_goal.arm_name).getResult();
00096 if (reactive_grasp_result.manipulation_result.value != reactive_grasp_result.manipulation_result.SUCCESS)
00097 {
00098 ROS_ERROR("Reactive grasp failed with error code %d", reactive_grasp_result.manipulation_result.value);
00099 return Result(GraspResult::GRASP_FAILED, false);
00100 }
00101 if (marker_publisher_) marker_publisher_->colorGraspMarker(marker_id_, 0.0, 1.0, 0.0);
00102 return Result(GraspResult::SUCCESS, true);
00103 }
00104
00105 GraspResult
00106 ReactiveGraspExecutor::nonReactiveLift(const object_manipulation_msgs::PickupGoal &pickup_goal)
00107 {
00108 motion_planning_msgs::OrderedCollisionOperations ord;
00109 motion_planning_msgs::CollisionOperation coll;
00110
00111 coll.object1 = handDescription().gripperCollisionName(pickup_goal.arm_name);
00112 coll.object2 = pickup_goal.collision_support_surface_name;
00113 coll.operation = motion_planning_msgs::CollisionOperation::DISABLE;
00114 ord.collision_operations.push_back(coll);
00115
00116 coll.object1 = pickup_goal.collision_object_name;
00117 coll.object2 = pickup_goal.collision_support_surface_name;
00118 ord.collision_operations.push_back(coll);
00119 ord.collision_operations = concat(ord.collision_operations,
00120 pickup_goal.additional_collision_operations.collision_operations);
00121
00122 float actual_distance;
00123 if (!mechInterface().translateGripper(pickup_goal.arm_name,
00124 pickup_goal.lift.direction,
00125 ord, pickup_goal.additional_link_padding,
00126 pickup_goal.lift.desired_distance, 0.0, actual_distance))
00127 {
00128 ROS_DEBUG(" Reactive grasp executor: lift performed no steps");
00129 return Result(GraspResult::LIFT_FAILED, false);
00130 }
00131 if (actual_distance < pickup_goal.lift.min_distance)
00132 {
00133 ROS_DEBUG(" Reactive grasp executor: lift distance below min threshold ");
00134 return Result(GraspResult::LIFT_FAILED, false);
00135 }
00136 if (actual_distance < pickup_goal.lift.desired_distance)
00137 {
00138 ROS_DEBUG(" Reactive grasp executor: lift distance below desired, but above min threshold");
00139 }
00140 else
00141 {
00142 ROS_DEBUG(" Reactive grasp executor: desired lift distance executed");
00143 }
00144 return Result(GraspResult::SUCCESS, true);
00145 }
00146
00147 GraspResult
00148 ReactiveGraspExecutor::reactiveLift(const object_manipulation_msgs::PickupGoal &pickup_goal)
00149 {
00150 object_manipulation_msgs::ReactiveLiftGoal reactive_lift_goal;
00151 reactive_lift_goal.lift = pickup_goal.lift;
00152 reactive_lift_goal.arm_name = pickup_goal.arm_name;
00153 reactive_lift_goal.target = pickup_goal.target;
00154 reactive_lift_goal.trajectory = interpolated_lift_trajectory_;
00155 reactive_lift_goal.collision_support_surface_name = pickup_goal.collision_support_surface_name;
00156
00157
00158
00159
00160
00161 ros::Duration timeout = ros::Duration(60.0);
00162 mechInterface().reactive_lift_action_client_.client(pickup_goal.arm_name).sendGoal(reactive_lift_goal);
00163 if ( !mechInterface().reactive_lift_action_client_.client(pickup_goal.arm_name).waitForResult(timeout) )
00164 {
00165 ROS_ERROR(" Reactive lift timed out");
00166 return Result(GraspResult::LIFT_FAILED, false);
00167 }
00168 object_manipulation_msgs::ReactiveLiftResult reactive_lift_result =
00169 *mechInterface().reactive_lift_action_client_.client(pickup_goal.arm_name).getResult();
00170 if (reactive_lift_result.manipulation_result.value != reactive_lift_result.manipulation_result.SUCCESS)
00171 {
00172 ROS_ERROR("Reactive lift failed with error code %d", reactive_lift_result.manipulation_result.value);
00173 return Result(GraspResult::LIFT_FAILED, false);
00174 }
00175 return Result(GraspResult::SUCCESS, true);
00176 }
00177
00178 GraspResult
00179 ReactiveGraspExecutor::lift(const object_manipulation_msgs::PickupGoal &pickup_goal)
00180 {
00181 if (pickup_goal.use_reactive_lift)
00182 {
00183 return reactiveLift(pickup_goal);
00184 }
00185 else
00186 {
00187 return nonReactiveLift(pickup_goal);
00188 }
00189 }
00190
00191 }