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