Public Attributes | List of all members
teb_local_planner::TebConfig::Recovery Struct Reference

Recovery/backup related parameters. More...

#include <teb_config.h>

Public Attributes

double oscillation_filter_duration
 Filter length/duration [sec] for the detection of oscillations. More...
 
double oscillation_omega_eps
 Threshold for the average normalized angular velocity: if oscillation_v_eps and oscillation_omega_eps are not exceeded both, a possible oscillation is detected. More...
 
bool oscillation_recovery
 Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robot frequently switches between left/right/forward/backwards) More...
 
double oscillation_recovery_min_duration
 Minumum duration [sec] for which the recovery mode is activated after an oscillation is detected. More...
 
double oscillation_v_eps
 Threshold for the average normalized linear velocity: if oscillation_v_eps and oscillation_omega_eps are not exceeded both, a possible oscillation is detected. More...
 
bool shrink_horizon_backup
 Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues. More...
 
double shrink_horizon_min_duration
 Specify minimum duration for the reduced horizon in case an infeasible trajectory is detected. More...
 

Detailed Description

Recovery/backup related parameters.

Definition at line 192 of file teb_config.h.

Member Data Documentation

double teb_local_planner::TebConfig::Recovery::oscillation_filter_duration

Filter length/duration [sec] for the detection of oscillations.

Definition at line 200 of file teb_config.h.

double teb_local_planner::TebConfig::Recovery::oscillation_omega_eps

Threshold for the average normalized angular velocity: if oscillation_v_eps and oscillation_omega_eps are not exceeded both, a possible oscillation is detected.

Definition at line 198 of file teb_config.h.

bool teb_local_planner::TebConfig::Recovery::oscillation_recovery

Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robot frequently switches between left/right/forward/backwards)

Definition at line 196 of file teb_config.h.

double teb_local_planner::TebConfig::Recovery::oscillation_recovery_min_duration

Minumum duration [sec] for which the recovery mode is activated after an oscillation is detected.

Definition at line 199 of file teb_config.h.

double teb_local_planner::TebConfig::Recovery::oscillation_v_eps

Threshold for the average normalized linear velocity: if oscillation_v_eps and oscillation_omega_eps are not exceeded both, a possible oscillation is detected.

Definition at line 197 of file teb_config.h.

bool teb_local_planner::TebConfig::Recovery::shrink_horizon_backup

Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues.

Definition at line 194 of file teb_config.h.

double teb_local_planner::TebConfig::Recovery::shrink_horizon_min_duration

Specify minimum duration for the reduced horizon in case an infeasible trajectory is detected.

Definition at line 195 of file teb_config.h.


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


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 5 2019 19:25:10