Skip to content

Commit 75e7019

Browse files
SteveMacenskiAndrew Lycas
authored andcommitted
add parameterized refinement recursion numbers in Smac Planner Smoother and Simple Smoother (ros-navigation#3284)
* add parameterized refinement recursion numbers * fix tests
1 parent aa74c89 commit 75e7019

File tree

6 files changed

+17
-9
lines changed

6 files changed

+17
-9
lines changed

nav2_smac_planner/include/nav2_smac_planner/smoother.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -232,7 +232,7 @@ class Smoother
232232
bool & reversing_segment);
233233

234234
double min_turning_rad_, tolerance_, data_w_, smooth_w_;
235-
int max_its_, refinement_ctr_;
235+
int max_its_, refinement_ctr_, refinement_num_;
236236
bool is_holonomic_, do_refinement_;
237237
MotionModel motion_model_;
238238
ompl::base::StateSpacePtr state_space_;

nav2_smac_planner/include/nav2_smac_planner/types.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -87,6 +87,9 @@ struct SmootherParams
8787
nav2_util::declare_parameter_if_not_declared(
8888
node, local_name + "do_refinement", rclcpp::ParameterValue(true));
8989
node->get_parameter(local_name + "do_refinement", do_refinement_);
90+
nav2_util::declare_parameter_if_not_declared(
91+
node, local_name + "refinement_num", rclcpp::ParameterValue(2));
92+
node->get_parameter(local_name + "refinement_num", refinement_num_);
9093
}
9194

9295
double tolerance_;
@@ -95,6 +98,7 @@ struct SmootherParams
9598
double w_smooth_;
9699
bool holonomic_;
97100
bool do_refinement_;
101+
int refinement_num_;
98102
};
99103

100104
/**

nav2_smac_planner/src/smoother.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@ Smoother::Smoother(const SmootherParams & params)
3131
smooth_w_ = params.w_smooth_;
3232
is_holonomic_ = params.holonomic_;
3333
do_refinement_ = params.do_refinement_;
34+
refinement_num_ = params.refinement_num_;
3435
}
3536

3637
void Smoother::initialize(const double & min_turning_radius)
@@ -49,7 +50,6 @@ bool Smoother::smooth(
4950
return false;
5051
}
5152

52-
refinement_ctr_ = 0;
5353
steady_clock::time_point start = steady_clock::now();
5454
double time_remaining = max_time;
5555
bool success = true, reversing_segment;
@@ -69,6 +69,7 @@ bool Smoother::smooth(
6969
// Make sure we're still able to smooth with time remaining
7070
steady_clock::time_point now = steady_clock::now();
7171
time_remaining = max_time - duration_cast<duration<double>>(now - start).count();
72+
refinement_ctr_ = 0;
7273

7374
// Smooth path segment naively
7475
const geometry_msgs::msg::Pose start_pose = curr_path_segment.poses.front().pose;
@@ -178,7 +179,7 @@ bool Smoother::smoothImpl(
178179

179180
// Lets do additional refinement, it shouldn't take more than a couple milliseconds
180181
// but really puts the path quality over the top.
181-
if (do_refinement_ && refinement_ctr_ < 4) {
182+
if (do_refinement_ && refinement_ctr_ < refinement_num_) {
182183
refinement_ctr_++;
183184
smoothImpl(new_path, reversing_segment, costmap, max_time);
184185
}

nav2_smoother/include/nav2_smoother/simple_smoother.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -121,7 +121,7 @@ class SimpleSmoother : public nav2_core::Smoother
121121
const double & value);
122122

123123
double tolerance_, data_w_, smooth_w_;
124-
int max_its_, refinement_ctr_;
124+
int max_its_, refinement_ctr_, refinement_num_;
125125
bool do_refinement_;
126126
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
127127
rclcpp::Logger logger_{rclcpp::get_logger("SimpleSmoother")};

nav2_smoother/src/simple_smoother.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,12 +44,15 @@ void SimpleSmoother::configure(
4444
node, name + ".w_smooth", rclcpp::ParameterValue(0.3));
4545
declare_parameter_if_not_declared(
4646
node, name + ".do_refinement", rclcpp::ParameterValue(true));
47+
declare_parameter_if_not_declared(
48+
node, name + ".refinement_num", rclcpp::ParameterValue(2));
4749

4850
node->get_parameter(name + ".tolerance", tolerance_);
4951
node->get_parameter(name + ".max_its", max_its_);
5052
node->get_parameter(name + ".w_data", data_w_);
5153
node->get_parameter(name + ".w_smooth", smooth_w_);
5254
node->get_parameter(name + ".do_refinement", do_refinement_);
55+
node->get_parameter(name + ".refinement_num", refinement_num_);
5356
}
5457

5558
bool SimpleSmoother::smooth(
@@ -58,7 +61,6 @@ bool SimpleSmoother::smooth(
5861
{
5962
auto costmap = costmap_sub_->getCostmap();
6063

61-
refinement_ctr_ = 0;
6264
steady_clock::time_point start = steady_clock::now();
6365
double time_remaining = max_time.seconds();
6466

@@ -80,6 +82,7 @@ bool SimpleSmoother::smooth(
8082
// Make sure we're still able to smooth with time remaining
8183
steady_clock::time_point now = steady_clock::now();
8284
time_remaining = max_time.seconds() - duration_cast<duration<double>>(now - start).count();
85+
refinement_ctr_ = 0;
8386

8487
// Smooth path segment naively
8588
success = success && smoothImpl(
@@ -180,7 +183,7 @@ bool SimpleSmoother::smoothImpl(
180183

181184
// Lets do additional refinement, it shouldn't take more than a couple milliseconds
182185
// but really puts the path quality over the top.
183-
if (do_refinement_ && refinement_ctr_ < 4) {
186+
if (do_refinement_ && refinement_ctr_ < refinement_num_) {
184187
refinement_ctr_++;
185188
smoothImpl(new_path, reversing_segment, costmap, max_time);
186189
}

nav2_smoother/test/test_simple_smoother.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -128,7 +128,7 @@ TEST(SmootherTest, test_simple_smoother)
128128
EXPECT_LT(
129129
fabs(
130130
straight_irregular_path.poses[i].pose.position.y -
131-
straight_irregular_path.poses[i + 1].pose.position.y), 0.38);
131+
straight_irregular_path.poses[i + 1].pose.position.y), 0.50);
132132
}
133133

134134
// Test regular path, should see no effective change
@@ -181,8 +181,8 @@ TEST(SmootherTest, test_simple_smoother)
181181
straight_regular_path.poses[10].pose.position.x = 0.95;
182182
straight_regular_path.poses[10].pose.position.y = 0.5;
183183
EXPECT_TRUE(smoother->smooth(straight_regular_path, max_time));
184-
EXPECT_NEAR(straight_regular_path.poses[5].pose.position.x, 0.637, 0.01);
185-
EXPECT_NEAR(straight_regular_path.poses[5].pose.position.y, 0.353, 0.01);
184+
EXPECT_NEAR(straight_regular_path.poses[5].pose.position.x, 0.607, 0.01);
185+
EXPECT_NEAR(straight_regular_path.poses[5].pose.position.y, 0.387, 0.01);
186186

187187
// Test that collisions are rejected
188188
nav_msgs::msg::Path collision_path;

0 commit comments

Comments
 (0)