SteveMacenski / slam_toolbox

Slam Toolbox for lifelong mapping and localization in potentially massive maps with ROS
GNU Lesser General Public License v2.1
1.59k stars 507 forks source link

Extracting exact cell occupancy alongside cell state result. #722

Open Paskul opened 1 month ago

Paskul commented 1 month ago

Feature description

I'm looking to extract the exact probability for occupancy of cells within the generating occupancy grid. I see slam_toolbox works in 3 states of occupied, free, and unknown, but I'm wondering if there is a way to extract something like hitRatio in updateCell() of Karto.h, as I believe this might be the exact value I am looking for. An example of a final product could include a state where a cell has an 80% likelihood that an obstacle exists in its current conditions (likely calculated from cellPassCnt and cellHitCnt), to be extracted as a message, and when the map updates, this value or likelihood would change, say to 70%. Working with messages in ROS2 is new to me and in the scale of this repo I'm unsure where I would implement this myself.

Implementation considerations

It might cause more harm than good to entirely replace cell state values: occupied, free, and unknown - but instead a new variable/message could be used to extract this cell probability information without replacing the entire state estimation already built. I saw a previous PR where covariance was added as a message in this topic leading to this pr, though I am still confused as to how I could implement this for my own needs.

SteveMacenski commented 1 month ago

We do not currently expose this information in any externally consumable output. That would need to have changes to the software so that this information can be extracted and published when generating the occupancy grid in the update map thread.

I saw a previous PR where covariance was added as a message in https://github.com/SteveMacenski/slam_toolbox/issues/427 leading to https://github.com/SteveMacenski/slam_toolbox/pull/508, though I am still confused as to how I could implement this for my own needs.

I don't think either of those help you in what you're looking for. That's w.r.t. pose, not the occ grid

Paskul commented 1 month ago

Thanks, I see. In making the code changes then, I see the OccupancyGrid with CellUpdater and I feel as if I can make immediate changes to expose hitRatio to the OccupancyGrid class, but what suggestions might you have to put this through to a message/topic? Where/how is the occupancy grid extracted to msgs in this repo?

SteveMacenski commented 1 month ago

I don't know how you'd like to consume that hit vs miss data, but something along the lines of the structure of the occupancy grid is probably good