Definition at line 101 of file ompl_planner_manager.cpp.
◆ OMPLPlannerManager()
ompl_interface::OMPLPlannerManager::OMPLPlannerManager |
( |
| ) |
|
|
inline |
◆ canServiceRequest()
◆ dynamicReconfigureCallback()
void ompl_interface::OMPLPlannerManager::dynamicReconfigureCallback |
( |
OMPLDynamicReconfigureConfig & |
config, |
|
|
uint32_t |
|
|
) |
| |
|
inlineprivate |
◆ getDescription()
std::string ompl_interface::OMPLPlannerManager::getDescription |
( |
| ) |
const |
|
inlineoverridevirtual |
◆ getPlanningAlgorithms()
void ompl_interface::OMPLPlannerManager::getPlanningAlgorithms |
( |
std::vector< std::string > & |
algs | ) |
const |
|
inlineoverridevirtual |
◆ getPlanningContext()
planning_interface::PlanningContextPtr ompl_interface::OMPLPlannerManager::getPlanningContext |
( |
const planning_scene::PlanningSceneConstPtr & |
planning_scene, |
|
|
const planning_interface::MotionPlanRequest & |
req, |
|
|
moveit_msgs::MoveItErrorCodes & |
error_code |
|
) |
| const |
|
inlineoverridevirtual |
◆ initialize()
bool ompl_interface::OMPLPlannerManager::initialize |
( |
const moveit::core::RobotModelConstPtr & |
model, |
|
|
const std::string & |
ns |
|
) |
| |
|
inlineoverridevirtual |
◆ setPlannerConfigurations()
◆ display_random_valid_states_
bool ompl_interface::OMPLPlannerManager::display_random_valid_states_ { false } |
|
private |
◆ dynamic_reconfigure_server_
std::unique_ptr<dynamic_reconfigure::Server<OMPLDynamicReconfigureConfig> > ompl_interface::OMPLPlannerManager::dynamic_reconfigure_server_ |
|
private |
◆ nh_
◆ ompl_interface_
std::unique_ptr<OMPLInterface> ompl_interface::OMPLPlannerManager::ompl_interface_ |
|
private |
◆ output_handler_
std::shared_ptr<ompl::msg::OutputHandler> ompl_interface::OMPLPlannerManager::output_handler_ |
|
private |
◆ planner_data_link_name_
std::string ompl_interface::OMPLPlannerManager::planner_data_link_name_ |
|
private |
◆ pub_markers_
◆ pub_valid_states_
◆ pub_valid_states_thread_
std::unique_ptr<std::thread> ompl_interface::OMPLPlannerManager::pub_valid_states_thread_ |
|
private |
◆ pub_valid_traj_
The documentation for this class was generated from the following file: