AmclParams Struct Reference

AmclParams Struct Reference#

Beluga ROS: beluga_ros::AmclParams Struct Reference
Beluga ROS
beluga_ros::AmclParams Struct Reference

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

#include <amcl.hpp>

Public Attributes

double update_min_d = 0.25
 Translational movement required from last resample for resampling to happen again.
 
double update_min_a = 0.2
 Rotational movement required from last resample for resampling to happen again.
 
std::size_t resample_interval = 1UL
 Number of filter updates required before resampling.
 
bool selective_resampling = false
 Whether to enable selective resampling [2] 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.
 
std::size_t min_particles = 500UL
 Minimum allowed number of particles.
 
std::size_t max_particles = 2000UL
 Maximum allowed number of particles.
 
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 [3] .
 
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 [3] .
 
double kld_epsilon = 0.05
 Maximum particle filter population error between the true distribution and the estimated distribution. It is used in KLD resampling [1] to limit the allowed number of particles to the minimum necessary.
 
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 [1] .
 
double spatial_resolution_x = 0.5
 Spatial resolution along the x-axis to create buckets for KLD resampling.
 
double spatial_resolution_y = 0.5
 Spatial resolution along the y-axis to create buckets for KLD resampling.
 
double spatial_resolution_theta = 10 * Sophus::Constants<double>::pi() / 180
 Spatial resolution around the z-axis to create buckets for KLD resampling.
 

Detailed Description

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


The documentation for this struct was generated from the following file:
  • /home/runner/work/beluga/beluga/beluga_ros/include/beluga_ros/amcl.hpp