place_executor.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 *  Copyright (c) 2009, Willow Garage, Inc.
00004 *  All rights reserved.
00005 *
00006 *  Redistribution and use in source and binary forms, with or without
00007 *  modification, are permitted provided that the following conditions
00008 *  are met:
00009 *
00010 *   * Redistributions of source code must retain the above copyright
00011 *     notice, this list of conditions and the following disclaimer.
00012 *   * Redistributions in binary form must reproduce the above
00013 *     copyright notice, this list of conditions and the following
00014 *     disclaimer in the documentation and/or other materials provided
00015 *     with the distribution.
00016 *   * Neither the name of the Willow Garage nor the names of its
00017 *     contributors may be used to endorse or promote products derived
00018 *     from this software without specific prior written permission.
00019 *
00020 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 *  POSSIBILITY OF SUCH DAMAGE.
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 //#include <demo_synchronizer/synchronizer_client.h>
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   //get the gripper pose relative to place location
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   //get it in the requested frame
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   //disable collision between gripper and object
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   //disable collision between gripper and table
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   //zero padding on fingertip links; shouldn't matter much due to collisions disabled above
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   //compute gripper location for final place
00152   geometry_msgs::PoseStamped gripper_place_pose = computeGripperPose(place_location,
00153                                                                      place_goal.grasp.grasp_pose,
00154                                                                      handDescription().robotFrame(place_goal.arm_name));
00155   //publish marker
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); //magenta
00162     }
00163     else
00164     {
00165       marker_publisher_->setMarkerPose(marker_id_, gripper_place_pose);
00166     }
00167   }
00168 
00169   //disable collisions between grasped object and table
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   //zero padding on fingertip links
00186   std::vector<motion_planning_msgs::LinkPadding> link_padding =
00187     MechanismInterface::fingertipPadding(place_goal.arm_name, 0.0);
00188   // padding on grasped object, which is still attached to the gripper
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   //search backwards from place to pre-place
00201   std::vector<double> empty;
00202   float actual_distance;
00203   ROS_INFO(" PlaceExecutor: compute from place to pre-place");
00204   int error_code = mechInterface().getInterpolatedIK(place_goal.arm_name,
00205                                                      gripper_place_pose, place_direction,
00206                                                      place_goal.approach.desired_distance,
00207                                                      empty,
00208                                                      place_goal.grasp.grasp_posture,
00209                                                      ord, link_padding,
00210                                                      true, place_trajectory_, actual_distance);
00211   ROS_DEBUG(" Place trajectory: actual(%f), min(%f), desired (%f)",
00212             actual_distance, place_goal.approach.min_distance, place_goal.approach.desired_distance);
00213 
00214   if (actual_distance < place_goal.approach.min_distance)
00215   {
00216     ROS_DEBUG("Place trajectory below min. threshold");
00217     if (place_trajectory_.points.empty())
00218     {
00219       ROS_DEBUG("Place trajectory empty; problem is with place location");
00220       if (error_code == ArmNavigationErrorCodes::COLLISION_CONSTRAINTS_VIOLATED)
00221         return Result(PlaceLocationResult::PLACE_IN_COLLISION, true);
00222       else if (error_code == ArmNavigationErrorCodes::JOINT_LIMITS_VIOLATED)
00223         return Result(PlaceLocationResult::PLACE_OUT_OF_REACH, true);
00224       else return Result(PlaceLocationResult::PLACE_UNFEASIBLE, true);
00225     }
00226     if (error_code == ArmNavigationErrorCodes::COLLISION_CONSTRAINTS_VIOLATED)
00227       return Result(PlaceLocationResult::PREPLACE_IN_COLLISION, true);
00228     else if (error_code == ArmNavigationErrorCodes::JOINT_LIMITS_VIOLATED)
00229       return Result(PlaceLocationResult::PREPLACE_OUT_OF_REACH, true);
00230     else return Result(PlaceLocationResult::PREPLACE_UNFEASIBLE, true);
00231   }
00232 
00233 
00234   //make sure first position is feasible with default padding
00235   if ( !mechInterface().checkStateValidity(place_goal.arm_name, place_trajectory_.points.front().positions,
00236                                            place_goal.additional_collision_operations,
00237                                            place_goal.additional_link_padding) )
00238   {
00239     ROS_DEBUG("First pose in place trajectory is unfeasible with default padding");
00240     return Result(PlaceLocationResult::PREPLACE_UNFEASIBLE, true);
00241   }
00242 
00243 
00244   //disable all collisions on grasped object, since we are no longer holding it during the retreat
00245   coll.object1 = place_goal.collision_object_name;
00246   coll.object2 = coll.COLLISION_SET_ALL;
00247   coll.operation = motion_planning_msgs::CollisionOperation::DISABLE;
00248   ord.collision_operations.clear();
00249   ord.collision_operations.push_back(coll);
00250   if (place_goal.allow_gripper_support_collision)
00251   {
00252     coll.object1 = handDescription().gripperCollisionName(place_goal.arm_name);
00253     coll.object2 = place_goal.collision_support_surface_name;
00254     ord.collision_operations.push_back(coll);
00255   }
00256   ord.collision_operations = concat(ord.collision_operations,
00257                                     place_goal.additional_collision_operations.collision_operations);
00258 
00259   geometry_msgs::Vector3Stamped retreat_direction;
00260   retreat_direction.header.stamp = ros::Time::now();
00261   retreat_direction.header.frame_id = handDescription().gripperFrame(place_goal.arm_name);
00262   retreat_direction.vector = mechInterface().negate( handDescription().approachDirection(place_goal.arm_name) );
00263 
00264   //search from place to retreat, using solution from place as seed
00265   ROS_INFO(" PlaceExecutor: compute from place to retreat");
00266   std::vector<double> place_joint_angles = place_trajectory_.points.back().positions;
00267   mechInterface().getInterpolatedIK(place_goal.arm_name,
00268                                     gripper_place_pose, retreat_direction,
00269                                     place_goal.desired_retreat_distance,
00270                                     place_joint_angles,
00271                                     place_goal.grasp.pre_grasp_posture,
00272                                     ord, link_padding,
00273                                     false, retreat_trajectory_, actual_distance);
00274   ROS_DEBUG("Retreat trajectory: actual (%f), min (%f) and desired (%f)", actual_distance,
00275            place_goal.min_retreat_distance, place_goal.desired_retreat_distance);
00276 
00277   if (actual_distance < place_goal.min_retreat_distance)
00278   {
00279    ROS_DEBUG("Retreat trajectory below min. threshold");
00280     if (retreat_trajectory_.points.empty())
00281     {
00282       ROS_DEBUG("Retreat trajectory empty; problem is with place location");
00283       if (error_code == ArmNavigationErrorCodes::COLLISION_CONSTRAINTS_VIOLATED)
00284         return Result(PlaceLocationResult::PLACE_IN_COLLISION, true);
00285       else if (error_code == ArmNavigationErrorCodes::JOINT_LIMITS_VIOLATED)
00286         return Result(PlaceLocationResult::PLACE_OUT_OF_REACH, true);
00287       else return Result(PlaceLocationResult::PLACE_UNFEASIBLE, true);
00288     }
00289     if (error_code == ArmNavigationErrorCodes::COLLISION_CONSTRAINTS_VIOLATED)
00290       return Result(PlaceLocationResult::RETREAT_IN_COLLISION, true);
00291     else if (error_code == ArmNavigationErrorCodes::JOINT_LIMITS_VIOLATED)
00292       return Result(PlaceLocationResult::RETREAT_OUT_OF_REACH, true);
00293     else return Result(PlaceLocationResult::RETREAT_UNFEASIBLE, true);
00294   }
00295 
00296   return Result(PlaceLocationResult::SUCCESS, true);
00297 }
00298 
00305 PlaceLocationResult
00306 PlaceExecutor::placeApproach(const object_manipulation_msgs::PlaceGoal &place_goal,
00307                              const geometry_msgs::PoseStamped&)
00308 {
00309   mechInterface().attemptTrajectory(place_goal.arm_name, place_trajectory_, true);
00310   return Result(PlaceLocationResult::SUCCESS, true);
00311 }
00312 
00313 
00323 PlaceLocationResult PlaceExecutor::place(const object_manipulation_msgs::PlaceGoal &place_goal,
00324                                          const geometry_msgs::PoseStamped &place_location)
00325 {
00326   //demo_synchronizer::getClient().rviz(1, "Collision models;IK contacts;Interpolated IK;Grasp execution");
00327 
00328   //compute interpolated trajectories
00329   PlaceLocationResult result = prepareInterpolatedTrajectories(place_goal, place_location);
00330   if (result.result_code != PlaceLocationResult::SUCCESS) return result;
00331 
00332   //demo_synchronizer::getClient().sync(2, "Using motion planner to move arm to pre-place location");
00333   //demo_synchronizer::getClient().rviz(1, "Collision models;Planning goal;Environment contacts;Collision map");
00334 
00335   //whether we are using the constraints or not
00336   bool use_constraints = true;
00337 
00338   //check if we can actually understand the constraints
00339   if(!constraintsUnderstandable(place_goal.path_constraints))
00340   {
00341     ROS_WARN("Constraints passed to place executor are of types not yet handled. Ignoring them.");
00342     use_constraints = false;
00343   }
00344 
00345   if (place_goal.path_constraints.orientation_constraints.empty())
00346   {
00347     use_constraints = false;
00348   }
00349 
00350   if(use_constraints)
00351   {
00352     //recompute the pre-place pose from the already computed trajectory
00353     geometry_msgs::PoseStamped place_pose;
00354     place_pose.header.frame_id = place_location.header.frame_id;
00355     place_pose.header.stamp = ros::Time(0.0);
00356     //ROS_DEBUG("Place pose in frame: %s",place_pose.header.frame_id.c_str());
00357     if(!mechInterface().getFK(place_goal.arm_name, place_trajectory_.points.front().positions, place_pose))
00358     {
00359       ROS_ERROR("Could not re-compute pre-place pose based on trajectory");
00360       throw MechanismException("Could not re-compute pre-place pose based on trajectory");
00361     }
00362     ROS_DEBUG("Attempting move arm to pre-place with constraints");
00363     if (!mechInterface().moveArmConstrained(place_goal.arm_name, place_pose,
00364                                             place_goal.additional_collision_operations,
00365                                             place_goal.additional_link_padding,
00366                                             place_goal.path_constraints,
00367                                             place_trajectory_.points.front().positions[2],
00368                                             false))
00369     {
00370       //TODO: in the future, this should be hard stop, with an informative message back
00371       //to the caller saying the constraints have failed
00372       ROS_WARN("Object place: move_arm to pre-place with constraints failed. Trying again without constraints.");
00373       use_constraints = false;
00374     }
00375   }
00376 
00377   //try to go to the pre-place pose without constraints
00378   if(!use_constraints)
00379   {
00380     ROS_DEBUG("Attempting move arm to pre-place without constraints");
00381     if ( !mechInterface().attemptMoveArmToGoal(place_goal.arm_name, place_trajectory_.points.front().positions,
00382                                                place_goal.additional_collision_operations,
00383                                                place_goal.additional_link_padding) )
00384     {
00385       ROS_DEBUG("Object place: move_arm (without constraints) to pre-place reports failure");
00386       return Result(PlaceLocationResult::MOVE_ARM_FAILED, true);
00387     }
00388   }
00389   ROS_DEBUG(" Arm moved to pre-place");
00390 
00391   //demo_synchronizer::getClient().sync(2, "Executing interpolated IK path for place, detaching and retreating");
00392   //demo_synchronizer::getClient().rviz(1, "Collision models");
00393 
00394   result = placeApproach(place_goal, place_location);
00395   if ( result.result_code != PlaceLocationResult::SUCCESS)
00396   {
00397     ROS_DEBUG(" Pre-place to place approach failed");
00398     return Result(PlaceLocationResult::PLACE_FAILED, false);
00399   }
00400   ROS_DEBUG(" Place trajectory done");
00401 
00402   mechInterface().detachAndAddBackObjectsAttachedToGripper(place_goal.arm_name, place_goal.collision_object_name);
00403   ROS_DEBUG(" Object detached");
00404 
00405   mechInterface().handPostureGraspAction(place_goal.arm_name, place_goal.grasp,
00406                                          object_manipulation_msgs::GraspHandPostureExecutionGoal::RELEASE);
00407   ROS_DEBUG(" Object released");
00408 
00409   result = retreat(place_goal);
00410   if (result.result_code != PlaceLocationResult::SUCCESS)
00411   {
00412     return Result(PlaceLocationResult::RETREAT_FAILED, false);
00413   }
00414   return Result(PlaceLocationResult::SUCCESS, true);
00415 }
00416 
00420 bool PlaceExecutor::constraintsUnderstandable(const motion_planning_msgs::Constraints &constraints)
00421 {
00422   if(constraints.position_constraints.empty() && constraints.orientation_constraints.empty() &&
00423      constraints.joint_constraints.empty() && constraints.visibility_constraints.empty())
00424     return true;
00425   if(constraints.orientation_constraints.size() == 1 && constraints.position_constraints.empty()
00426      && constraints.joint_constraints.empty() && constraints.visibility_constraints.empty())
00427     return true;
00428   return false;
00429 }
00430 
00431 PlaceLocationResult
00432 ReactivePlaceExecutor::placeApproach(const object_manipulation_msgs::PlaceGoal &place_goal,
00433                                      const geometry_msgs::PoseStamped &place_location)
00434 {
00435   //compute gripper location for final place
00436   geometry_msgs::PoseStamped gripper_place_pose = computeGripperPose(place_location,
00437                                                                      place_goal.grasp.grasp_pose,
00438                                                                      handDescription().robotFrame(place_goal.arm_name));
00439 
00440   //prepare the goal for reactive placing
00441   object_manipulation_msgs::ReactivePlaceGoal reactive_place_goal;
00442   reactive_place_goal.arm_name = place_goal.arm_name;
00443   reactive_place_goal.collision_object_name = place_goal.collision_object_name;
00444   reactive_place_goal.collision_support_surface_name = place_goal.collision_support_surface_name;
00445   reactive_place_goal.trajectory = place_trajectory_;
00446   reactive_place_goal.final_place_pose = gripper_place_pose;
00447 
00448   //give the reactive place 1 minute to do its thing
00449   ros::Duration timeout = ros::Duration(60.0);
00450   ROS_DEBUG(" Calling the reactive place action");
00451   mechInterface().reactive_place_action_client_.client(place_goal.arm_name).sendGoal(reactive_place_goal);
00452   if ( !mechInterface().reactive_place_action_client_.client(place_goal.arm_name).waitForResult(timeout) )
00453   {
00454     ROS_ERROR("  Reactive place timed out");
00455     return Result(PlaceLocationResult::PLACE_FAILED, false);
00456   }
00457   object_manipulation_msgs::ReactivePlaceResult reactive_place_result =
00458     *mechInterface().reactive_place_action_client_.client(place_goal.arm_name).getResult();
00459   if (reactive_place_result.manipulation_result.value != reactive_place_result.manipulation_result.SUCCESS)
00460   {
00461     ROS_ERROR("  Reactive place failed with error code %d", reactive_place_result.manipulation_result.value);
00462     return Result(PlaceLocationResult::PLACE_FAILED, false);
00463   }
00464   ROS_DEBUG("  Reactive place action succeeded");
00465   return Result(PlaceLocationResult::SUCCESS, true);
00466 }
00467 
00468 } //namespace object_grasping
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


katana_object_manipulator
Author(s): Henning Deeken
autogenerated on Thu Jan 3 2013 14:44:43