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 #include <ros/ros.h>
00037 
00038 #include <planning_interface/planning_interface.h>
00039 #include <planning_scene/planning_scene.h>
00040 #include <planning_models/robot_model.h>
00041 #include <moveit_msgs/GetMotionPlan.h>
00042 #include <sbpl_interface/sbpl_meta_interface.h>
00043 
00044 #include <pluginlib/class_list_macros.h>
00045 
00046 namespace sbpl_interface_ros
00047 {
00048 
00049 class SBPLMetaPlanner : public planning_interface::Planner
00050 {
00051 public:
00052   void init(const planning_models::RobotModelConstPtr& model)
00053   {
00054     ros::NodeHandle nh;
00055     
00056     sbpl_meta_interface_.reset(new sbpl_interface::SBPLMetaInterface(model));
00057   }
00058 
00059   bool canServiceRequest(const moveit_msgs::GetMotionPlan::Request &req,
00060                          planning_interface::PlannerCapability &capabilities) const
00061   {
00062     
00063     
00064     return true;
00065   }
00066 
00067   bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
00068              const moveit_msgs::GetMotionPlan::Request &req,
00069              moveit_msgs::GetMotionPlan::Response &res) const
00070   {
00071     bool solve_ok = sbpl_meta_interface_->solve(planning_scene,
00072                                                 req,
00073                                                 res);
00074     return solve_ok;
00075   }
00076 
00077   bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
00078              const moveit_msgs::GetMotionPlan::Request &req,
00079              moveit_msgs::MotionPlanDetailedResponse &res) const
00080   {
00081     moveit_msgs::GetMotionPlan::Response res2;
00082     if (sbpl_meta_interface_->solve(planning_scene,
00083                                     req,
00084                                     res2))
00085     {
00086       res.trajectory_start = res2.trajectory_start;
00087       res.trajectory.push_back(res2.trajectory);
00088       res.description.push_back("plan");
00089       res.processing_time.push_back(res2.planning_time);
00090       return true;
00091     }
00092     else
00093       return false;
00094   }
00095 
00096   std::string getDescription() const { return "SBPLMeta"; }
00097 
00098   void getPlanningAlgorithms(std::vector<std::string> &algs) const
00099   {
00100     algs.resize(1);
00101     algs[0] = "SBPLMeta";
00102   }
00103 
00104   void terminate() const
00105   {
00106     
00107   }
00108 
00109 private:
00110   ros::Publisher display_bfs_publisher_;
00111   boost::shared_ptr<sbpl_interface::SBPLMetaInterface> sbpl_meta_interface_;
00112 };
00113 
00114 } 
00115 
00116 PLUGINLIB_EXPORT_CLASS( sbpl_interface_ros::SBPLMetaPlanner, planning_interface::Planner);