Public Member Functions | Private Member Functions | Private Attributes | List of all members
ompl_interface::OMPLPlannerManager Class Reference
Inheritance diagram for ompl_interface::OMPLPlannerManager:
Inheritance graph
[legend]

Public Member Functions

bool canServiceRequest (const moveit_msgs::MotionPlanRequest &req) const override
 
std::string getDescription () const override
 
void getPlanningAlgorithms (std::vector< std::string > &algs) const override
 
planning_interface::PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const override
 
bool initialize (const moveit::core::RobotModelConstPtr &model, const std::string &ns) override
 
 OMPLPlannerManager ()
 
void setPlannerConfigurations (const planning_interface::PlannerConfigurationMap &pconfig) override
 
- Public Member Functions inherited from planning_interface::PlannerManager
const PlannerConfigurationMapgetPlannerConfigurations () const
 
PlanningContextPtr getPlanningContext (const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req) const
 
 PlannerManager ()
 
void terminate () const
 
virtual ~PlannerManager ()
 

Private Member Functions

void dynamicReconfigureCallback (OMPLDynamicReconfigureConfig &config, uint32_t)
 

Private Attributes

bool display_random_valid_states_ { false }
 
std::unique_ptr< dynamic_reconfigure::Server< OMPLDynamicReconfigureConfig > > dynamic_reconfigure_server_
 
ros::NodeHandle nh_
 
std::unique_ptr< OMPLInterfaceompl_interface_
 
std::shared_ptr< ompl::msg::OutputHandler > output_handler_
 
std::string planner_data_link_name_
 
ros::Publisher pub_markers_
 
ros::Publisher pub_valid_states_
 
std::unique_ptr< std::thread > pub_valid_states_thread_
 
ros::Publisher pub_valid_traj_
 

Additional Inherited Members

- Protected Attributes inherited from planning_interface::PlannerManager
PlannerConfigurationMap config_settings_
 

Detailed Description

Definition at line 101 of file ompl_planner_manager.cpp.

Constructor & Destructor Documentation

◆ OMPLPlannerManager()

ompl_interface::OMPLPlannerManager::OMPLPlannerManager ( )
inline

Definition at line 104 of file ompl_planner_manager.cpp.

Member Function Documentation

◆ canServiceRequest()

bool ompl_interface::OMPLPlannerManager::canServiceRequest ( const moveit_msgs::MotionPlanRequest req) const
inlineoverridevirtual

Implements planning_interface::PlannerManager.

Definition at line 153 of file ompl_planner_manager.cpp.

◆ dynamicReconfigureCallback()

void ompl_interface::OMPLPlannerManager::dynamicReconfigureCallback ( OMPLDynamicReconfigureConfig &  config,
uint32_t   
)
inlineprivate

Definition at line 296 of file ompl_planner_manager.cpp.

◆ getDescription()

std::string ompl_interface::OMPLPlannerManager::getDescription ( ) const
inlineoverridevirtual

Reimplemented from planning_interface::PlannerManager.

Definition at line 158 of file ompl_planner_manager.cpp.

◆ getPlanningAlgorithms()

void ompl_interface::OMPLPlannerManager::getPlanningAlgorithms ( std::vector< std::string > &  algs) const
inlineoverridevirtual

Reimplemented from planning_interface::PlannerManager.

Definition at line 163 of file ompl_planner_manager.cpp.

◆ 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

Implements planning_interface::PlannerManager.

Definition at line 180 of file ompl_planner_manager.cpp.

◆ initialize()

bool ompl_interface::OMPLPlannerManager::initialize ( const moveit::core::RobotModelConstPtr &  model,
const std::string &  ns 
)
inlineoverridevirtual

Reimplemented from planning_interface::PlannerManager.

Definition at line 139 of file ompl_planner_manager.cpp.

◆ setPlannerConfigurations()

void ompl_interface::OMPLPlannerManager::setPlannerConfigurations ( const planning_interface::PlannerConfigurationMap pconfig)
inlineoverridevirtual

Reimplemented from planning_interface::PlannerManager.

Definition at line 172 of file ompl_planner_manager.cpp.

Member Data Documentation

◆ display_random_valid_states_

bool ompl_interface::OMPLPlannerManager::display_random_valid_states_ { false }
private

Definition at line 338 of file ompl_planner_manager.cpp.

◆ dynamic_reconfigure_server_

std::unique_ptr<dynamic_reconfigure::Server<OMPLDynamicReconfigureConfig> > ompl_interface::OMPLPlannerManager::dynamic_reconfigure_server_
private

Definition at line 335 of file ompl_planner_manager.cpp.

◆ nh_

ros::NodeHandle ompl_interface::OMPLPlannerManager::nh_
private

Definition at line 334 of file ompl_planner_manager.cpp.

◆ ompl_interface_

std::unique_ptr<OMPLInterface> ompl_interface::OMPLPlannerManager::ompl_interface_
private

Definition at line 336 of file ompl_planner_manager.cpp.

◆ output_handler_

std::shared_ptr<ompl::msg::OutputHandler> ompl_interface::OMPLPlannerManager::output_handler_
private

Definition at line 343 of file ompl_planner_manager.cpp.

◆ planner_data_link_name_

std::string ompl_interface::OMPLPlannerManager::planner_data_link_name_
private

Definition at line 342 of file ompl_planner_manager.cpp.

◆ pub_markers_

ros::Publisher ompl_interface::OMPLPlannerManager::pub_markers_
private

Definition at line 339 of file ompl_planner_manager.cpp.

◆ pub_valid_states_

ros::Publisher ompl_interface::OMPLPlannerManager::pub_valid_states_
private

Definition at line 340 of file ompl_planner_manager.cpp.

◆ pub_valid_states_thread_

std::unique_ptr<std::thread> ompl_interface::OMPLPlannerManager::pub_valid_states_thread_
private

Definition at line 337 of file ompl_planner_manager.cpp.

◆ pub_valid_traj_

ros::Publisher ompl_interface::OMPLPlannerManager::pub_valid_traj_
private

Definition at line 341 of file ompl_planner_manager.cpp.


The documentation for this class was generated from the following file:


ompl
Author(s): Ioan Sucan
autogenerated on Sat Apr 27 2024 02:26:21