Skip to content

[collision_monitor] Add temporal debounce for min_points trigger#6006

Merged
SteveMacenski merged 7 commits intoros-navigation:mainfrom
Neomelt:fix/4364-temporal-min-points
Mar 18, 2026
Merged

[collision_monitor] Add temporal debounce for min_points trigger#6006
SteveMacenski merged 7 commits intoros-navigation:mainfrom
Neomelt:fix/4364-temporal-min-points

Conversation

@Neomelt
Copy link
Contributor

@Neomelt Neomelt commented Mar 5, 2026

Basic Info

Info Please fill out this column
Ticket(s) this addresses #4364
Primary OS tested on Ubuntu 24.04 (ROS 2 Jazzy)
Robotic platform tested on bag replay (Livox pointcloud dataset), no physical robot yet
Does this PR contain AI generated software? No
Was this PR description generated by AI software? No

Description of contribution in a few bullet points

  • Adds temporal debounce / hysteresis to polygon min_points trigger evaluation in nav2_collision_monitor
  • Introduces two per-polygon parameters with backward-compatible defaults:
    • trigger_consecutive_points (default 1)
    • release_consecutive_points (default 1)
  • Integrates the debounce decision into processStopSlowdownLimit() for STOP / SLOWDOWN / LIMIT
  • Keeps previous behavior unchanged when both parameters remain 1
  • Adds runtime parameter update handling for these new parameters and resets internal debounce state on updates

Description of documentation updates required from your changes

  • Add parameter docs for:
    • trigger_consecutive_points
    • release_consecutive_points
  • Mention temporal debounce tuning guidance in collision monitor tuning docs (recommended baseline from this test: start with 3/3)

Description of how this change was tested

  • Build validation (Jazzy overlay):
    • colcon build --packages-up-to nav2_collision_monitor --symlink-install --cmake-args -DBUILD_TESTING=OFF
  • Replay validation against issue scenario (same bag and runtime setup per run):
    • bag: /home/neomelt/Downloads/indoor_2min_bag/
    • source topic: /livox/lidar (pointcloud)
    • command input: dedicated /cm_cmd_vel_stamped
    • static TF added for replay wiring:
      • odom -> base_footprint
      • base_footprint -> livox_frame
  • Measured action_type switching count from /collision_monitor_state:
    • 1/1: samples=16, switches=15
    • 3/3: samples=10, switches=9
    • 4/4: samples=10, switches=9
    • 5/5: samples=10, switches=9
    • 2/4: samples=15, switches=14
    • 2/5: samples=15, switches=14
    • 3/5: samples=10, switches=9
  • Summary: 3/3 reduces toggling versus baseline (15 -> 9, ~40% reduction in this replay)

Future work that may be required in bullet points

  • Add focused unit tests for debounce state transitions (trigger/release counters and reset behavior)
  • Extend validation on additional bags and a full nav stack setup (non-injected TF path)
  • Add physical robot validation to tune defaults per sensor modality

Closes #4364

@codecov
Copy link

codecov bot commented Mar 5, 2026

Codecov Report

❌ Patch coverage is 96.29630% with 2 lines in your changes missing coverage. Please review.

Files with missing lines Patch % Lines
nav2_collision_monitor/src/polygon.cpp 96.15% 2 Missing ⚠️
Files with missing lines Coverage Δ
..._collision_monitor/src/collision_detector_node.cpp 97.26% <100.00%> (-0.04%) ⬇️
...2_collision_monitor/src/collision_monitor_node.cpp 97.01% <100.00%> (ø)
nav2_collision_monitor/src/polygon.cpp 96.89% <96.15%> (-0.15%) ⬇️

... and 5 files with indirect coverage changes

🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

Copy link
Collaborator

@mini-1235 mini-1235 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@gennartan would you mind taking a look and doing a review here?

@Neomelt
Copy link
Contributor Author

Neomelt commented Mar 9, 2026

Copy link
Contributor

@gennartan gennartan left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Overall, everything seems to be working correctly on my side and the changes look good 👍

I only left two small comments that should help the PR integrate a bit better with the rest of the project.

Signed-off-by: Xlqmu <3212929002@qq.com>
@Neomelt
Copy link
Contributor Author

Neomelt commented Mar 9, 2026

Thanks, updated and pushed. @gennartan

Signed-off-by: Xlqmu <3212929002@qq.com>
Copy link
Contributor

@gennartan gennartan left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Seems good to me

@Neomelt
Copy link
Contributor Author

Neomelt commented Mar 13, 2026

Hi @SteveMacenski, gentle ping when you have a moment 🙏
This PR has an approval, requested updates were addressed, and CI is green.
Would you mind taking a final look for merge?
Happy to make any follow-up changes if needed. Thanks!

@SteveMacenski
Copy link
Member

Review now - sorry for the delay, I've been slammed and trying to get to as much as I can each day :-)

Copy link
Member

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This looks like a few requested changes, but really this is mostly pedantic for conciseness (extra work/complexity without functional difference) with a couple of small correction errors. Overall this is essentially perfect!

}

if (polygon->getPointsInside(sources_collision_points_map) >= polygon->getMinPoints()) {
const int points_inside = polygon->getPointsInside(sources_collision_points_map);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Question (not asking for the change necessarily): Does it make sense potentially to have the getPointsInside now be an internal detail of an API like isTriggered() rather than externally getting the points in this application? Seems unimportant now to have points_inside in the code of the monitor/detector nodes if we're moving the triggering logic internal to the polygons

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ok

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@Neomelt can you respond to my question and if you think that is better?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You’re right — sorry for the earlier brief reply.I agree that direction is better long-term: encapsulating getPointsInside() behind a trigger-oriented API would clean up monitor/detector logic.For this PR I kept scope focused on debounce and lifecycle/state consistency, maybe I can open a focused follow-up refactor PR for that API cleanup.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Would it be possible to do it here? Rename isTriggeredByPoints to isTriggered and get the getPointsInside first thing in the function for use.

Copy link
Contributor Author

@Neomelt Neomelt Mar 18, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done 👍

@Neomelt Neomelt force-pushed the fix/4364-temporal-min-points branch 2 times, most recently from ff6198f to 46c2524 Compare March 16, 2026 06:20
@Neomelt Neomelt force-pushed the fix/4364-temporal-min-points branch from 46c2524 to f27c4fb Compare March 16, 2026 06:29
@Neomelt
Copy link
Contributor Author

Neomelt commented Mar 16, 2026

@SteveMacenski Thanks a lot for the detailed review — I applied your suggestions and pushed some changes.I also reran the tests on Jazzy locally and everything is green.When you get a chance, could you take another look at the PR?

@SteveMacenski
Copy link
Member

@Neomelt approved minus the 2 items I reopened and tagged you in from the last review

…n API

Signed-off-by: Neomelt <niezhenghua2004@gmail.com>
@Neomelt
Copy link
Contributor Author

Neomelt commented Mar 18, 2026

Pushed follow-up in 56bd139a to address the API encapsulation request (isTriggered + internalized getPointsInside) and updated call sites/tests accordingly.\n\nAlso updated docs in ros-navigation/docs.nav2.org#888 (detector page follow-up in 24cc271).\n\nCould you take another quick look when you have a moment? 🙏

@SteveMacenski SteveMacenski merged commit 7e657bf into ros-navigation:main Mar 18, 2026
18 checks passed
@Neomelt
Copy link
Contributor Author

Neomelt commented Mar 18, 2026

Thanks for the direct and detailed feedback throughout this PR.
I appreciate the high bar — it helped me improve both the implementation and how I communicate design choices.🙏

@SteveMacenski
Copy link
Member

Anytime and thanks for the help! This is a great feature to have :-)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

[collision_monitor] Add temporal axis to min_points behavior

4 participants