Skip to content

Fix premature mission termination in mapless coverage navigation#1

Draft
Copilot wants to merge 11 commits intomainfrom
copilot/review-navigation-logic
Draft

Fix premature mission termination in mapless coverage navigation#1
Copilot wants to merge 11 commits intomainfrom
copilot/review-navigation-logic

Conversation

Copy link

Copilot AI commented Mar 13, 2026

is_target_safe() treats unknown costmap cells as unsafe, which is wrong for mapless rolling-window navigation. Since most of the costmap starts unobserved (cost=-1), nearly all targets get rejected → retry limit exhausted → mission ends immediately without visiting any waypoints.

is_target_safe() — core fix

The old logic had two problems:

  • Returns False if any neighbor cell is out of the costmap grid (cost is None → return False)
  • Requires at least one known cell (return has_known_cells), so targets in unobserved space always fail
# Before: unknown space = unsafe
if cost is None:
    return False        # out-of-bounds neighbor → immediate reject
if cost < 0:
    continue            # skip unknown
has_known_cells = True
...
return has_known_cells  # False when all cells unknown

# After: unknown space = potentially free (let move_base handle actual path safety)
if cost is None:
    continue            # skip out-of-bounds neighbors
if cost < 0:
    continue            # skip unknown cells
if cost >= self.target_cost_threshold:
    return False        # only reject on known obstacles
return True

This is consistent with NavfnROS/allow_unknown=true already set in the launch config.

Other changes

  • Costmap settling: Configurable costmap_settle_time param (default 3s, was hardcoded 1s) — gives the lidar time to populate the rolling window before target generation
  • Recovery behaviors: Enabled recovery_behavior_enabled=true in move_base so it can recover from stuck states
  • Retry improvement: Refresh targets from updated costmap after clearing costmaps during retry
  • Diagnostics: Log initial target census (total/pending/active) at mission start

Tests

14 unit tests for is_target_safe(), target generation, and sweep ordering — runs without ROS via lightweight stubs.

Original prompt

I would like to understand the navigation stack super well right now... in the when i run it, there seems to be a problem where it doesnt navigate to waypoints and then stop, and it always finishes prematurely. Help me review the codebase and help me understand the navigation logic so that i can make a reliable navigation. It is starting in relatively the middle of a 2 x 2 walled area is where i am testing it and there are 2 plant obstacles and it should try to get relatively good coverage , right now i think it thinks its unsafe even though lots of space to move


📱 Kick off Copilot coding agent tasks wherever you are with GitHub Mobile, available on iOS and Android.

Copilot AI and others added 2 commits March 13, 2026 16:12
The coverage planner was treating all unknown costmap cells as unsafe,
causing most targets to be rejected in mapless rolling-window navigation.
This made the planner give up after exhausting its retry limit (8 attempts),
prematurely ending the mission.

Changes:
- is_target_safe(): skip out-of-bounds neighbor cells instead of failing
  immediately; remove has_known_cells requirement so unknown space is
  treated as potentially free (correct for mapless navigation)
- Enable move_base recovery behaviors for stuck situations
- Increase costmap settling time from 1s to 3s before target generation
- Refresh targets after clearing costmaps during retry
- Add diagnostic logging for initial target census
- Add unit tests for is_target_safe() covering unknown space, edge-of-
  costmap, and obstacle detection scenarios

Co-authored-by: mtaruno <44710581+mtaruno@users.noreply.github.com>
…used args in test stubs

Co-authored-by: mtaruno <44710581+mtaruno@users.noreply.github.com>
Copilot AI changed the title [WIP] Review navigation stack for waypoint issues Fix premature mission termination in mapless coverage navigation Mar 13, 2026
Copilot AI requested a review from mtaruno March 13, 2026 16:14
@mtaruno
Copy link
Owner

mtaruno commented Mar 13, 2026

give me all the paramrters i can try tuning and an explanation of what the parameter is when testing. Do u think i shd just try to tune parameters and eventually it would run well?

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.

2 participants