plan_stage.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/plan_stage.h>
00039 #include <moveit/kinematic_constraints/utils.h>
00040 #include <ros/console.h>
00041 
00042 namespace pick_place
00043 {
00044 
00045 PlanStage::PlanStage(const planning_scene::PlanningSceneConstPtr &scene,
00046                      const planning_pipeline::PlanningPipelinePtr &planning_pipeline) :
00047   ManipulationStage("plan"),
00048   planning_scene_(scene),
00049   planning_pipeline_(planning_pipeline)
00050 {
00051 }
00052 
00053 void PlanStage::signalStop()
00054 {
00055   ManipulationStage::signalStop();
00056   planning_pipeline_->terminate();
00057 }
00058 
00059 bool PlanStage::evaluate(const ManipulationPlanPtr &plan) const
00060 {
00061   planning_interface::MotionPlanRequest req;
00062   planning_interface::MotionPlanResponse res;
00063   req.group_name = plan->shared_data_->planning_group_;
00064   req.num_planning_attempts = 1;
00065   req.allowed_planning_time = (plan->shared_data_->timeout_ - ros::WallTime::now()).toSec();
00066   req.path_constraints = plan->shared_data_->path_constraints_;
00067   req.planner_id = plan->shared_data_->planner_id_;
00068 
00069   req.goal_constraints.resize(1, kinematic_constraints::constructGoalConstraints(plan->approach_state_->getJointStateGroup(plan->shared_data_->planning_group_)));
00070   unsigned int attempts = 0;
00071   do
00072   {
00073     attempts++;
00074     if (!signal_stop_ && planning_pipeline_->generatePlan(planning_scene_, req, res) &&
00075         res.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS &&
00076         res.trajectory_ && !res.trajectory_->empty())
00077     {
00078       if (!plan->approach_posture_.name.empty())
00079       {
00080         robot_state::RobotStatePtr state(new robot_state::RobotState(res.trajectory_->getLastWayPoint()));
00081         state->setStateValues(plan->approach_posture_);
00082         robot_trajectory::RobotTrajectoryPtr traj(new robot_trajectory::RobotTrajectory(state->getRobotModel(), plan->shared_data_->end_effector_group_));
00083         traj->addSuffixWayPoint(state, PickPlace::DEFAULT_GRASP_POSTURE_COMPLETION_DURATION);
00084         plan_execution::ExecutableTrajectory et(traj, "pre_grasp");
00085         plan->trajectories_.insert(plan->trajectories_.begin(), et);
00086       }
00087       plan_execution::ExecutableTrajectory et(res.trajectory_, name_);
00088       plan->trajectories_.insert(plan->trajectories_.begin(), et);
00089       plan->error_code_ = res.error_code_;
00090 
00091       return true;
00092     }
00093     else
00094       plan->error_code_ = res.error_code_;
00095   }
00096   // if the planner reported an invalid plan, give it a second chance
00097   while (!signal_stop_ && plan->error_code_.val == moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN && attempts < 2);
00098 
00099   return false;
00100 }
00101 
00102 }


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