#include <sbpl_meta_interface.h>
Public Member Functions | |
const PlanningStatistics & | getLastPlanningStatistics () const |
SBPLMetaInterface (const planning_models::RobotModelConstPtr &kmodel) | |
bool | solve (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::GetMotionPlan::Request &req, moveit_msgs::GetMotionPlan::Response &res) |
virtual | ~SBPLMetaInterface () |
Protected Member Functions | |
void | runSolver (bool use_first, const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::GetMotionPlan::Request &req, moveit_msgs::GetMotionPlan::Response &res, const PlanningParameters ¶ms) |
Protected Attributes | |
bool | first_done_ |
bool | first_ok_ |
PlanningStatistics | last_planning_statistics_ |
boost::condition_variable | planner_done_condition_ |
boost::mutex | planner_done_mutex_ |
boost::shared_ptr < sbpl_interface::SBPLInterface > | sbpl_interface_first_ |
boost::shared_ptr < sbpl_interface::SBPLInterface > | sbpl_interface_second_ |
bool | second_done_ |
bool | second_ok_ |
Definition at line 46 of file sbpl_meta_interface.h.
sbpl_interface::SBPLMetaInterface::SBPLMetaInterface | ( | const planning_models::RobotModelConstPtr & | kmodel | ) |
Definition at line 41 of file sbpl_meta_interface.cpp.
virtual sbpl_interface::SBPLMetaInterface::~SBPLMetaInterface | ( | ) | [inline, virtual] |
Definition at line 51 of file sbpl_meta_interface.h.
const PlanningStatistics& sbpl_interface::SBPLMetaInterface::getLastPlanningStatistics | ( | ) | const [inline] |
Definition at line 57 of file sbpl_meta_interface.h.
void sbpl_interface::SBPLMetaInterface::runSolver | ( | bool | use_first, |
const planning_scene::PlanningSceneConstPtr & | planning_scene, | ||
const moveit_msgs::GetMotionPlan::Request & | req, | ||
moveit_msgs::GetMotionPlan::Response & | res, | ||
const PlanningParameters & | params | ||
) | [protected] |
Definition at line 126 of file sbpl_meta_interface.cpp.
bool sbpl_interface::SBPLMetaInterface::solve | ( | const planning_scene::PlanningSceneConstPtr & | planning_scene, |
const moveit_msgs::GetMotionPlan::Request & | req, | ||
moveit_msgs::GetMotionPlan::Response & | res | ||
) |
Definition at line 47 of file sbpl_meta_interface.cpp.
bool sbpl_interface::SBPLMetaInterface::first_done_ [protected] |
Definition at line 72 of file sbpl_meta_interface.h.
bool sbpl_interface::SBPLMetaInterface::first_ok_ [protected] |
Definition at line 71 of file sbpl_meta_interface.h.
Definition at line 79 of file sbpl_meta_interface.h.
boost::condition_variable sbpl_interface::SBPLMetaInterface::planner_done_condition_ [protected] |
Definition at line 70 of file sbpl_meta_interface.h.
boost::mutex sbpl_interface::SBPLMetaInterface::planner_done_mutex_ [protected] |
Definition at line 69 of file sbpl_meta_interface.h.
boost::shared_ptr<sbpl_interface::SBPLInterface> sbpl_interface::SBPLMetaInterface::sbpl_interface_first_ [protected] |
Definition at line 76 of file sbpl_meta_interface.h.
boost::shared_ptr<sbpl_interface::SBPLInterface> sbpl_interface::SBPLMetaInterface::sbpl_interface_second_ [protected] |
Definition at line 77 of file sbpl_meta_interface.h.
bool sbpl_interface::SBPLMetaInterface::second_done_ [protected] |
Definition at line 74 of file sbpl_meta_interface.h.
bool sbpl_interface::SBPLMetaInterface::second_ok_ [protected] |
Definition at line 73 of file sbpl_meta_interface.h.