Public Member Functions | |
| bool | computePlan (moveit_msgs::GetMotionPlan::Request &req, moveit_msgs::GetMotionPlan::Response &res) |
| void | displaySolution (const moveit_msgs::MotionPlanResponse &mplan_res) |
| OMPLPlannerService (planning_scene_monitor::PlanningSceneMonitor &psm, bool debug=false) | |
| void | status () |
Private Attributes | |
| bool | debug_ |
| ros::ServiceServer | display_states_service_ |
| ros::NodeHandle | nh_ |
| ompl_interface::OMPLInterface | ompl_interface_ |
| ros::ServiceServer | plan_service_ |
| planning_scene_monitor::PlanningSceneMonitor & | psm_ |
| ros::Publisher | pub_plan_ |
| ros::Publisher | pub_request_ |
Definition at line 51 of file ompl_planner.cpp.
| OMPLPlannerService::OMPLPlannerService | ( | planning_scene_monitor::PlanningSceneMonitor & | psm, |
| bool | debug = false |
||
| ) | [inline] |
Definition at line 54 of file ompl_planner.cpp.
| bool OMPLPlannerService::computePlan | ( | moveit_msgs::GetMotionPlan::Request & | req, |
| moveit_msgs::GetMotionPlan::Response & | res | ||
| ) | [inline] |
Definition at line 65 of file ompl_planner.cpp.
| void OMPLPlannerService::displaySolution | ( | const moveit_msgs::MotionPlanResponse & | mplan_res | ) | [inline] |
Definition at line 93 of file ompl_planner.cpp.
| void OMPLPlannerService::status | ( | ) | [inline] |
Definition at line 102 of file ompl_planner.cpp.
bool OMPLPlannerService::debug_ [private] |
Definition at line 118 of file ompl_planner.cpp.
Definition at line 115 of file ompl_planner.cpp.
ros::NodeHandle OMPLPlannerService::nh_ [private] |
Definition at line 111 of file ompl_planner.cpp.
Definition at line 113 of file ompl_planner.cpp.
Definition at line 114 of file ompl_planner.cpp.
Definition at line 112 of file ompl_planner.cpp.
ros::Publisher OMPLPlannerService::pub_plan_ [private] |
Definition at line 116 of file ompl_planner.cpp.
Definition at line 117 of file ompl_planner.cpp.