Skip to content
Chapter 2 · Particle FiltersLesson 2.2

Monte Carlo Localization

Approximating beliefs with weighted samples; sampling, weighting, resampling.

A short intro to PF and Monte Carlo Localization

The Kalman filter and its variants only model Gaussian beliefs. The particle filter drops that restriction:

  • Use multiple samples (particles) to represent the belief over a pose.
  • The more samples in a region, the higher the probability there.
  • Each particle has a weight; larger weight ⇒ higher probability.

Particle set

The particles are a set of weighted samples:

where is a state hypothesis and is its importance weight. The samples represent the posterior as a sum of Dirac deltas:

Note. More accurate representation needs more samples. The bigger or more complex the distribution, the more samples — and that directly drives compute cost.

VisualizationSample-based representation
-4-2024
200 particles drawn from the bimodal mixture. The denser the particle cloud in a region, the higher the implied probability mass.

Switch between a unimodal Gaussian and a bimodal mixture and watch how the rug-mark density on the x-axis tracks the true PDF. Crank the particle count down to a handful and the approximation gets blocky; crank it up and the histogram smooths out toward the curve.

How do we obtain such samples?

Closed-form sampling is only possible for a few distributions (e.g. Gaussian). For arbitrary distributions, use importance sampling.

Importance sampling principle

Use a different proposal distribution to generate samples and account for the difference with a weight:

Pre-condition: if then .

VisualizationImportance sampling — how proposal width matters
-4-2024target f(x)proposal g(x)IS weighted
Target f(x) is the bimodal density (red). Proposal g(x) = N(0, σ²) (grey). The bars are the IS-weighted estimate of f(x). Effective sample size: 1162 / 2000.

A good (broad) proposal covers both modes of the bimodal target — the weighted bars follow closely and the effective sample size is high. A bad (narrow) proposal misses the left mode entirely; a few extreme weights dominate and the ESS collapses — the estimate is noisy even with thousands of samples.

Takeaway. A well-matched proposal yields a weighted histogram that closely follows . A poor proposal leads to a few dominating weights and a noisy approximation.

Particle filter (PF)

The particle filter is a realization of the recursive Bayes filter — specifically a non-parametric approach that does not maintain a closed-form distribution.

The two Bayes-filter steps become:

  • Prediction step. Draw samples from the proposal distribution (use the motion model to sample).
  • Correction step. Use the observations to compute the correction (weights).

The more samples we use, the better our estimate.

Particle filter algorithm

algorithmParticle_Filter(𝒳_{t-1}, u_t, z_t)
  1. X̄_t = X_t = ∅# init
  2. for j = 1 to J:# iterate over previous samples
  3. x_t^{[j]} ~ π(x_t)# sample from proposal
  4. w_t^{[j]} = p(x_t^{[j]}) / π(x_t^{[j]})# importance weight
  5. X̄_t = X̄_t ∪ ⟨x_t^{[j]}, w_t^{[j]}⟩# add to predicted set
  6. for j = 1 to J:# resample
  7. draw i ∈ 1..J with probability ∝ w_t^{[i]}# draw i ∝ weights
  8. add x_t^{[i]} to X_t# copy particle
  9. return X_t

Monte Carlo Localization (MCL)

When we only localize and assume a known map (e.g., an occupancy grid), the particle filter specializes to Monte Carlo Localization (MCL).

  • Each particle is a pose hypothesis.
  • Proposal is the motion model:
  • Correction uses the observation model with known map :

Compared to the generic particle filter algorithm, lines 3 and 4 become:

  • Sample from motion model:
  • Weight by observation likelihood:

Note. The particle filter becomes MCL when we choose the motion model as the proposal. A more detailed derivation shows that the importance weight then becomes proportional to the observation likelihood.

Resampling

Resampling reallocates our limited particle budget — low-weight (unlikely) samples die out, high-weight (likely) ones get replicated, so the particle set better captures the belief at each step.

  • Prune low-weight particles — weak hypotheses die out.
  • Replicate high-weight particles — stronger hypotheses.
  • Concentrate computational effort on high-probability regions of the state space.
  • "Survival of the fittest" — avoids many samples covering unlikely states.

Resampling methods

Roulette wheel resampling

  • Build the cumulative sum (CDF) of normalized weights.
  • Draw independent uniforms .
  • For each , find the first CDF bin (binary search) and copy that particle.
  • Complexity: .
  • Simple but higher variance — a few high-weight particles may be chosen many times.

Stochastic Universal Sampling (SUS)

  • Build the CDF of normalized weights.
  • Draw a single random offset .
  • Place equally spaced pointers at
  • For each pointer, select the first CDF bin pointer and copy that particle.
  • Complexity: .
  • Low variance — allocations are closer to expected counts, reducing sample impoverishment.
VisualizationResampling — roulette wheel vs. stochastic universal sampling
weighted CDF0123456789101112131516171819evenly-spaced pointersresulting offspring count per particle11211111211112111
Top: CDF strip of 20 weighted particles (wider bin = higher weight). Middle: where the 20 pointers land. Bottom: how many copies each particle gets.

The top strip shows the CDF — each bin's width is proportional to the particle's weight. The middle strip shows the pointers (red): random for roulette wheel, evenly spaced for SUS. The bottom histogram shows the resulting offspring count per particle. Switch methods and reseed a few times: roulette is much "lumpier" than SUS even though both sample the same CDF.

A working MCL example

VisualizationMonte Carlo Localization (MCL)
step 0 · GT (green) · estimate (yellow) · particles (red)
Particles (red dots) start scattered randomly across the free space. As the robot drives, each particle predicts via the motion model and is reweighted by how well its simulated LiDAR scan matches the real one. Resampling concentrates particles on the true pose.

This is Monte Carlo Localization running in your browser: 300 particles start scattered across the free space with random orientations. The green robot follows a pre-set trajectory. Each tick: every particle is pushed by the motion model + noise, then weighted by how well its simulated LiDAR scan matches the real one, then we resample if the effective sample size drops below half. Within a couple of seconds the red particle cloud collapses onto the green robot — that's the filter "locking on".

What we implemented beyond the textbook MCL

The notebook ships a Pygame demo with a few practical tricks on top of the textbook algorithm:

  • Likelihood-field sensor model (endpoint distance). Instead of the full probabilistic beam model, precompute a distance field of the occupancy map and score each particle by how close beam endpoints fall to walls. Fast and stable. Tuning knob: sigma_hit (px std around the endpoint).
  • Beam subsampling + hit-only beams. Using every -th beam cuts measurement cost by ~ with minor accuracy loss. Ignoring max-range beams (which are weakly informative in the likelihood-field model) stabilizes the update in structured maps.
  • Pixel-quantized particles. Snap each particle's to integer pixel centers so visualization is crisp and map collision checks are simple. Keep continuous.
  • Top-K read-out + EMA smoothing. Compute the displayed estimate from the top-K% particles by weight (less mean-of-modes bias) and smooth with an EMA (visualization only — the filter state is untouched).
  • Systematic resampling + random injection. Resample only when ESS drops below a threshold; after resampling, inject a small fraction of random free-space particles to combat impoverishment and recover from kidnapping.

Summary

  • Particle filters are non-parametric recursive Bayes filters.
  • The posterior is represented by a set of weighted samples.
  • Propose to draw samples.
  • Weight to account for the difference between proposal and target.
  • Work well in low-dimensional spaces.
  • Monte Carlo Localization is a particle filter where:
    • Particles are propagated according to the motion model.
    • They are weighted according to the observation likelihood.

Reading material

Particle filter

  • Thrun, Burgard, Fox. Probabilistic Robotics, Chapter 3.

Monte Carlo Localization

  • Thrun, Burgard, Fox. Probabilistic Robotics, §8.3.