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

Global settings. More...

#include <PlannerSettings.h>

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

Classes

struct  BenchmarkSettings
 Settings related to benchmarking. More...
 
struct  EnvironmentSettings
 
struct  ForwardPropagationSettings
 
struct  OmplSettings
 Settings related to OMPL. More...
 
struct  SbplSettings
 
struct  SmoothingSettings
 
struct  SteerSettings
 
struct  ThetaStarSettings
 

Public Member Functions

 GlobalSettings ()
 
void load (const nlohmann::json &j)
 

Public Attributes

std::shared_ptr< Environmentenvironment
 Environment used for planning. More...
 
PlannerSettings::GlobalSettings::EnvironmentSettings env
 
PlannerSettings::GlobalSettings::EnvironmentSettings this
 
Property< bool > log_env_distances {false, "log_env_distances", this}
 Whether to log the distances precomputed by the grid mazes. More...
 
Property< bool > auto_choose_distance_computation_method
 
Property< distance_computation::Methoddistance_computation_method
 
Property< double > max_planning_time {15, "max_planning_time", this}
 
Property< unsigned int > fast_odf_threshold
 For maps with more cells than this threshold, a fast approximating algorithm is used to compute the obstacle distance field (necessary for clearance evaluations and GRIPS). More...
 
Property< bool > estimate_theta {false, "estimate_theta", this}
 Whether to estimate the orientation of the start and goal states for planners that need them (e.g. More...
 
Property< bool > evaluate_clearing {true, "evaluate_clearing", this}
 Whether to compute stats on clearing distances of the found solutions. More...
 
Property< double > exact_goal_radius {1e-2, "exact_goal_radius", this}
 Radius threshold to evaluate whether the exact goal has been found. More...
 
Property< unsigned int > interpolation_limit {500u, "interpolation_limit", this}
 Any og::PathGeometric with more nodes will not get interpolated. More...
 
Property< double > max_path_length {10000, "max_path_length", this}
 Maximal length a og::PathGeometric can have to be interpolated. More...
 
Property< double > cusp_angle_threshold
 Threshold in radians of the difference between consecutive yaw angles to be considered a cusp. More...
 
PlannerSettings::GlobalSettings::BenchmarkSettings benchmark
 
PlannerSettings::GlobalSettings::BenchmarkSettings this
 
PlannerSettings::GlobalSettings::OmplSettings ompl
 
PlannerSettings::GlobalSettings::OmplSettings this
 
PlannerSettings::GlobalSettings::SteerSettings steer
 
PlannerSettings::GlobalSettings::SteerSettings this
 
PlannerSettings::GlobalSettings::ForwardPropagationSettings forwardpropagation
 
PlannerSettings::GlobalSettings::ForwardPropagationSettings this
 
PlannerSettings::GlobalSettings::SbplSettings sbpl
 
PlannerSettings::GlobalSettings::SbplSettings this
 
PlannerSettings::GlobalSettings::SmoothingSettings smoothing
 
PlannerSettings::GlobalSettings::SmoothingSettings this
 
PlannerSettings::GlobalSettings::ThetaStarSettings theta_star
 
PlannerSettings::GlobalSettings::ThetaStarSettings this
 

Detailed Description

Global settings.

Constructor & Destructor Documentation

◆ GlobalSettings()

PlannerSettings::GlobalSettings::GlobalSettings ( )
inline

Member Function Documentation

◆ load()

void PlannerSettings::GlobalSettings::load ( const nlohmann::json &  j)
inline

Member Data Documentation

◆ auto_choose_distance_computation_method

Property<bool> PlannerSettings::GlobalSettings::auto_choose_distance_computation_method
Initial value:
{
true, "auto_choose_distance_computation_method", this}

◆ benchmark

PlannerSettings::GlobalSettings::BenchmarkSettings PlannerSettings::GlobalSettings::benchmark

◆ cusp_angle_threshold

Property<double> PlannerSettings::GlobalSettings::cusp_angle_threshold
Initial value:
{60 * M_PI / 180.,
"cusp_angle_threshold", this}

Threshold in radians of the difference between consecutive yaw angles to be considered a cusp.

◆ distance_computation_method

Property<distance_computation::Method> PlannerSettings::GlobalSettings::distance_computation_method
Initial value:
{
distance_computation::BRUTE_FORCE, "distance_computation_method", this}
@ BRUTE_FORCE
Definition: PlannerSettings.h:31

◆ env

PlannerSettings::GlobalSettings::EnvironmentSettings PlannerSettings::GlobalSettings::env

◆ environment

std::shared_ptr<Environment> PlannerSettings::GlobalSettings::environment

Environment used for planning.

◆ estimate_theta

Property<bool> PlannerSettings::GlobalSettings::estimate_theta {false, "estimate_theta", this}

Whether to estimate the orientation of the start and goal states for planners that need them (e.g.

SBPL).

◆ evaluate_clearing

Property<bool> PlannerSettings::GlobalSettings::evaluate_clearing {true, "evaluate_clearing", this}

Whether to compute stats on clearing distances of the found solutions.

◆ exact_goal_radius

Property<double> PlannerSettings::GlobalSettings::exact_goal_radius {1e-2, "exact_goal_radius", this}

Radius threshold to evaluate whether the exact goal has been found.

◆ fast_odf_threshold

Property<unsigned int> PlannerSettings::GlobalSettings::fast_odf_threshold
Initial value:
{100 * 100, "fast_odf_threshold",
this}

For maps with more cells than this threshold, a fast approximating algorithm is used to compute the obstacle distance field (necessary for clearance evaluations and GRIPS).

◆ forwardpropagation

PlannerSettings::GlobalSettings::ForwardPropagationSettings PlannerSettings::GlobalSettings::forwardpropagation

◆ interpolation_limit

Property<unsigned int> PlannerSettings::GlobalSettings::interpolation_limit {500u, "interpolation_limit", this}

Any og::PathGeometric with more nodes will not get interpolated.

◆ log_env_distances

Property<bool> PlannerSettings::GlobalSettings::log_env_distances {false, "log_env_distances", this}

Whether to log the distances precomputed by the grid mazes.

◆ max_path_length

Property<double> PlannerSettings::GlobalSettings::max_path_length {10000, "max_path_length", this}

Maximal length a og::PathGeometric can have to be interpolated.

◆ max_planning_time

Property<double> PlannerSettings::GlobalSettings::max_planning_time {15, "max_planning_time", this}

◆ ompl

PlannerSettings::GlobalSettings::OmplSettings PlannerSettings::GlobalSettings::ompl

◆ sbpl

PlannerSettings::GlobalSettings::SbplSettings PlannerSettings::GlobalSettings::sbpl

◆ smoothing

PlannerSettings::GlobalSettings::SmoothingSettings PlannerSettings::GlobalSettings::smoothing

◆ steer

PlannerSettings::GlobalSettings::SteerSettings PlannerSettings::GlobalSettings::steer

◆ theta_star

PlannerSettings::GlobalSettings::ThetaStarSettings PlannerSettings::GlobalSettings::theta_star

◆ this [1/8]

PlannerSettings::GlobalSettings::EnvironmentSettings PlannerSettings::GlobalSettings::this

◆ this [2/8]

PlannerSettings::GlobalSettings::BenchmarkSettings PlannerSettings::GlobalSettings::this

◆ this [3/8]

PlannerSettings::GlobalSettings::OmplSettings PlannerSettings::GlobalSettings::this

◆ this [4/8]

PlannerSettings::GlobalSettings::SteerSettings PlannerSettings::GlobalSettings::this

◆ this [5/8]

PlannerSettings::GlobalSettings::ForwardPropagationSettings PlannerSettings::GlobalSettings::this

◆ this [6/8]

PlannerSettings::GlobalSettings::SbplSettings PlannerSettings::GlobalSettings::this

◆ this [7/8]

PlannerSettings::GlobalSettings::SmoothingSettings PlannerSettings::GlobalSettings::this

◆ this [8/8]

PlannerSettings::GlobalSettings::ThetaStarSettings PlannerSettings::GlobalSettings::this

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