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

Optimization related parameters. More...

#include <teb_config.h>

Public Attributes

int no_inner_iterations
 Number of solver iterations called in each outerloop iteration. More...
 
int no_outer_iterations
 Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with no_inner_iterations. More...
 
double obstacle_cost_exponent
 Exponent for nonlinear obstacle cost (cost = linear_cost * obstacle_cost_exponent). Set to 1 to disable nonlinear cost (default) More...
 
bool optimization_activate
 Activate the optimization. More...
 
bool optimization_verbose
 Print verbose information. More...
 
double penalty_epsilon
 Add a small safety margin to penalty functions for hard-constraint approximations. More...
 
double weight_acc_lim_theta
 Optimization weight for satisfying the maximum allowed angular acceleration. More...
 
double weight_acc_lim_x
 Optimization weight for satisfying the maximum allowed translational acceleration. More...
 
double weight_acc_lim_y
 Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonomic robots) More...
 
double weight_adapt_factor
 Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer TEB iteration (weight_new = weight_old*factor); Increasing weights iteratively instead of setting a huge value a-priori leads to better numerical conditions of the underlying optimization problem. More...
 
double weight_dynamic_obstacle
 Optimization weight for satisfying a minimum separation from dynamic obstacles. More...
 
double weight_dynamic_obstacle_inflation
 Optimization weight for the inflation penalty of dynamic obstacles (should be small) More...
 
double weight_inflation
 Optimization weight for the inflation penalty (should be small) More...
 
double weight_kinematics_forward_drive
 Optimization weight for forcing the robot to choose only forward directions (positive transl. velocities, only diffdrive robot) More...
 
double weight_kinematics_nh
 Optimization weight for satisfying the non-holonomic kinematics. More...
 
double weight_kinematics_turning_radius
 Optimization weight for enforcing a minimum turning radius (carlike robots) More...
 
double weight_max_vel_theta
 Optimization weight for satisfying the maximum allowed angular velocity. More...
 
double weight_max_vel_x
 Optimization weight for satisfying the maximum allowed translational velocity. More...
 
double weight_max_vel_y
 Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic robots) More...
 
double weight_obstacle
 Optimization weight for satisfying a minimum separation from obstacles. More...
 
double weight_optimaltime
 Optimization weight for contracting the trajectory w.r.t. transition time. More...
 
double weight_prefer_rotdir
 Optimization weight for preferring a specific turning direction (-> currently only activated if an oscillation is detected, see 'oscillation_recovery'. More...
 
double weight_shortest_path
 Optimization weight for contracting the trajectory w.r.t. path length. More...
 
double weight_viapoint
 Optimization weight for minimizing the distance to via-points. More...
 

Detailed Description

Optimization related parameters.

Definition at line 136 of file teb_config.h.

Member Data Documentation

int teb_local_planner::TebConfig::Optimization::no_inner_iterations

Number of solver iterations called in each outerloop iteration.

Definition at line 138 of file teb_config.h.

int teb_local_planner::TebConfig::Optimization::no_outer_iterations

Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with no_inner_iterations.

Definition at line 139 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::obstacle_cost_exponent

Exponent for nonlinear obstacle cost (cost = linear_cost * obstacle_cost_exponent). Set to 1 to disable nonlinear cost (default)

Definition at line 165 of file teb_config.h.

bool teb_local_planner::TebConfig::Optimization::optimization_activate

Activate the optimization.

Definition at line 141 of file teb_config.h.

bool teb_local_planner::TebConfig::Optimization::optimization_verbose

Print verbose information.

Definition at line 142 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::penalty_epsilon

Add a small safety margin to penalty functions for hard-constraint approximations.

Definition at line 144 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_acc_lim_theta

Optimization weight for satisfying the maximum allowed angular acceleration.

Definition at line 151 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_acc_lim_x

Optimization weight for satisfying the maximum allowed translational acceleration.

Definition at line 149 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_acc_lim_y

Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonomic robots)

Definition at line 150 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_adapt_factor

Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer TEB iteration (weight_new = weight_old*factor); Increasing weights iteratively instead of setting a huge value a-priori leads to better numerical conditions of the underlying optimization problem.

Definition at line 164 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_dynamic_obstacle

Optimization weight for satisfying a minimum separation from dynamic obstacles.

Definition at line 159 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_dynamic_obstacle_inflation

Optimization weight for the inflation penalty of dynamic obstacles (should be small)

Definition at line 160 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_inflation

Optimization weight for the inflation penalty (should be small)

Definition at line 158 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_kinematics_forward_drive

Optimization weight for forcing the robot to choose only forward directions (positive transl. velocities, only diffdrive robot)

Definition at line 153 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_kinematics_nh

Optimization weight for satisfying the non-holonomic kinematics.

Definition at line 152 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_kinematics_turning_radius

Optimization weight for enforcing a minimum turning radius (carlike robots)

Definition at line 154 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_max_vel_theta

Optimization weight for satisfying the maximum allowed angular velocity.

Definition at line 148 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_max_vel_x

Optimization weight for satisfying the maximum allowed translational velocity.

Definition at line 146 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_max_vel_y

Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic robots)

Definition at line 147 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_obstacle

Optimization weight for satisfying a minimum separation from obstacles.

Definition at line 157 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_optimaltime

Optimization weight for contracting the trajectory w.r.t. transition time.

Definition at line 155 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_prefer_rotdir

Optimization weight for preferring a specific turning direction (-> currently only activated if an oscillation is detected, see 'oscillation_recovery'.

Definition at line 162 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_shortest_path

Optimization weight for contracting the trajectory w.r.t. path length.

Definition at line 156 of file teb_config.h.

double teb_local_planner::TebConfig::Optimization::weight_viapoint

Optimization weight for minimizing the distance to via-points.

Definition at line 161 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 3 2020 04:03:08