Struct HATebConfig::Obstacles
Defined in File hateb_config.h
Nested Relationships
This struct is a nested type of Class HATebConfig.
Struct Documentation
-
struct Obstacles
Obstacle related parameters.
Public Members
-
double min_obstacle_dist
Minimum desired separation from obstacles.
-
double inflation_dist
buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect)
-
bool use_nonlinear_obstacle_penalty
-
double obstacle_cost_mult
-
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)
-
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.
-
bool include_costmap_obstacles
Specify whether the obstacles in the costmap should be taken into account directly.
-
double costmap_obstacles_behind_robot_dist
Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify distance in meters)
-
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.
-
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).
-
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.
-
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.
-
std::string costmap_converter_plugin
Define a plugin name of the costmap_converter package (costmap cells are converted to points/lines/polygons)
-
bool costmap_converter_spin_thread
If
true, the costmap converter invokes its callback queue in a different thread.
-
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)
-
double min_obstacle_dist