Go to the documentation of this file.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 
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 <moveit/robot_state/conversions.h>
00042 #include <eigen_conversions/eigen_msg.h>
00043 #include <ros/console.h>
00044 
00045 namespace pick_place
00046 {
00047 
00048 PlacePlan::PlacePlan(const PickPlaceConstPtr &pick_place) : PickPlacePlanBase(pick_place, "place")
00049 {
00050 }
00051 
00052 bool PlacePlan::transformToEndEffectorGoal(const geometry_msgs::PoseStamped &goal_pose,
00053                        const robot_state::AttachedBody* attached_body,
00054                        geometry_msgs::PoseStamped &place_pose) const
00055 {
00056   const EigenSTL::vector_Affine3d& fixed_transforms = attached_body->getFixedTransforms();
00057   if (fixed_transforms.empty())
00058     return false;
00059   Eigen::Affine3d end_effector_transform;
00060   tf::poseMsgToEigen(goal_pose.pose, end_effector_transform);
00061   end_effector_transform = end_effector_transform * fixed_transforms[0].inverse();
00062   place_pose.header = goal_pose.header;
00063   tf::poseEigenToMsg(end_effector_transform, place_pose.pose);
00064   return true;
00065 }
00066 
00067 bool PlacePlan::plan(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PlaceGoal &goal)
00068 {
00069   double timeout = goal.allowed_planning_time;
00070   ros::WallTime endtime = ros::WallTime::now() + ros::WallDuration(timeout);
00071   std::string attached_object_name = goal.attached_object_name;
00072   const robot_model::JointModelGroup *jmg = NULL;
00073   const robot_model::JointModelGroup *eef = NULL;
00074 
00075   if (planning_scene->getRobotModel()->hasEndEffector(goal.group_name))
00076   {
00077     eef = planning_scene->getRobotModel()->getEndEffector(goal.group_name);
00078     if (eef)
00079     {
00080       const std::string &eef_parent = eef->getEndEffectorParentGroup().first;
00081       jmg = planning_scene->getRobotModel()->getJointModelGroup(eef_parent);
00082     }
00083   }
00084   else
00085   {
00086     jmg = planning_scene->getRobotModel()->getJointModelGroup(goal.group_name);
00087     if (jmg)
00088     {
00089       const std::vector<std::string> &eef_names = jmg->getAttachedEndEffectorNames();
00090       if (eef_names.size() == 1)
00091       {
00092         eef = planning_scene->getRobotModel()->getEndEffector(eef_names[0]);
00093       }
00094     }
00095   }
00096 
00097   if (!jmg)
00098   {
00099     error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
00100     return false;
00101   }
00102 
00103   
00104   int loop_count = 0;
00105   while (attached_object_name.empty() && loop_count < 2)
00106   {
00107     
00108     
00109     const std::vector<std::string> &links = loop_count == 0 ?
00110       (eef ? eef->getLinkModelNames() : jmg->getLinkModelNames()) : jmg->getLinkModelNames();
00111     
00112     if (loop_count == 0 && !eef)
00113       loop_count++;
00114     loop_count++;
00115     for (std::size_t i = 0 ; i < links.size() ; ++i)
00116     {
00117       const robot_state::LinkState *ls = planning_scene->getCurrentState().getLinkState(links[i]);
00118       if (ls)
00119       {
00120         std::vector<const robot_state::AttachedBody*> attached_bodies;
00121         ls->getAttachedBodies(attached_bodies);
00122         if (attached_bodies.empty())
00123           continue;
00124         if (attached_bodies.size() > 1 || !attached_object_name.empty())
00125         {
00126           ROS_ERROR("Multiple attached bodies for group '%s' but no explicit attached object to place was specified", goal.group_name.c_str());
00127           error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_OBJECT_NAME;
00128           return false;
00129         }
00130         else
00131           attached_object_name = attached_bodies[0]->getName();
00132       }
00133     }
00134   }
00135 
00136   const robot_state::AttachedBody *attached_body = planning_scene->getCurrentState().getAttachedBody(attached_object_name);
00137   if (!attached_body)
00138   {
00139     ROS_ERROR("There is no object to detach");
00140     error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_OBJECT_NAME;
00141     return false;
00142   }
00143 
00144   ros::WallTime start_time = ros::WallTime::now();
00145 
00146   
00147   ManipulationPlanSharedDataPtr plan_data(new ManipulationPlanSharedData());
00148   ManipulationPlanSharedDataConstPtr const_plan_data = plan_data;
00149   plan_data->planning_group_ = jmg->getName();
00150   plan_data->end_effector_group_ = eef ? eef->getName() : "";
00151   plan_data->ik_link_name_ = eef ? eef->getEndEffectorParentGroup().second : "";
00152   plan_data->timeout_ = endtime;
00153   plan_data->path_constraints_ = goal.path_constraints;
00154   plan_data->planner_id_ = goal.planner_id;
00155   plan_data->minimize_object_distance_ = false;
00156   plan_data->max_goal_sampling_attempts_ = std::max(2u, jmg->getDefaultIKAttempts());
00157   moveit_msgs::AttachedCollisionObject &detach_object_msg = plan_data->diff_attached_object_;
00158 
00159   
00160   detach_object_msg.link_name = attached_body->getAttachedLinkName();
00161   detach_object_msg.object.id = attached_object_name;
00162   detach_object_msg.object.operation = moveit_msgs::CollisionObject::REMOVE;
00163 
00164   collision_detection::AllowedCollisionMatrixPtr approach_place_acm(new collision_detection::AllowedCollisionMatrix(planning_scene->getAllowedCollisionMatrix()));
00165 
00166   
00167   approach_place_acm->setEntry(eef->getLinkModelNames(), goal.allowed_touch_objects, true);
00168 
00169   
00170   std::vector<std::string> touch_links(attached_body->getTouchLinks().begin(), attached_body->getTouchLinks().end());
00171   approach_place_acm->setEntry(attached_object_name, touch_links, true);
00172 
00173   if (!goal.support_surface_name.empty())
00174   {
00175     
00176     approach_place_acm->setEntry(goal.support_surface_name, attached_object_name, true);
00177 
00178     
00179     if (goal.allow_gripper_support_collision && eef)
00180       approach_place_acm->setEntry(goal.support_surface_name, eef->getLinkModelNames(), true);
00181   }
00182 
00183 
00184   
00185   pipeline_.reset();
00186 
00187   ManipulationStagePtr stage1(new ReachableAndValidPoseFilter(planning_scene, approach_place_acm, pick_place_->getConstraintsSamplerManager()));
00188   ManipulationStagePtr stage2(new ApproachAndTranslateStage(planning_scene, approach_place_acm));
00189   ManipulationStagePtr stage3(new PlanStage(planning_scene, pick_place_->getPlanningPipeline()));
00190   pipeline_.addStage(stage1).addStage(stage2).addStage(stage3);
00191 
00192   initialize();
00193 
00194   pipeline_.start();
00195 
00196   
00197   for (std::size_t i = 0 ; i < goal.place_locations.size() ; ++i)
00198   {
00199     ManipulationPlanPtr p(new ManipulationPlan(const_plan_data));
00200     const manipulation_msgs::PlaceLocation &pl = goal.place_locations[i];
00201     
00202     
00203     transformToEndEffectorGoal(pl.place_pose, attached_body, p->goal_pose_);
00204     p->approach_ = pl.approach;
00205     p->retreat_ = pl.retreat;
00206     p->retreat_posture_ = pl.post_place_posture;
00207     if (p->retreat_posture_.name.empty())
00208       p->retreat_posture_ = attached_body->getDetachPosture();
00209     pipeline_.push(p);
00210   }
00211   ROS_INFO("Added %d place locations", (int) goal.place_locations.size());
00212 
00213   
00214   waitForPipeline(endtime);
00215 
00216   pipeline_.stop();
00217 
00218   last_plan_time_ = (ros::WallTime::now() - start_time).toSec();
00219 
00220   if (!getSuccessfulManipulationPlans().empty())
00221     error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00222   else
00223   {
00224     if (last_plan_time_ > timeout)
00225       error_code_.val = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
00226     else
00227     {
00228       error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
00229       if (goal.place_locations.size() > 0)
00230       {
00231         ROS_WARN("All supplied place locations failed. Retrying last location in verbose mode.");
00232         
00233         initialize();
00234         pipeline_.setVerbose(true);
00235         pipeline_.start();
00236         pipeline_.reprocessLastFailure();
00237         waitForPipeline(ros::WallTime::now() + ros::WallDuration(1.0));
00238         pipeline_.stop();
00239         pipeline_.setVerbose(false);
00240       }
00241     }
00242   }
00243   ROS_INFO("Place completed after %lf seconds", last_plan_time_);
00244 
00245   return error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS;
00246 }
00247 
00248 PlacePlanPtr PickPlace::planPlace(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PlaceGoal &goal) const
00249 {
00250   PlacePlanPtr p(new PlacePlan(shared_from_this()));
00251   if (planning_scene::PlanningScene::isEmpty(goal.planning_options.planning_scene_diff))
00252     p->plan(planning_scene, goal);
00253   else
00254     p->plan(planning_scene->diff(goal.planning_options.planning_scene_diff), goal);
00255 
00256   if (display_computed_motion_plans_)
00257   {
00258     const std::vector<pick_place::ManipulationPlanPtr> &success = p->getSuccessfulManipulationPlans();
00259     if (!success.empty())
00260       visualizePlan(success.back());
00261   }
00262 
00263   if (display_grasps_)
00264   {
00265     const std::vector<pick_place::ManipulationPlanPtr> &success = p->getSuccessfulManipulationPlans();
00266     visualizeGrasps(success);
00267     const std::vector<pick_place::ManipulationPlanPtr> &failed = p->getFailedManipulationPlans();
00268     visualizeGrasps(failed);
00269   }
00270 
00271   return p;
00272 }
00273 
00274 }