pick.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, 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 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/pick_place/pick_place.h>
00038 #include <moveit/pick_place/reachable_valid_pose_filter.h>
00039 #include <moveit/pick_place/approach_and_translate_stage.h>
00040 #include <moveit/pick_place/plan_stage.h>
00041 #include <ros/console.h>
00042 
00043 namespace pick_place
00044 {
00045 
00046 PickPlan::PickPlan(const PickPlaceConstPtr &pick_place) : PickPlacePlanBase(pick_place, "pick")
00047 {
00048 }
00049 
00050 namespace
00051 {
00052 struct OrderGraspQuality
00053 {
00054   OrderGraspQuality(const std::vector<manipulation_msgs::Grasp> &grasps) : grasps_(grasps)
00055   {
00056   }
00057 
00058   bool operator()(const std::size_t a, const std::size_t b) const
00059   {
00060     return grasps_[a].grasp_quality > grasps_[b].grasp_quality;
00061   }
00062 
00063   const std::vector<manipulation_msgs::Grasp> &grasps_;
00064 };
00065 }
00066 
00067 bool PickPlan::plan(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PickupGoal &goal)
00068 {
00069   double timeout = goal.allowed_planning_time;
00070   ros::WallTime endtime = ros::WallTime::now() + ros::WallDuration(timeout);
00071 
00072   std::string planning_group = goal.group_name;
00073   std::string end_effector = goal.end_effector;
00074   if (end_effector.empty() && !planning_group.empty())
00075   {
00076     const robot_model::JointModelGroup *jmg = planning_scene->getRobotModel()->getJointModelGroup(planning_group);
00077     if (!jmg)
00078     {
00079       error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
00080       return false;
00081     }
00082     const std::vector<std::string> &eefs = jmg->getAttachedEndEffectorNames();
00083     if (!eefs.empty())
00084     {
00085       end_effector = eefs.front();
00086       if (eefs.size() > 1)
00087         ROS_WARN_STREAM("Choice of end-effector for group '" << planning_group << "' is ambiguous. Assuming '" << end_effector << "'");
00088     }
00089   }
00090   else
00091     if (!end_effector.empty() && planning_group.empty())
00092     {
00093       const robot_model::JointModelGroup *jmg = planning_scene->getRobotModel()->getEndEffector(end_effector);
00094       if (!jmg)
00095       {
00096         error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
00097         return false;
00098       }
00099       planning_group = jmg->getEndEffectorParentGroup().first;
00100       ROS_INFO_STREAM("Assuming the planning group for end effector '" << end_effector << "' is '" << planning_group << "'");
00101     }
00102   const robot_model::JointModelGroup *eef = end_effector.empty() ? NULL : planning_scene->getRobotModel()->getEndEffector(end_effector);
00103   if (!eef)
00104   {
00105     ROS_ERROR("No end-effector specified for pick action");
00106     error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
00107     return false;
00108   }
00109   const std::string &ik_link = eef->getEndEffectorParentGroup().second;
00110 
00111   ros::WallTime start_time = ros::WallTime::now();
00112 
00113   // construct common data for possible manipulation plans
00114   ManipulationPlanSharedDataPtr plan_data(new ManipulationPlanSharedData());
00115   ManipulationPlanSharedDataConstPtr const_plan_data = plan_data;
00116   plan_data->planning_group_ = planning_group;
00117   plan_data->end_effector_group_ = eef->getName();
00118   plan_data->ik_link_name_ = ik_link;
00119   plan_data->timeout_ = endtime;
00120   plan_data->path_constraints_ = goal.path_constraints;
00121   plan_data->planner_id_ = goal.planner_id;
00122   plan_data->minimize_object_distance_ = goal.minimize_object_distance;
00123   plan_data->max_goal_sampling_attempts_ = std::max(2u, planning_scene->getRobotModel()->getJointModelGroup(planning_group)->getDefaultIKAttempts());
00124   moveit_msgs::AttachedCollisionObject &attach_object_msg = plan_data->diff_attached_object_;
00125 
00126   // construct the attached object message that will change the world to what it would become after a pick
00127   attach_object_msg.link_name = ik_link;
00128   attach_object_msg.object.id = goal.target_name;
00129   attach_object_msg.object.operation = moveit_msgs::CollisionObject::ADD;
00130   attach_object_msg.touch_links = goal.attached_object_touch_links.empty() ? eef->getLinkModelNames() : goal.attached_object_touch_links;
00131   collision_detection::AllowedCollisionMatrixPtr approach_grasp_acm(new collision_detection::AllowedCollisionMatrix(planning_scene->getAllowedCollisionMatrix()));
00132 
00133   // we are allowed to touch the target object
00134   approach_grasp_acm->setEntry(goal.target_name, attach_object_msg.touch_links, true);
00135   // we are allowed to touch certain other objects with the gripper
00136   approach_grasp_acm->setEntry(eef->getLinkModelNames(), goal.allowed_touch_objects, true);
00137   if (!goal.support_surface_name.empty())
00138   {
00139     // we are allowed to have contact between the target object and the support surface before the grasp
00140     approach_grasp_acm->setEntry(goal.support_surface_name, goal.target_name, true);
00141 
00142     // optionally, it may be allowed to touch the support surface with the gripper
00143     if (goal.allow_gripper_support_collision)
00144       approach_grasp_acm->setEntry(goal.support_surface_name, eef->getLinkModelNames(), true);
00145   }
00146 
00147   // configure the manipulation pipeline
00148   pipeline_.reset();
00149   ManipulationStagePtr stage1(new ReachableAndValidPoseFilter(planning_scene, approach_grasp_acm, pick_place_->getConstraintsSamplerManager()));
00150   ManipulationStagePtr stage2(new ApproachAndTranslateStage(planning_scene, approach_grasp_acm));
00151   ManipulationStagePtr stage3(new PlanStage(planning_scene, pick_place_->getPlanningPipeline()));
00152   pipeline_.addStage(stage1).addStage(stage2).addStage(stage3);
00153 
00154   initialize();
00155   pipeline_.start();
00156 
00157   // order the grasps by quality
00158   std::vector<std::size_t> grasp_order(goal.possible_grasps.size());
00159   for (std::size_t i = 0 ; i < goal.possible_grasps.size() ; ++i)
00160     grasp_order[i] = i;
00161   OrderGraspQuality oq(goal.possible_grasps);
00162   std::sort(grasp_order.begin(), grasp_order.end(), oq);
00163 
00164   // feed the available grasps to the stages we set up
00165   for (std::size_t i = 0 ; i < goal.possible_grasps.size() ; ++i)
00166   {
00167     ManipulationPlanPtr p(new ManipulationPlan(const_plan_data));
00168     const manipulation_msgs::Grasp &g = goal.possible_grasps[grasp_order[i]];
00169     p->approach_ = g.approach;
00170     p->retreat_ = g.retreat;
00171     p->goal_pose_ = g.grasp_pose;
00172     // if no frame of reference was specified, assume the transform to be in the reference frame of the object
00173     if (p->goal_pose_.header.frame_id.empty())
00174       p->goal_pose_.header.frame_id = goal.target_name;
00175     p->approach_posture_ = g.pre_grasp_posture;
00176     p->retreat_posture_ = g.grasp_posture;
00177     pipeline_.push(p);
00178   }
00179 
00180   // wait till we're done
00181   waitForPipeline(endtime);
00182   pipeline_.stop();
00183 
00184   last_plan_time_ = (ros::WallTime::now() - start_time).toSec();
00185 
00186   if (!getSuccessfulManipulationPlans().empty())
00187     error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00188   else
00189   {
00190     if (last_plan_time_ > timeout)
00191       error_code_.val = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
00192     else
00193     {
00194       error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
00195       if (goal.possible_grasps.size() > 0)
00196       {
00197         ROS_WARN("All supplied grasps failed. Retrying last grasp in verbose mode.");
00198         // everything failed. we now start the pipeline again in verbose mode for one grasp
00199         initialize();
00200         pipeline_.setVerbose(true);
00201         pipeline_.start();
00202         pipeline_.reprocessLastFailure();
00203         waitForPipeline(ros::WallTime::now() + ros::WallDuration(1.0));
00204         pipeline_.stop();
00205         pipeline_.setVerbose(false);
00206       }
00207     }
00208   }
00209   ROS_INFO("Pickup completed after %lf seconds", last_plan_time_);
00210 
00211   return error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS;
00212 }
00213 
00214 PickPlanPtr PickPlace::planPick(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PickupGoal &goal) const
00215 {
00216   PickPlanPtr p(new PickPlan(shared_from_this()));
00217 
00218   if (planning_scene::PlanningScene::isEmpty(goal.planning_options.planning_scene_diff))
00219     p->plan(planning_scene, goal);
00220   else
00221     p->plan(planning_scene->diff(goal.planning_options.planning_scene_diff), goal);
00222 
00223   if (display_computed_motion_plans_)
00224   {
00225     const std::vector<pick_place::ManipulationPlanPtr> &success = p->getSuccessfulManipulationPlans();
00226     if (!success.empty())
00227       visualizePlan(success.back());
00228   }
00229 
00230   if (display_grasps_)
00231   {
00232     const std::vector<pick_place::ManipulationPlanPtr> &success = p->getSuccessfulManipulationPlans();
00233     visualizeGrasps(success);
00234     const std::vector<pick_place::ManipulationPlanPtr> &failed = p->getFailedManipulationPlans();
00235     visualizeGrasps(failed);
00236   }
00237 
00238   return p;
00239 }
00240 
00241 }


manipulation
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:33:06