at-wat / mcl_3dl

A ROS node to perform a probabilistic 3-D/6-DOF localization system for mobile robots with 3-D LIDAR(s). It implements pointcloud based Monte Carlo localization that uses a reference pointcloud as a map.
BSD 3-Clause "New" or "Revised" License
475 stars 117 forks source link

use of entropy #385

Closed remco-r closed 3 years ago

remco-r commented 3 years ago

The status topic outputs entropy.

Calculation happens like this:


 float getEntropy()
  {
    float sum = 0.0f;
    for (auto& particle : *pf_)
    {
      sum += particle.probability_;
    }

    float entropy = 0.0f;
    for (auto& particle : *pf_)
    {
      if (particle.probability_ / sum > 0.0)
        entropy += particle.probability_ / sum * std::log(particle.probability_ / sum);
    }

    return -entropy;
  }

sum does not have to be calculated. Its always 1.0, because particle.probability_ = 1/particles.size(). Then, entropy is always the same number if the particle size does not change. Particle size only changes when doing global localization. This is the only moment you can see the entropy going down.

What use is this metric if its not used in the code, and there is already particle_size present in the status output?

remco-r commented 3 years ago

i filed this too soon. probability is initialized as 1/particle_size and then in the measure step updated with likelihood. However still the sum will be near 1.0 and the entropy will not change, at least not in the printable digits.

at-wat commented 3 years ago

FYI @DaikiMaekawa (https://github.com/at-wat/mcl_3dl/pull/265)