Skip to content

Conversation

CPPavithra
Copy link


Basic Info

Info Please fill out this column
Ticket(s) this addresses Fixes #5330
Primary OS tested on Ubuntu 22.04
Robotic platform tested on Gazebo simulation
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

  • Added full footprint collision checking to the SimpleSmoother.
  • The smoother now correctly uses the robot's orientation to validate poses.
  • If a smoothed path is found to be in collision, the smoother safely reverts to the original, valid path segment.

Description of documentation updates required from your changes

No documentation changes are required. This PR is a bug fix that improves the safety and correctness of the smoother without adding new user-facing parameters or behaviors that need configuration.

Description of how this change was tested

  • A new unit test was added to verify that the smoother correctly identifies and rejects paths that are in footprint collision but would have previously been considered valid.
  • Successfully ran all existing unit tests for the nav2_smoother package.
  • Performed linting validation using colcon test.

Future work that may be required in bullet points

  • The current implementation reverts the entire path segment on any detected collision. A more advanced approach could potentially be developed to only partially revert or re-smooth from the last valid point.

For Maintainers: - [ ] Check that any new parameters added are updated in docs.nav2.org

  • Check that any significant change is added to the migration guide
  • Check that any new features OR changes to existing behaviors are reflected in the tuning guide
  • Check that any new functions have Doxygen added
  • Check that any new features have test coverage
  • Check that any new plugins is added to the plugins page
  • If BT Node, Additionally: add to BT's XML index of nodes for groot, BT package's readme table, and BT library lists
  • Should this be backported to current distributions? If so, tag with backport-*.

@SteveMacenski
Copy link
Member

@CPPavithra check out the CI build issues on linting / system build. Your solution does not compile.

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.

How was this tested? I think a new test case(s) might be good to make sure this works properly

@@ -94,6 +95,7 @@ class SimpleSmoother : public nav2_core::Smoother
* @param costmap Pointer to minimal costmap
* @param max_time Maximum time to compute, stop early if over limit
*/

Copy link
Member

Choose a reason for hiding this comment

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

Remove extra space

@@ -124,6 +126,9 @@ class SimpleSmoother : public nav2_core::Smoother
int max_its_, refinement_ctr_, refinement_num_;
bool do_refinement_, enforce_path_inversion_;
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
//member variables added to store foorprint sub and collision checker
Copy link
Member

Choose a reason for hiding this comment

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

Remove comment

auto node = parent.lock();
logger_ = node->get_logger();

declare_parameter_if_not_declared(
Copy link
Member

Choose a reason for hiding this comment

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

Why the reorganization? Revert to only the line changes required for the feature addition please.

@@ -126,6 +138,7 @@ void SimpleSmoother::smoothImpl(

nav_msgs::msg::Path new_path = path;
nav_msgs::msg::Path last_path = path;
const nav_msgs::msg::Path original_path = path; //new var
Copy link
Member

Choose a reason for hiding this comment

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

Why the comment?

@@ -199,6 +212,30 @@ void SimpleSmoother::smoothImpl(
}

updateApproximatePathOrientations(new_path, reversing_segment);

/* ***********************************************************************
Copy link
Member

Choose a reason for hiding this comment

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

Why these blocks? Remove?

************** START: NEW FOOTPRINT COLLISION CHECKING *****************
************************************************************************/
//After smoothing,we perform a full footprint collision check on the result.
for (const auto & pose : new_path.poses) {
Copy link
Member

Choose a reason for hiding this comment

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

I think the collision checking should be modifying the block in the while loop so we can exit out in the first iteration that becomes invalid. That way, we can smooth as much as possible before causing collision (as we do now).

If you updateApproximatePathOrientations proactively before checking collision, you can use the footprint checker in the while loop.

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.

SMAC smoother can generate infeasible paths when using non-circular robots in very confined spaces
2 participants