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_interface.h>
00043
00044 #include <pluginlib/class_list_macros.h>
00045
00046 namespace sbpl_interface_ros
00047 {
00048
00049 class SBPLPlanner : public planning_interface::Planner
00050 {
00051 public:
00052 void init(const planning_models::RobotModelConstPtr& model)
00053 {
00054 ros::NodeHandle nh;
00055 display_bfs_publisher_ = nh.advertise<visualization_msgs::Marker>("planning_components_visualization", 10, true);
00056 sbpl_interface_.reset(new sbpl_interface::SBPLInterface(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 sbpl_interface::PlanningParameters params;
00072 params.use_bfs_ = false;
00073 bool solve_ok = sbpl_interface_->solve(planning_scene,
00074 req,
00075 res,
00076 params);
00077 return solve_ok;
00078 }
00079
00080 bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
00081 const moveit_msgs::GetMotionPlan::Request &req,
00082 moveit_msgs::MotionPlanDetailedResponse &res) const
00083 {
00084 sbpl_interface::PlanningParameters params;
00085 params.use_bfs_ = false;
00086
00087 moveit_msgs::GetMotionPlan::Response res2;
00088 if (sbpl_interface_->solve(planning_scene,
00089 req,
00090 res2,
00091 params))
00092 {
00093 res.trajectory_start = res2.trajectory_start;
00094 res.trajectory.push_back(res2.trajectory);
00095 res.description.push_back("plan");
00096 res.processing_time.push_back(res2.planning_time);
00097 return true;
00098 }
00099 else
00100 return false;
00101 }
00102
00103 std::string getDescription() const { return "SBPL"; }
00104
00105 void getPlanningAlgorithms(std::vector<std::string> &algs) const
00106 {
00107 algs.resize(1);
00108 algs[0] = "SBPL";
00109 }
00110
00111 void terminate() const
00112 {
00113
00114 }
00115
00116 private:
00117 ros::Publisher display_bfs_publisher_;
00118 boost::shared_ptr<sbpl_interface::SBPLInterface> sbpl_interface_;
00119 };
00120
00121 }
00122
00123 PLUGINLIB_EXPORT_CLASS( sbpl_interface_ros::SBPLPlanner, planning_interface::Planner);