| Public Member Functions | |
| bool | canServiceRequest (const moveit_msgs::GetMotionPlan::Request &req, planning_interface::PlannerCapability &capabilities) const | 
| std::string | getDescription () const | 
| void | getPlanningAlgorithms (std::vector< std::string > &algs) const | 
| void | init (const planning_models::RobotModelConstPtr &model) | 
| bool | solve (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::GetMotionPlan::Request &req, moveit_msgs::GetMotionPlan::Response &res) const | 
| bool | solve (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::GetMotionPlan::Request &req, moveit_msgs::MotionPlanDetailedResponse &res) const | 
| void | terminate () const | 
| Private Attributes | |
| ros::Publisher | display_bfs_publisher_ | 
| boost::shared_ptr < sbpl_interface::SBPLInterface > | sbpl_interface_ | 
Definition at line 49 of file sbpl_plugin.cpp.
| bool sbpl_interface_ros::SBPLPlanner::canServiceRequest | ( | const moveit_msgs::GetMotionPlan::Request & | req, | 
| planning_interface::PlannerCapability & | capabilities | ||
| ) | const  [inline] | 
Definition at line 59 of file sbpl_plugin.cpp.
| std::string sbpl_interface_ros::SBPLPlanner::getDescription | ( | ) | const  [inline] | 
Definition at line 103 of file sbpl_plugin.cpp.
| void sbpl_interface_ros::SBPLPlanner::getPlanningAlgorithms | ( | std::vector< std::string > & | algs | ) | const  [inline] | 
Definition at line 105 of file sbpl_plugin.cpp.
| void sbpl_interface_ros::SBPLPlanner::init | ( | const planning_models::RobotModelConstPtr & | model | ) |  [inline] | 
Definition at line 52 of file sbpl_plugin.cpp.
| bool sbpl_interface_ros::SBPLPlanner::solve | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, | 
| const moveit_msgs::GetMotionPlan::Request & | req, | ||
| moveit_msgs::GetMotionPlan::Response & | res | ||
| ) | const  [inline] | 
Definition at line 67 of file sbpl_plugin.cpp.
| bool sbpl_interface_ros::SBPLPlanner::solve | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, | 
| const moveit_msgs::GetMotionPlan::Request & | req, | ||
| moveit_msgs::MotionPlanDetailedResponse & | res | ||
| ) | const  [inline] | 
Definition at line 80 of file sbpl_plugin.cpp.
| void sbpl_interface_ros::SBPLPlanner::terminate | ( | ) | const  [inline] | 
Definition at line 111 of file sbpl_plugin.cpp.
Definition at line 117 of file sbpl_plugin.cpp.
| boost::shared_ptr<sbpl_interface::SBPLInterface> sbpl_interface_ros::SBPLPlanner::sbpl_interface_  [private] | 
Definition at line 118 of file sbpl_plugin.cpp.