Bench-MR
A Motion Planning Benchmark for Wheeled Mobile Robots
Public Member Functions | Public Attributes | List of all members
PlannerSettings::GlobalSettings::OmplSettings Struct Reference

Settings related to OMPL. More...

#include <PlannerSettings.h>

Inheritance diagram for PlannerSettings::GlobalSettings::OmplSettings:
Inheritance graph
[legend]
Collaboration diagram for PlannerSettings::GlobalSettings::OmplSettings:
Collaboration graph
[legend]

Public Member Functions

 OmplSettings (const char *name, Group *parent=nullptr)
 Custom constructor to expose planner settings and their default values. More...
 
void retrieveGeometricPlannerParams ()
 Retrieve available parameters and defaults for geometric planners. More...
 
void retrieveControlPlannerParams ()
 Retrieve available parameters and defaults for control planners. More...
 
void initializeSampler () const
 Sets the OMPL sampler based on the state space (steering function) and selected sampler. More...
 

Public Attributes

ompl::base::StateSpacePtr state_space {nullptr}
 
ompl::control::ControlSpacePtr control_space {nullptr}
 
ompl::base::SpaceInformationPtr space_info {nullptr}
 
ompl::control::SpaceInformationPtr control_space_info {nullptr}
 
ompl::base::OptimizationObjectivePtr objective {nullptr}
 
Stopwatch steering_timer
 
Property< double > state_equality_tolerance
 
Property< double > cost_threshold {100, "cost_threshold", this}
 
Property< unsigned int > seed {1, "seed", this}
 
Property< std::string > sampler {"iid", "sampler", this}
 The sampler used by OMPL. More...
 
Property< std::string > optimization_objective
 The optimization objective used by OMPL. More...
 
Property< nlohmann::json > geometric_planner_settings
 Planner settings for geometric planners. More...
 
Property< nlohmann::json > control_planner_settings
 Planner settings for control planners. More...
 

Detailed Description

Settings related to OMPL.

Constructor & Destructor Documentation

◆ OmplSettings()

PlannerSettings::GlobalSettings::OmplSettings::OmplSettings ( const char *  name,
Group *  parent = nullptr 
)

Custom constructor to expose planner settings and their default values.

Member Function Documentation

◆ initializeSampler()

void PlannerSettings::GlobalSettings::OmplSettings::initializeSampler ( ) const

Sets the OMPL sampler based on the state space (steering function) and selected sampler.

◆ retrieveControlPlannerParams()

void PlannerSettings::GlobalSettings::OmplSettings::retrieveControlPlannerParams ( )

Retrieve available parameters and defaults for control planners.

◆ retrieveGeometricPlannerParams()

void PlannerSettings::GlobalSettings::OmplSettings::retrieveGeometricPlannerParams ( )

Retrieve available parameters and defaults for geometric planners.

Member Data Documentation

◆ control_planner_settings

Property<nlohmann::json> PlannerSettings::GlobalSettings::OmplSettings::control_planner_settings
Initial value:
{
{}, "control_planner_settings", this}

Planner settings for control planners.

Geometric and control planners are split since planner names are not unique across these two namespaces.

Keys are planners names, values are key:value pairs of planner parameters. Populated with default params in constructor.

◆ control_space

ompl::control::ControlSpacePtr PlannerSettings::GlobalSettings::OmplSettings::control_space {nullptr}

◆ control_space_info

ompl::control::SpaceInformationPtr PlannerSettings::GlobalSettings::OmplSettings::control_space_info {nullptr}

◆ cost_threshold

Property<double> PlannerSettings::GlobalSettings::OmplSettings::cost_threshold {100, "cost_threshold", this}

◆ geometric_planner_settings

Property<nlohmann::json> PlannerSettings::GlobalSettings::OmplSettings::geometric_planner_settings
Initial value:
{
{}, "geometric_planner_settings", this}

Planner settings for geometric planners.

Geometric and control planners are split since planner names are not unique across these two namespaces.

Keys are planners names, values are key:value pairs of planner parameters.

◆ objective

ompl::base::OptimizationObjectivePtr PlannerSettings::GlobalSettings::OmplSettings::objective {nullptr}

◆ optimization_objective

Property<std::string> PlannerSettings::GlobalSettings::OmplSettings::optimization_objective
Initial value:
{
"min_pathlength", "optimization_objective", this}

The optimization objective used by OMPL.

Currently supported: "min_pathlength", "max_minclearance", "max_smoothness", "min_curvature"

◆ sampler

Property<std::string> PlannerSettings::GlobalSettings::OmplSettings::sampler {"iid", "sampler", this}

The sampler used by OMPL.

Currently supported: "iid", "halton"

◆ seed

Property<unsigned int> PlannerSettings::GlobalSettings::OmplSettings::seed {1, "seed", this}

◆ space_info

ompl::base::SpaceInformationPtr PlannerSettings::GlobalSettings::OmplSettings::space_info {nullptr}

◆ state_equality_tolerance

Property<double> PlannerSettings::GlobalSettings::OmplSettings::state_equality_tolerance
Initial value:
{1e-4, "state_equality_tolerance",
this}

◆ state_space

ompl::base::StateSpacePtr PlannerSettings::GlobalSettings::OmplSettings::state_space {nullptr}

◆ steering_timer

Stopwatch PlannerSettings::GlobalSettings::OmplSettings::steering_timer

The documentation for this struct was generated from the following files: