Bench-MR
A Motion Planning Benchmark for Wheeled Mobile Robots
|
Global settings. More...
#include <PlannerSettings.h>
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< Environment > | environment |
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::Method > | distance_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 |
Global settings.
|
inline |
|
inline |
Property<bool> PlannerSettings::GlobalSettings::auto_choose_distance_computation_method |
PlannerSettings::GlobalSettings::BenchmarkSettings PlannerSettings::GlobalSettings::benchmark |
Property<double> PlannerSettings::GlobalSettings::cusp_angle_threshold |
Threshold in radians of the difference between consecutive yaw angles to be considered a cusp.
Property<distance_computation::Method> PlannerSettings::GlobalSettings::distance_computation_method |
PlannerSettings::GlobalSettings::EnvironmentSettings PlannerSettings::GlobalSettings::env |
std::shared_ptr<Environment> PlannerSettings::GlobalSettings::environment |
Environment used for planning.
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).
Property<bool> PlannerSettings::GlobalSettings::evaluate_clearing {true, "evaluate_clearing", this} |
Whether to compute stats on clearing distances of the found solutions.
Property<double> PlannerSettings::GlobalSettings::exact_goal_radius {1e-2, "exact_goal_radius", this} |
Radius threshold to evaluate whether the exact goal has been found.
Property<unsigned int> PlannerSettings::GlobalSettings::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).
PlannerSettings::GlobalSettings::ForwardPropagationSettings PlannerSettings::GlobalSettings::forwardpropagation |
Property<unsigned int> PlannerSettings::GlobalSettings::interpolation_limit {500u, "interpolation_limit", this} |
Any og::PathGeometric with more nodes will not get interpolated.
Property<bool> PlannerSettings::GlobalSettings::log_env_distances {false, "log_env_distances", this} |
Whether to log the distances precomputed by the grid mazes.
Property<double> PlannerSettings::GlobalSettings::max_path_length {10000, "max_path_length", this} |
Maximal length a og::PathGeometric can have to be interpolated.
Property<double> PlannerSettings::GlobalSettings::max_planning_time {15, "max_planning_time", this} |
PlannerSettings::GlobalSettings::OmplSettings PlannerSettings::GlobalSettings::ompl |
PlannerSettings::GlobalSettings::SbplSettings PlannerSettings::GlobalSettings::sbpl |
PlannerSettings::GlobalSettings::SmoothingSettings PlannerSettings::GlobalSettings::smoothing |
PlannerSettings::GlobalSettings::SteerSettings PlannerSettings::GlobalSettings::steer |
PlannerSettings::GlobalSettings::ThetaStarSettings PlannerSettings::GlobalSettings::theta_star |
PlannerSettings::GlobalSettings::EnvironmentSettings PlannerSettings::GlobalSettings::this |
PlannerSettings::GlobalSettings::BenchmarkSettings PlannerSettings::GlobalSettings::this |
PlannerSettings::GlobalSettings::OmplSettings PlannerSettings::GlobalSettings::this |
PlannerSettings::GlobalSettings::SteerSettings PlannerSettings::GlobalSettings::this |
PlannerSettings::GlobalSettings::ForwardPropagationSettings PlannerSettings::GlobalSettings::this |
PlannerSettings::GlobalSettings::SbplSettings PlannerSettings::GlobalSettings::this |
PlannerSettings::GlobalSettings::SmoothingSettings PlannerSettings::GlobalSettings::this |
PlannerSettings::GlobalSettings::ThetaStarSettings PlannerSettings::GlobalSettings::this |