Public Attributes | List of all members
beluga::AmclParams Struct Reference

Struct containing parameters for the Adaptive Monte Carlo Localization (AMCL) implementation. More...

#include <amcl_core.hpp>

Public Attributes

double alpha_fast = 0.1
 Used as part of the recovery mechanism when considering how many random particles to insert. More...
 
double alpha_slow = 0.001
 Used as part of the recovery mechanism when considering how many random particles to insert. More...
 
double kld_epsilon = 0.05
 Used as part of the kld sampling mechanism. More...
 
double kld_z = 3.0
 Used as part of the kld sampling mechanism. More...
 
std::size_t max_particles = 2000UL
 Maximum number of particles in the filter at any point in time. More...
 
std::size_t min_particles = 500UL
 Minimum number of particles in the filter at any point in time. More...
 
std::size_t resample_interval = 1UL
 Filter iterations interval at which a resampling will happen, unitless. More...
 
bool selective_resampling = false
 Whether to use selective resampling or not. More...
 
double update_min_a = 0.2
 Min angular distance in radians between updates. More...
 
double update_min_d = 0.25
 Min distance in meters between updates. More...
 

Detailed Description

Struct containing parameters for the Adaptive Monte Carlo Localization (AMCL) implementation.

Definition at line 33 of file amcl_core.hpp.

Member Data Documentation

◆ alpha_fast

double beluga::AmclParams::alpha_fast = 0.1

Used as part of the recovery mechanism when considering how many random particles to insert.

Definition at line 49 of file amcl_core.hpp.

◆ alpha_slow

double beluga::AmclParams::alpha_slow = 0.001

Used as part of the recovery mechanism when considering how many random particles to insert.

Definition at line 47 of file amcl_core.hpp.

◆ kld_epsilon

double beluga::AmclParams::kld_epsilon = 0.05

Used as part of the kld sampling mechanism.

Definition at line 51 of file amcl_core.hpp.

◆ kld_z

double beluga::AmclParams::kld_z = 3.0

Used as part of the kld sampling mechanism.

Definition at line 53 of file amcl_core.hpp.

◆ max_particles

std::size_t beluga::AmclParams::max_particles = 2000UL

Maximum number of particles in the filter at any point in time.

Definition at line 45 of file amcl_core.hpp.

◆ min_particles

std::size_t beluga::AmclParams::min_particles = 500UL

Minimum number of particles in the filter at any point in time.

Definition at line 43 of file amcl_core.hpp.

◆ resample_interval

std::size_t beluga::AmclParams::resample_interval = 1UL

Filter iterations interval at which a resampling will happen, unitless.

Definition at line 39 of file amcl_core.hpp.

◆ selective_resampling

bool beluga::AmclParams::selective_resampling = false

Whether to use selective resampling or not.

Definition at line 41 of file amcl_core.hpp.

◆ update_min_a

double beluga::AmclParams::update_min_a = 0.2

Min angular distance in radians between updates.

Definition at line 37 of file amcl_core.hpp.

◆ update_min_d

double beluga::AmclParams::update_min_d = 0.25

Min distance in meters between updates.

Definition at line 35 of file amcl_core.hpp.


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


beluga
Author(s):
autogenerated on Tue Jul 16 2024 02:59:53