Skip to content

Commit

Permalink
implement steve's suggestions
Browse files Browse the repository at this point in the history
Signed-off-by: rayferric <[email protected]>
  • Loading branch information
rayferric committed Jan 17, 2025
1 parent ad7b15c commit 386a8b8
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 22 deletions.
3 changes: 1 addition & 2 deletions nav2_smoother/include/nav2_smoother/simple_smoother.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,9 +92,8 @@ class SimpleSmoother : public nav2_core::Smoother
* @param reversing_segment Return if this is a reversing segment
* @param costmap Pointer to minimal costmap
* @param max_time Maximum time to compute, stop early if over limit
* @return If smoothing was successful
*/
bool smoothImpl(
void smoothImpl(
nav_msgs::msg::Path & path,
bool & reversing_segment,
const nav2_costmap_2d::Costmap2D * costmap,
Expand Down
28 changes: 8 additions & 20 deletions nav2_smoother/src/simple_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,7 @@ bool SimpleSmoother::smooth(
steady_clock::time_point start = steady_clock::now();
double time_remaining = max_time.seconds();

bool success = true, reversing_segment;
unsigned int segments_smoothed = 0;
bool reversing_segment;
nav_msgs::msg::Path curr_path_segment;
curr_path_segment.header = path.header;

Expand All @@ -88,15 +87,9 @@ bool SimpleSmoother::smooth(
time_remaining = max_time.seconds() - duration_cast<duration<double>>(now - start).count();
refinement_ctr_ = 0;

bool segment_was_smoothed = smoothImpl(
curr_path_segment, reversing_segment, costmap.get(), time_remaining);

if (segment_was_smoothed) {
segments_smoothed++;
}

// Smooth path segment naively
success = success && segment_was_smoothed;
// Attempt to smooth the segment
// May throw SmootherTimedOut
smoothImpl(curr_path_segment, reversing_segment, costmap.get(), time_remaining);

// Assemble the path changes to the main path
std::copy(
Expand All @@ -106,14 +99,10 @@ bool SimpleSmoother::smooth(
}
}

if (segments_smoothed == 0) {
throw nav2_core::FailedToSmoothPath("No segments were smoothed");
}

return success;
return true;
}

bool SimpleSmoother::smoothImpl(
void SimpleSmoother::smoothImpl(
nav_msgs::msg::Path & path,
bool & reversing_segment,
const nav2_costmap_2d::Costmap2D * costmap,
Expand Down Expand Up @@ -142,7 +131,7 @@ bool SimpleSmoother::smoothImpl(
"Number of iterations has exceeded limit of %i.", max_its_);
path = last_path;
updateApproximatePathOrientations(path, reversing_segment);
return false;
return;
}

// Make sure still have time left to process
Expand Down Expand Up @@ -188,7 +177,7 @@ bool SimpleSmoother::smoothImpl(
"Returning the last path before the infeasibility was introduced.");
path = last_path;
updateApproximatePathOrientations(path, reversing_segment);
return false;
return;
}
}

Expand All @@ -204,7 +193,6 @@ bool SimpleSmoother::smoothImpl(

updateApproximatePathOrientations(new_path, reversing_segment);
path = new_path;
return true;
}

double SimpleSmoother::getFieldByDim(
Expand Down

0 comments on commit 386a8b8

Please sign in to comment.