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 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 #ifndef MOVEIT_PICK_PLACE_PICK_PLACE_ 00038 #define MOVEIT_PICK_PLACE_PICK_PLACE_ 00039 00040 #include <moveit/pick_place/manipulation_pipeline.h> 00041 #include <moveit/pick_place/pick_place_params.h> 00042 #include <moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h> 00043 #include <moveit/planning_pipeline/planning_pipeline.h> 00044 #include <moveit_msgs/PickupAction.h> 00045 #include <moveit_msgs/PlaceAction.h> 00046 #include <boost/noncopyable.hpp> 00047 #include <boost/enable_shared_from_this.hpp> 00048 00049 namespace pick_place 00050 { 00051 00052 class PickPlace; 00053 typedef boost::shared_ptr<PickPlace> PickPlacePtr; 00054 typedef boost::shared_ptr<const PickPlace> PickPlaceConstPtr; 00055 00056 class PickPlacePlanBase 00057 { 00058 public: 00059 00060 PickPlacePlanBase(const PickPlaceConstPtr &pick_place, const std::string &name); 00061 ~PickPlacePlanBase(); 00062 00063 const std::vector<ManipulationPlanPtr>& getSuccessfulManipulationPlans() const 00064 { 00065 return pipeline_.getSuccessfulManipulationPlans(); 00066 } 00067 const std::vector<ManipulationPlanPtr>& getFailedManipulationPlans() const 00068 { 00069 return pipeline_.getFailedManipulationPlans(); 00070 } 00071 00072 const moveit_msgs::MoveItErrorCodes& getErrorCode() const 00073 { 00074 return error_code_; 00075 } 00076 00077 protected: 00078 00079 void initialize(); 00080 void waitForPipeline(const ros::WallTime &endtime); 00081 void foundSolution(); 00082 void emptyQueue(); 00083 00084 PickPlaceConstPtr pick_place_; 00085 ManipulationPipeline pipeline_; 00086 00087 double last_plan_time_; 00088 bool done_; 00089 bool pushed_all_poses_; 00090 boost::condition_variable done_condition_; 00091 boost::mutex done_mutex_; 00092 moveit_msgs::MoveItErrorCodes error_code_; 00093 }; 00094 00095 class PickPlan : public PickPlacePlanBase 00096 { 00097 public: 00098 00099 PickPlan(const PickPlaceConstPtr &pick_place); 00100 bool plan(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PickupGoal &goal); 00101 }; 00102 00103 typedef boost::shared_ptr<PickPlan> PickPlanPtr; 00104 typedef boost::shared_ptr<const PickPlan> PickPlanConstPtr; 00105 00106 class PlacePlan : public PickPlacePlanBase 00107 { 00108 public: 00109 00110 PlacePlan(const PickPlaceConstPtr &pick_place); 00111 bool plan(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PlaceGoal &goal); 00112 }; 00113 00114 typedef boost::shared_ptr<PlacePlan> PlacePlanPtr; 00115 typedef boost::shared_ptr<const PlacePlan> PlacePlanConstPtr; 00116 00117 class PickPlace : private boost::noncopyable, 00118 public boost::enable_shared_from_this<PickPlace> 00119 { 00120 public: 00121 00122 static const std::string DISPLAY_PATH_TOPIC; 00123 static const std::string DISPLAY_GRASP_TOPIC; 00124 00125 // the amount of time (maximum) to wait for achieving a grasp posture 00126 static const double DEFAULT_GRASP_POSTURE_COMPLETION_DURATION; // seconds 00127 00128 PickPlace(const planning_pipeline::PlanningPipelinePtr &planning_pipeline); 00129 00130 const constraint_samplers::ConstraintSamplerManagerPtr& getConstraintsSamplerManager() const 00131 { 00132 return constraint_sampler_manager_loader_->getConstraintSamplerManager(); 00133 } 00134 00135 const planning_pipeline::PlanningPipelinePtr& getPlanningPipeline() const 00136 { 00137 return planning_pipeline_; 00138 } 00139 00140 const robot_model::RobotModelConstPtr& getRobotModel() const 00141 { 00142 return planning_pipeline_->getRobotModel(); 00143 } 00144 00146 PickPlanPtr planPick(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PickupGoal &goal) const; 00147 00149 PlacePlanPtr planPlace(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PlaceGoal &goal) const; 00150 00151 void displayComputedMotionPlans(bool flag); 00152 void displayProcessedGrasps(bool flag); 00153 00154 void visualizePlan(const ManipulationPlanPtr &plan) const; 00155 00156 void visualizeGrasp(const ManipulationPlanPtr &plan) const; 00157 00158 void visualizeGrasps(const std::vector<ManipulationPlanPtr>& plans) const; 00159 00160 private: 00161 00162 ros::NodeHandle nh_; 00163 planning_pipeline::PlanningPipelinePtr planning_pipeline_; 00164 bool display_computed_motion_plans_; 00165 bool display_grasps_; 00166 ros::Publisher display_path_publisher_; 00167 ros::Publisher grasps_publisher_; 00168 00169 constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_; 00170 }; 00171 00172 } 00173 00174 #endif