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