Skip to content

[RPP] min_distance_to_obstacle and velocity_scaled_lookahead dont work well together when min_lookahead < min_distance_to_obstacle #5595

@EricoMeger

Description

@EricoMeger

Bug report

Required Info:

  • Operating System:
    • Ubuntu 24.04
  • Computer:
    • Intel Twin Lake N150, 8GB RAM
  • ROS2 Version:
    • Jazzy installed via deb packages
  • Version or commit hash:
    • 1.3.8-1noble.20250915.220228
    • Custom RPP with min_distance_to_obstacle from Rolling implemented
  • DDS implementation:
    • Zenoh

Expected behavior

When using min_distance_to_obstacle, I would expect the robot to stop when an obstacle is detected within this range and remain stationary until the path is clear. The collision checking logic should consistently enforce this safety distance, even when the robot's velocity is zero.

Actual behavior

The robot initially stops correctly at the specified min_distance_to_obstacle. However, it then begins to slowly "creep" forward in a stop-and-go pattern, gradually getting closer to the obstacle and not maintaining the intended safety gap.
I've observed this same creeping pattern in two different scenarios:

  1. When using a custom modification to the controller that commands zero velocity on imminent collision.
  2. When using the default controller behavior that triggers a Wait recovery on the BT.

Steps to reproduce issue

  1. Configure the RPP controller with the following parameters, ensuring min_lookahead_dist is smaller than min_distance_to_obstacle:
use_collision_detection: true 
use_velocity_scaled_lookahead_dist: true
min_distance_to_obstacle: 0.65
min_lookahead_dist: 0.2 
  1. Run a navigation task, and put an obstacle on the robot's path.

  2. The robot will approach the obstacle, stop correctly at the min_distance_to_obstacle, but then slowly creep closer to it.

Additional information

In isCollisionImminent, the simulation distance is limited by carrot_dist, which shrinks to min_lookahead_dist when stopped. This prevents the checker from evaluating the full min_distance_to_obstacle range.

if (hypot(curr_pose.position.x - robot_xy.x, curr_pose.position.y - robot_xy.y) > carrot_dist) {
    break;
}

A potential fix that I've tested locally:

To ensure the simulation always respects the safety margin, the distance boundary can be modified to account for min_distance_to_obstacle. This can be done by defining a new limit before the loop:

double simulation_distance_limit = std::max(carrot_dist, params_->min_distance_to_obstacle);

And updating the break condition to use this new limit:

if (hypot(curr_pose.x - robot_xy.x, curr_pose.y - robot_xy.y) > simulation_distance_limit) {
    break;
}

This change was tested on a physical robot and resolved the creeping behavior, with no observed negative side effects on general navigation.

I'm opening this issue to report the behavior and share my findings. I'm not sure if the current interaction is the intended design, but this approach seems to make the feature more reliable. I'm curious to hear your thoughts.

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't working

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions