@@ -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
5558bool 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 }
0 commit comments