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

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

#include <amcl.hpp>

Public Attributes

double alpha_fast = 0.1
 Exponential decay rate for the fast average weight filter, used in deciding when to recover from a bad approximation by adding random poses [thrun2005probabilistic] . More...
 
double alpha_slow = 0.001
 Exponential decay rate for the slow average weight filter, used in deciding when to recover from a bad approximation by adding random poses [thrun2005probabilistic] . More...
 
double kld_epsilon = 0.05
 Maximum particle filter population error between the true distribution and the estimated distribution. It is used in KLD resampling [fox2001adaptivekldsampling] to limit the allowed number of particles to the minimum necessary. More...
 
double kld_z = 3.0
 Upper standard normal quantile for $P$, where $P$ is the probability that the error in the estimated distribution will be less than kld_epsilon in KLD resampling [fox2001adaptivekldsampling] . More...
 
std::size_t max_particles = 2000UL
 Maximum allowed number of particles. More...
 
std::size_t min_particles = 500UL
 Minimum allowed number of particles. More...
 
std::size_t resample_interval = 1UL
 Number of filter updates required before resampling. More...
 
bool selective_resampling = false
 Whether to enable selective resampling [grisetti2007selectiveresampling] to help avoid loss of diversity in the particle population. The resampling step will only happen if the effective number of particles ( $N_{eff} = 1/ {\sum w_i^2}$) is lower than half the current number of particles, where $w_i$ refers to the normalized weight of each particle. More...
 
double spatial_resolution_theta = 10 * Sophus::Constants<double>::pi() / 180
 Spatial resolution around the z-axis to create buckets for KLD resampling. More...
 
double spatial_resolution_x = 0.5
 Spatial resolution along the x-axis to create buckets for KLD resampling. More...
 
double spatial_resolution_y = 0.5
 Spatial resolution along the y-axis to create buckets for KLD resampling. More...
 
double update_min_a = 0.2
 Rotational movement required from last resample for resampling to happen again. More...
 
double update_min_d = 0.25
 Translational movement required from last resample for resampling to happen again. More...
 

Detailed Description

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

Definition at line 36 of file amcl.hpp.

Member Data Documentation

◆ alpha_fast

double beluga_ros::AmclParams::alpha_fast = 0.1

Exponential decay rate for the fast average weight filter, used in deciding when to recover from a bad approximation by adding random poses [thrun2005probabilistic] .

Definition at line 65 of file amcl.hpp.

◆ alpha_slow

double beluga_ros::AmclParams::alpha_slow = 0.001

Exponential decay rate for the slow average weight filter, used in deciding when to recover from a bad approximation by adding random poses [thrun2005probabilistic] .

Definition at line 61 of file amcl.hpp.

◆ kld_epsilon

double beluga_ros::AmclParams::kld_epsilon = 0.05

Maximum particle filter population error between the true distribution and the estimated distribution. It is used in KLD resampling [fox2001adaptivekldsampling] to limit the allowed number of particles to the minimum necessary.

Definition at line 70 of file amcl.hpp.

◆ kld_z

double beluga_ros::AmclParams::kld_z = 3.0

Upper standard normal quantile for $P$, where $P$ is the probability that the error in the estimated distribution will be less than kld_epsilon in KLD resampling [fox2001adaptivekldsampling] .

Definition at line 74 of file amcl.hpp.

◆ max_particles

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

Maximum allowed number of particles.

Definition at line 57 of file amcl.hpp.

◆ min_particles

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

Minimum allowed number of particles.

Definition at line 54 of file amcl.hpp.

◆ resample_interval

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

Number of filter updates required before resampling.

Definition at line 44 of file amcl.hpp.

◆ selective_resampling

bool beluga_ros::AmclParams::selective_resampling = false

Whether to enable selective resampling [grisetti2007selectiveresampling] to help avoid loss of diversity in the particle population. The resampling step will only happen if the effective number of particles ( $N_{eff} = 1/ {\sum w_i^2}$) is lower than half the current number of particles, where $w_i$ refers to the normalized weight of each particle.

Definition at line 51 of file amcl.hpp.

◆ spatial_resolution_theta

double beluga_ros::AmclParams::spatial_resolution_theta = 10 * Sophus::Constants<double>::pi() / 180

Spatial resolution around the z-axis to create buckets for KLD resampling.

Definition at line 83 of file amcl.hpp.

◆ spatial_resolution_x

double beluga_ros::AmclParams::spatial_resolution_x = 0.5

Spatial resolution along the x-axis to create buckets for KLD resampling.

Definition at line 77 of file amcl.hpp.

◆ spatial_resolution_y

double beluga_ros::AmclParams::spatial_resolution_y = 0.5

Spatial resolution along the y-axis to create buckets for KLD resampling.

Definition at line 80 of file amcl.hpp.

◆ update_min_a

double beluga_ros::AmclParams::update_min_a = 0.2

Rotational movement required from last resample for resampling to happen again.

Definition at line 41 of file amcl.hpp.

◆ update_min_d

double beluga_ros::AmclParams::update_min_d = 0.25

Translational movement required from last resample for resampling to happen again.

Definition at line 38 of file amcl.hpp.


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


beluga_ros
Author(s):
autogenerated on Tue Jul 16 2024 03:00:02