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

Obstacle related parameters. More...

#include <teb_config.h>

Public Attributes

std::string costmap_converter_plugin
 Define a plugin name of the costmap_converter package (costmap cells are converted to points/lines/polygons) More...
 
int costmap_converter_rate
 The rate that defines how often the costmap_converter plugin processes the current costmap (the value should not be much higher than the costmap update rate) More...
 
bool costmap_converter_spin_thread
 If true, the costmap converter invokes its callback queue in a different thread. More...
 
double costmap_obstacles_behind_robot_dist
 Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify distance in meters) More...
 
double dynamic_obstacle_inflation_dist
 Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect) More...
 
bool include_costmap_obstacles
 Specify whether the obstacles in the costmap should be taken into account directly. More...
 
bool include_dynamic_obstacles
 Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (this also effects homotopy class planning); If false, all obstacles are considered to be static. More...
 
double inflation_dist
 buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect) More...
 
bool legacy_obstacle_association
 If true, the old association strategy is used (for each obstacle, find the nearest TEB pose), otherwise the new one (for each teb pose, find only "relevant" obstacles). More...
 
double min_obstacle_dist
 Minimum desired separation from obstacles. More...
 
double obstacle_association_cutoff_factor
 See obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist all obstacles are ignored during optimization. obstacle_association_force_inclusion_factor is processed first. More...
 
double obstacle_association_force_inclusion_factor
 The non-legacy obstacle association technique tries to connect only relevant obstacles with the discretized trajectory during optimization, all obstacles within a specifed distance are forced to be included (as a multiple of min_obstacle_dist), e.g. choose 2.0 in order to consider obstacles within a radius of 2.0*min_obstacle_dist. More...
 
int obstacle_poses_affected
 The obstacle position is attached to the closest pose on the trajectory to reduce computational effort, but take a number of neighbors into account as well. More...
 

Detailed Description

Obstacle related parameters.

Definition at line 117 of file teb_config.h.

Member Data Documentation

std::string teb_local_planner::TebConfig::Obstacles::costmap_converter_plugin

Define a plugin name of the costmap_converter package (costmap cells are converted to points/lines/polygons)

Definition at line 129 of file teb_config.h.

int teb_local_planner::TebConfig::Obstacles::costmap_converter_rate

The rate that defines how often the costmap_converter plugin processes the current costmap (the value should not be much higher than the costmap update rate)

Definition at line 131 of file teb_config.h.

bool teb_local_planner::TebConfig::Obstacles::costmap_converter_spin_thread

If true, the costmap converter invokes its callback queue in a different thread.

Definition at line 130 of file teb_config.h.

double teb_local_planner::TebConfig::Obstacles::costmap_obstacles_behind_robot_dist

Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify distance in meters)

Definition at line 124 of file teb_config.h.

double teb_local_planner::TebConfig::Obstacles::dynamic_obstacle_inflation_dist

Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect)

Definition at line 121 of file teb_config.h.

bool teb_local_planner::TebConfig::Obstacles::include_costmap_obstacles

Specify whether the obstacles in the costmap should be taken into account directly.

Definition at line 123 of file teb_config.h.

bool teb_local_planner::TebConfig::Obstacles::include_dynamic_obstacles

Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (this also effects homotopy class planning); If false, all obstacles are considered to be static.

Definition at line 122 of file teb_config.h.

double teb_local_planner::TebConfig::Obstacles::inflation_dist

buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect)

Definition at line 120 of file teb_config.h.

bool teb_local_planner::TebConfig::Obstacles::legacy_obstacle_association

If true, the old association strategy is used (for each obstacle, find the nearest TEB pose), otherwise the new one (for each teb pose, find only "relevant" obstacles).

Definition at line 126 of file teb_config.h.

double teb_local_planner::TebConfig::Obstacles::min_obstacle_dist

Minimum desired separation from obstacles.

Definition at line 119 of file teb_config.h.

double teb_local_planner::TebConfig::Obstacles::obstacle_association_cutoff_factor

See obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist all obstacles are ignored during optimization. obstacle_association_force_inclusion_factor is processed first.

Definition at line 128 of file teb_config.h.

double teb_local_planner::TebConfig::Obstacles::obstacle_association_force_inclusion_factor

The non-legacy obstacle association technique tries to connect only relevant obstacles with the discretized trajectory during optimization, all obstacles within a specifed distance are forced to be included (as a multiple of min_obstacle_dist), e.g. choose 2.0 in order to consider obstacles within a radius of 2.0*min_obstacle_dist.

Definition at line 127 of file teb_config.h.

int teb_local_planner::TebConfig::Obstacles::obstacle_poses_affected

The obstacle position is attached to the closest pose on the trajectory to reduce computational effort, but take a number of neighbors into account as well.

Definition at line 125 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