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 #include "object_manipulator/place_execution/place_executor.h"
00035
00036 #include "object_manipulator/tools/hand_description.h"
00037 #include "object_manipulator/tools/exceptions.h"
00038 #include "object_manipulator/tools/vector_tools.h"
00039
00040
00041
00042 using object_manipulation_msgs::PlaceLocationResult;
00043 using motion_planning_msgs::ArmNavigationErrorCodes;
00044
00045 namespace object_manipulator {
00046
00047 geometry_msgs::PoseStamped PlaceExecutor::computeGripperPose(geometry_msgs::PoseStamped place_location,
00048 geometry_msgs::Pose grasp_pose,
00049 std::string frame_id)
00050 {
00051
00052 tf::Transform place_trans;
00053 tf::poseMsgToTF(place_location.pose, place_trans);
00054 tf::Transform grasp_trans;
00055 tf::poseMsgToTF(grasp_pose, grasp_trans);
00056 grasp_trans = place_trans * grasp_trans;
00057
00058
00059 tf::Stamped<tf::Pose> grasp_trans_stamped;
00060 grasp_trans_stamped.setData(grasp_trans);
00061 grasp_trans_stamped.frame_id_ = place_location.header.frame_id;
00062 grasp_trans_stamped.stamp_ = ros::Time::now();
00063 if (!listener_.waitForTransform(frame_id, place_location.header.frame_id, ros::Time::now(), ros::Duration(1.0)))
00064 {
00065 ROS_ERROR("Object place: tf does not have transform from %s to %s",
00066 place_location.header.frame_id.c_str(),
00067 frame_id.c_str());
00068 throw MechanismException( std::string("Object place: tf does not have transform from ") +
00069 place_location.header.frame_id.c_str() + std::string(" to ") +
00070 frame_id);
00071 }
00072 tf::Stamped<tf::Pose> grasp_trans_base;
00073 try
00074 {
00075 listener_.transformPose( frame_id, grasp_trans_stamped, grasp_trans_base);
00076 }
00077 catch (tf::TransformException ex)
00078 {
00079 ROS_ERROR("Object place: tf failed to transform gripper pose into frame %s; exception: %s",
00080 frame_id.c_str(), ex.what());
00081 throw MechanismException( std::string("tf failed to transform gripper pose into frame ") +
00082 frame_id + std::string("; tf exception: ") +
00083 std::string(ex.what()) );
00084 }
00085
00086 geometry_msgs::PoseStamped gripper_pose;
00087 tf::poseTFToMsg(grasp_trans_base, gripper_pose.pose);
00088 gripper_pose.header.frame_id = frame_id;
00089 gripper_pose.header.stamp = ros::Time::now();
00090 return gripper_pose;
00091 }
00092
00107 PlaceLocationResult PlaceExecutor::retreat(const object_manipulation_msgs::PlaceGoal &place_goal)
00108 {
00109 motion_planning_msgs::OrderedCollisionOperations ord;
00110 motion_planning_msgs::CollisionOperation coll;
00111
00112 coll.object1 = handDescription().gripperCollisionName(place_goal.arm_name);
00113 coll.object2 = place_goal.collision_object_name;
00114 coll.operation = motion_planning_msgs::CollisionOperation::DISABLE;
00115 ord.collision_operations.push_back(coll);
00116
00117 coll.object2 = place_goal.collision_support_surface_name;
00118 ord.collision_operations.push_back(coll);
00119 ord.collision_operations = concat(ord.collision_operations,
00120 place_goal.additional_collision_operations.collision_operations);
00121
00122
00123 std::vector<motion_planning_msgs::LinkPadding> link_padding
00124 = concat(MechanismInterface::fingertipPadding(place_goal.arm_name, 0.0),
00125 place_goal.additional_link_padding);
00126
00127 geometry_msgs::Vector3Stamped direction;
00128 direction.header.stamp = ros::Time::now();
00129 direction.header.frame_id = handDescription().gripperFrame(place_goal.arm_name);
00130 direction.vector = mechInterface().negate( handDescription().approachDirection(place_goal.arm_name) );
00131
00132 float actual_distance;
00133 mechInterface().translateGripper(place_goal.arm_name,
00134 direction,
00135 ord, link_padding,
00136 place_goal.desired_retreat_distance, 0, actual_distance);
00137 if (actual_distance < place_goal.min_retreat_distance)
00138 {
00139 ROS_DEBUG("Object place: retreat incomplete (%f executed and %f desired)",
00140 actual_distance, place_goal.min_retreat_distance);
00141 return Result(PlaceLocationResult::RETREAT_FAILED, false);
00142 }
00143
00144 return Result(PlaceLocationResult::SUCCESS, true);
00145 }
00146
00147 PlaceLocationResult
00148 PlaceExecutor::prepareInterpolatedTrajectories(const object_manipulation_msgs::PlaceGoal &place_goal,
00149 const geometry_msgs::PoseStamped &place_location)
00150 {
00151
00152 geometry_msgs::PoseStamped gripper_place_pose = computeGripperPose(place_location,
00153 place_goal.grasp.grasp_pose,
00154 handDescription().robotFrame(place_goal.arm_name));
00155
00156 if (marker_publisher_)
00157 {
00158 if (marker_id_ < 0)
00159 {
00160 marker_id_ = marker_publisher_->addGraspMarker(gripper_place_pose);
00161 marker_publisher_->colorGraspMarker(marker_id_, 1.0, 0.0, 1.0);
00162 }
00163 else
00164 {
00165 marker_publisher_->setMarkerPose(marker_id_, gripper_place_pose);
00166 }
00167 }
00168
00169
00170 motion_planning_msgs::OrderedCollisionOperations ord;
00171 motion_planning_msgs::CollisionOperation coll;
00172 coll.object1 = place_goal.collision_object_name;
00173 coll.object2 = place_goal.collision_support_surface_name;
00174 coll.operation = motion_planning_msgs::CollisionOperation::DISABLE;
00175 ord.collision_operations.push_back(coll);
00176 if (place_goal.allow_gripper_support_collision)
00177 {
00178 coll.object1 = handDescription().gripperCollisionName(place_goal.arm_name);
00179 coll.object2 = place_goal.collision_support_surface_name;
00180 ord.collision_operations.push_back(coll);
00181 }
00182 ord.collision_operations = concat(ord.collision_operations,
00183 place_goal.additional_collision_operations.collision_operations);
00184
00185
00186 std::vector<motion_planning_msgs::LinkPadding> link_padding =
00187 MechanismInterface::fingertipPadding(place_goal.arm_name, 0.0);
00188
00189 motion_planning_msgs::LinkPadding padding;
00190 padding.link_name = handDescription().attachedName(place_goal.arm_name);
00191 padding.padding = place_goal.place_padding;
00192 link_padding.push_back(padding);
00193 link_padding = concat(link_padding, place_goal.additional_link_padding);
00194
00195 geometry_msgs::Vector3Stamped place_direction;
00196 place_direction.header.frame_id = place_goal.approach.direction.header.frame_id;
00197 place_direction.header.stamp = ros::Time::now();
00198 place_direction.vector = mechInterface().negate(place_goal.approach.direction.vector);
00199
00200
00201 std::vector<double> empty;
00202 float actual_distance;
00203 int error_code = mechInterface().getInterpolatedIK(place_goal.arm_name,
00204 gripper_place_pose, place_direction,
00205 place_goal.approach.desired_distance,
00206 empty,
00207 place_goal.grasp.grasp_posture,
00208 ord, link_padding,
00209 true, place_trajectory_, actual_distance);
00210 ROS_DEBUG(" Place trajectory: actual(%f), min(%f), desired (%f)",
00211 actual_distance, place_goal.approach.min_distance, place_goal.approach.desired_distance);
00212
00213 if (actual_distance < place_goal.approach.min_distance)
00214 {
00215 ROS_DEBUG("Place trajectory below min. threshold");
00216 if (place_trajectory_.points.empty())
00217 {
00218 ROS_DEBUG("Place trajectory empty; problem is with place location");
00219 if (error_code == ArmNavigationErrorCodes::COLLISION_CONSTRAINTS_VIOLATED)
00220 return Result(PlaceLocationResult::PLACE_IN_COLLISION, true);
00221 else if (error_code == ArmNavigationErrorCodes::JOINT_LIMITS_VIOLATED)
00222 return Result(PlaceLocationResult::PLACE_OUT_OF_REACH, true);
00223 else return Result(PlaceLocationResult::PLACE_UNFEASIBLE, true);
00224 }
00225 if (error_code == ArmNavigationErrorCodes::COLLISION_CONSTRAINTS_VIOLATED)
00226 return Result(PlaceLocationResult::PREPLACE_IN_COLLISION, true);
00227 else if (error_code == ArmNavigationErrorCodes::JOINT_LIMITS_VIOLATED)
00228 return Result(PlaceLocationResult::PREPLACE_OUT_OF_REACH, true);
00229 else return Result(PlaceLocationResult::PREPLACE_UNFEASIBLE, true);
00230 }
00231
00232
00233
00234 if ( !mechInterface().checkStateValidity(place_goal.arm_name, place_trajectory_.points.front().positions,
00235 place_goal.additional_collision_operations,
00236 place_goal.additional_link_padding) )
00237 {
00238 ROS_DEBUG("First pose in place trajectory is unfeasible with default padding");
00239 return Result(PlaceLocationResult::PREPLACE_UNFEASIBLE, true);
00240 }
00241
00242
00243
00244 coll.object1 = place_goal.collision_object_name;
00245 coll.object2 = coll.COLLISION_SET_ALL;
00246 coll.operation = motion_planning_msgs::CollisionOperation::DISABLE;
00247 ord.collision_operations.clear();
00248 ord.collision_operations.push_back(coll);
00249 if (place_goal.allow_gripper_support_collision)
00250 {
00251 coll.object1 = handDescription().gripperCollisionName(place_goal.arm_name);
00252 coll.object2 = place_goal.collision_support_surface_name;
00253 ord.collision_operations.push_back(coll);
00254 }
00255 ord.collision_operations = concat(ord.collision_operations,
00256 place_goal.additional_collision_operations.collision_operations);
00257
00258 geometry_msgs::Vector3Stamped retreat_direction;
00259 retreat_direction.header.stamp = ros::Time::now();
00260 retreat_direction.header.frame_id = handDescription().gripperFrame(place_goal.arm_name);
00261 retreat_direction.vector = mechInterface().negate( handDescription().approachDirection(place_goal.arm_name) );
00262
00263
00264 std::vector<double> place_joint_angles = place_trajectory_.points.back().positions;
00265 mechInterface().getInterpolatedIK(place_goal.arm_name,
00266 gripper_place_pose, retreat_direction,
00267 place_goal.desired_retreat_distance,
00268 place_joint_angles,
00269 place_goal.grasp.pre_grasp_posture,
00270 ord, link_padding,
00271 false, retreat_trajectory_, actual_distance);
00272 ROS_DEBUG("Retreat trajectory: actual (%f), min (%f) and desired (%f)", actual_distance,
00273 place_goal.min_retreat_distance, place_goal.desired_retreat_distance);
00274
00275 if (actual_distance < place_goal.min_retreat_distance)
00276 {
00277 ROS_DEBUG("Retreat trajectory below min. threshold");
00278 if (retreat_trajectory_.points.empty())
00279 {
00280 ROS_DEBUG("Retreat trajectory empty; problem is with place location");
00281 if (error_code == ArmNavigationErrorCodes::COLLISION_CONSTRAINTS_VIOLATED)
00282 return Result(PlaceLocationResult::PLACE_IN_COLLISION, true);
00283 else if (error_code == ArmNavigationErrorCodes::JOINT_LIMITS_VIOLATED)
00284 return Result(PlaceLocationResult::PLACE_OUT_OF_REACH, true);
00285 else return Result(PlaceLocationResult::PLACE_UNFEASIBLE, true);
00286 }
00287 if (error_code == ArmNavigationErrorCodes::COLLISION_CONSTRAINTS_VIOLATED)
00288 return Result(PlaceLocationResult::RETREAT_IN_COLLISION, true);
00289 else if (error_code == ArmNavigationErrorCodes::JOINT_LIMITS_VIOLATED)
00290 return Result(PlaceLocationResult::RETREAT_OUT_OF_REACH, true);
00291 else return Result(PlaceLocationResult::RETREAT_UNFEASIBLE, true);
00292 }
00293
00294 return Result(PlaceLocationResult::SUCCESS, true);
00295 }
00296
00303 PlaceLocationResult
00304 PlaceExecutor::placeApproach(const object_manipulation_msgs::PlaceGoal &place_goal,
00305 const geometry_msgs::PoseStamped&)
00306 {
00307 mechInterface().attemptTrajectory(place_goal.arm_name, place_trajectory_, true);
00308 return Result(PlaceLocationResult::SUCCESS, true);
00309 }
00310
00311
00321 PlaceLocationResult PlaceExecutor::place(const object_manipulation_msgs::PlaceGoal &place_goal,
00322 const geometry_msgs::PoseStamped &place_location)
00323 {
00324
00325
00326
00327 PlaceLocationResult result = prepareInterpolatedTrajectories(place_goal, place_location);
00328 if (result.result_code != PlaceLocationResult::SUCCESS) return result;
00329
00330
00331
00332
00333
00334 bool use_constraints = true;
00335
00336
00337 if(!constraintsUnderstandable(place_goal.path_constraints))
00338 {
00339 ROS_WARN("Constraints passed to place executor are of types not yet handled. Ignoring them.");
00340 use_constraints = false;
00341 }
00342
00343 if (place_goal.path_constraints.orientation_constraints.empty())
00344 {
00345 use_constraints = false;
00346 }
00347
00348 if(use_constraints)
00349 {
00350
00351 geometry_msgs::PoseStamped place_pose;
00352 place_pose.header.frame_id = place_location.header.frame_id;
00353 place_pose.header.stamp = ros::Time(0.0);
00354
00355 if(!mechInterface().getFK(place_goal.arm_name, place_trajectory_.points.front().positions, place_pose))
00356 {
00357 ROS_ERROR("Could not re-compute pre-place pose based on trajectory");
00358 throw MechanismException("Could not re-compute pre-place pose based on trajectory");
00359 }
00360 ROS_DEBUG("Attempting move arm to pre-place with constraints");
00361 if (!mechInterface().moveArmConstrained(place_goal.arm_name, place_pose,
00362 place_goal.additional_collision_operations,
00363 place_goal.additional_link_padding,
00364 place_goal.path_constraints,
00365 place_trajectory_.points.front().positions[2],
00366 false))
00367 {
00368
00369
00370 ROS_WARN("Object place: move_arm to pre-place with constraints failed. Trying again without constraints.");
00371 use_constraints = false;
00372 }
00373 }
00374
00375
00376 if(!use_constraints)
00377 {
00378 ROS_DEBUG("Attempting move arm to pre-place without constraints");
00379 if ( !mechInterface().attemptMoveArmToGoal(place_goal.arm_name, place_trajectory_.points.front().positions,
00380 place_goal.additional_collision_operations,
00381 place_goal.additional_link_padding) )
00382 {
00383 ROS_DEBUG("Object place: move_arm (without constraints) to pre-place reports failure");
00384 return Result(PlaceLocationResult::MOVE_ARM_FAILED, true);
00385 }
00386 }
00387 ROS_DEBUG(" Arm moved to pre-place");
00388
00389
00390
00391
00392 result = placeApproach(place_goal, place_location);
00393 if ( result.result_code != PlaceLocationResult::SUCCESS)
00394 {
00395 ROS_DEBUG(" Pre-place to place approach failed");
00396 return Result(PlaceLocationResult::PLACE_FAILED, false);
00397 }
00398 ROS_DEBUG(" Place trajectory done");
00399
00400 mechInterface().detachAndAddBackObjectsAttachedToGripper(place_goal.arm_name, place_goal.collision_object_name);
00401 ROS_DEBUG(" Object detached");
00402
00403 mechInterface().handPostureGraspAction(place_goal.arm_name, place_goal.grasp,
00404 object_manipulation_msgs::GraspHandPostureExecutionGoal::RELEASE);
00405 ROS_DEBUG(" Object released");
00406
00407 result = retreat(place_goal);
00408 if (result.result_code != PlaceLocationResult::SUCCESS)
00409 {
00410 return Result(PlaceLocationResult::RETREAT_FAILED, false);
00411 }
00412 return Result(PlaceLocationResult::SUCCESS, true);
00413 }
00414
00418 bool PlaceExecutor::constraintsUnderstandable(const motion_planning_msgs::Constraints &constraints)
00419 {
00420 if(constraints.position_constraints.empty() && constraints.orientation_constraints.empty() &&
00421 constraints.joint_constraints.empty() && constraints.visibility_constraints.empty())
00422 return true;
00423 if(constraints.orientation_constraints.size() == 1 && constraints.position_constraints.empty()
00424 && constraints.joint_constraints.empty() && constraints.visibility_constraints.empty())
00425 return true;
00426 return false;
00427 }
00428
00429 PlaceLocationResult
00430 ReactivePlaceExecutor::placeApproach(const object_manipulation_msgs::PlaceGoal &place_goal,
00431 const geometry_msgs::PoseStamped &place_location)
00432 {
00433
00434 geometry_msgs::PoseStamped gripper_place_pose = computeGripperPose(place_location,
00435 place_goal.grasp.grasp_pose,
00436 handDescription().robotFrame(place_goal.arm_name));
00437
00438
00439 object_manipulation_msgs::ReactivePlaceGoal reactive_place_goal;
00440 reactive_place_goal.arm_name = place_goal.arm_name;
00441 reactive_place_goal.collision_object_name = place_goal.collision_object_name;
00442 reactive_place_goal.collision_support_surface_name = place_goal.collision_support_surface_name;
00443 reactive_place_goal.trajectory = place_trajectory_;
00444 reactive_place_goal.final_place_pose = gripper_place_pose;
00445
00446
00447 ros::Duration timeout = ros::Duration(60.0);
00448 ROS_DEBUG(" Calling the reactive place action");
00449 mechInterface().reactive_place_action_client_.client(place_goal.arm_name).sendGoal(reactive_place_goal);
00450 if ( !mechInterface().reactive_place_action_client_.client(place_goal.arm_name).waitForResult(timeout) )
00451 {
00452 ROS_ERROR(" Reactive place timed out");
00453 return Result(PlaceLocationResult::PLACE_FAILED, false);
00454 }
00455 object_manipulation_msgs::ReactivePlaceResult reactive_place_result =
00456 *mechInterface().reactive_place_action_client_.client(place_goal.arm_name).getResult();
00457 if (reactive_place_result.manipulation_result.value != reactive_place_result.manipulation_result.SUCCESS)
00458 {
00459 ROS_ERROR(" Reactive place failed with error code %d", reactive_place_result.manipulation_result.value);
00460 return Result(PlaceLocationResult::PLACE_FAILED, false);
00461 }
00462 ROS_DEBUG(" Reactive place action succeeded");
00463 return Result(PlaceLocationResult::SUCCESS, true);
00464 }
00465
00466 }