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 #include <sbpl_interface/sbpl_meta_interface.h>
00036 #include <sbpl_interface/sbpl_interface.h>
00037 #include <planning_models/conversions.h>
00038
00039 namespace sbpl_interface {
00040
00041 SBPLMetaInterface::SBPLMetaInterface(const planning_models::RobotModelConstPtr& kmodel)
00042 {
00043 sbpl_interface_first_.reset(new sbpl_interface::SBPLInterface(kmodel));
00044 sbpl_interface_second_.reset(new sbpl_interface::SBPLInterface(kmodel));
00045 }
00046
00047 bool SBPLMetaInterface::solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
00048 const moveit_msgs::GetMotionPlan::Request &req,
00049 moveit_msgs::GetMotionPlan::Response &res)
00050 {
00051 first_ok_ = false;
00052 first_done_ = false;
00053 second_ok_ = false;
00054 second_done_ = false;
00055
00056 PlanningParameters param_bfs;
00057 param_bfs.use_bfs_ = true;
00058 PlanningParameters param_no_bfs;
00059 param_no_bfs.use_bfs_ = false;
00060 moveit_msgs::GetMotionPlan::Response res1, res2;
00061 boost::thread thread1(boost::bind(&SBPLMetaInterface::runSolver, this, true,
00062 boost::cref(planning_scene), boost::cref(req), boost::ref(res1), param_bfs));
00063 boost::thread thread2(boost::bind(&SBPLMetaInterface::runSolver, this, false,
00064 boost::cref(planning_scene), boost::cref(req), boost::ref(res2), param_no_bfs));
00065 boost::mutex::scoped_lock lock(planner_done_mutex_);
00066 planner_done_condition_.wait(lock);
00067
00068 if(first_done_) {
00069 std::cerr << "FIRST DONE" << std::endl;
00070 if(first_ok_) {
00071 std::cerr << "First ok, interrupting second" << std::endl;
00072 if(!second_done_) {
00073 thread2.interrupt();
00074 thread2.join();
00075 }
00076 } else {
00077 if(!second_done_) {
00078 planner_done_condition_.wait(lock);
00079 }
00080 }
00081 }
00082 if(second_done_) {
00083 std::cerr << "Second done" << std::endl;
00084 if(second_ok_) {
00085 std::cerr << "Second ok, interrupting first" << std::endl;
00086 if(!first_done_) {
00087 thread1.interrupt();
00088 thread1.join();
00089 }
00090 } else {
00091 if(!first_done_) {
00092 planner_done_condition_.wait(lock);
00093 }
00094 }
00095 }
00096
00097 if(!first_ok_ && !second_ok_) {
00098 std::cerr << "Both planners failed" << std::endl;
00099 res = res1;
00100 return false;
00101 }
00102 if(!first_ok_ && second_ok_) {
00103 std::cerr << "Sbpl interface no bfs reports time " << sbpl_interface_second_->getLastPlanningStatistics().total_planning_time_ << std::endl;
00104 last_planning_statistics_ = sbpl_interface_second_->getLastPlanningStatistics();
00105 res = res2;
00106 return true;
00107 } else if(first_ok_ && !second_ok_) {
00108 std::cerr << "Sbpl interface bfs reports time " << sbpl_interface_first_->getLastPlanningStatistics().total_planning_time_ << std::endl;
00109 last_planning_statistics_ = sbpl_interface_first_->getLastPlanningStatistics();
00110 res = res1;
00111 return true;
00112 }
00113 std::cerr << "Sbpl interface bfs reports time " << sbpl_interface_first_->getLastPlanningStatistics().total_planning_time_ << std::endl;
00114 std::cerr << "Sbpl interface no bfs reports time " << sbpl_interface_second_->getLastPlanningStatistics().total_planning_time_ << std::endl;
00115 if(sbpl_interface_first_->getLastPlanningStatistics().total_planning_time_ <
00116 sbpl_interface_second_->getLastPlanningStatistics().total_planning_time_) {
00117 last_planning_statistics_ = sbpl_interface_first_->getLastPlanningStatistics();
00118 res = res1;
00119 } else {
00120 last_planning_statistics_ = sbpl_interface_second_->getLastPlanningStatistics();
00121 res = res2;
00122 }
00123 return true;
00124 }
00125
00126 void SBPLMetaInterface::runSolver(bool use_first,
00127 const planning_scene::PlanningSceneConstPtr& planning_scene,
00128 const moveit_msgs::GetMotionPlan::Request &req,
00129 moveit_msgs::GetMotionPlan::Response &res,
00130 const PlanningParameters& params)
00131 {
00132 try {
00133 if(use_first) {
00134 std::cerr << "Running first planner" << std::endl;
00135 first_ok_ = sbpl_interface_first_->solve(planning_scene,
00136 req,
00137 res,
00138 params);
00139 first_done_ = true;
00140 } else {
00141 std::cerr << "Running second planner" << std::endl;
00142 second_ok_ = sbpl_interface_second_->solve(planning_scene,
00143 req,
00144 res,
00145 params);
00146 second_done_ = true;
00147 }
00148 planner_done_condition_.notify_all();
00149 } catch(...) {
00150 std::cerr << "Interruption requested\n";
00151 }
00152 }
00153
00154
00155 }