Skip to content

Commit 8f16980

Browse files
author
Kemal Bektas
committed
Add terminal_checking_interval parameter
Signed-off-by: Kemal Bektas <kemal.bektas@node-robotics.com>
1 parent b03a803 commit 8f16980

File tree

13 files changed

+72
-20
lines changed

13 files changed

+72
-20
lines changed

nav2_navfn_planner/include/nav2_navfn_planner/navfn.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -183,7 +183,7 @@ class NavFn
183183
float priInc; /**< priority threshold increment */
184184

185185
/**< number of cycles between checks for cancellation */
186-
int cancel_check_interval;
186+
static constexpr int terminal_checking_interval = 500;
187187

188188
/** goal and start positions */
189189
/**

nav2_navfn_planner/src/navfn.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -582,7 +582,7 @@ NavFn::propNavFnDijkstra(int cycles, std::function<bool()> cancelChecker, bool a
582582
int startCell = start[1] * nx + start[0];
583583

584584
for (; cycle < cycles; cycle++) { // go for this many cycles, unless interrupted
585-
if (cycle % cancel_check_interval == 0 && cancelChecker()) {
585+
if (cycle % terminal_checking_interval == 0 && cancelChecker()) {
586586
throw nav2_core::PlannerCancelled("Planner was cancelled");
587587
}
588588

@@ -672,7 +672,7 @@ NavFn::propNavFnAstar(int cycles, std::function<bool()> cancelChecker)
672672

673673
// do main cycle
674674
for (; cycle < cycles; cycle++) { // go for this many cycles, unless interrupted
675-
if (cycle % cancel_check_interval == 0 && cancelChecker()) {
675+
if (cycle % terminal_checking_interval == 0 && cancelChecker()) {
676676
throw nav2_core::PlannerCancelled("Planner was cancelled");
677677
}
678678

nav2_smac_planner/README.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -109,6 +109,7 @@ planner_server:
109109
allow_unknown: false # allow traveling in unknown space
110110
max_iterations: 1000000 # maximum total iterations to search for before failing (in case unreachable), set to -1 to disable
111111
max_on_approach_iterations: 1000 # maximum number of iterations to attempt to reach goal once in tolerance
112+
terminal_checking_interval: 500 # number of iterations between checking if the goal has been cancelled
112113
max_planning_time: 3.5 # max time in s for planner to plan, smooth, and upsample. Will scale maximum smoothing and upsampling times based on remaining time after planning.
113114
motion_model_for_search: "DUBIN" # For Hybrid Dubin, Redds-Shepp
114115
cost_travel_multiplier: 2.0 # For 2D: Cost multiplier to apply to search to steer away from high cost areas. Larger values will place in the center of aisles more exactly (if non-`FREE` cost potential field exists) but take slightly longer to compute. To optimize for speed, a value of 1.0 is reasonable. A reasonable tradeoff value is 2.0. A value of 0.0 effective disables steering away from obstacles and acts like a naive binary search A*.

nav2_smac_planner/include/nav2_smac_planner/a_star.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -88,13 +88,15 @@ class AStarAlgorithm
8888
* @param max_on_approach_iterations Maximum number of iterations before returning a valid
8989
* path once within thresholds to refine path
9090
* comes at more compute time but smoother paths.
91+
* @param terminal_checking_interval Number of iterations to check if the task has been canceled
9192
* @param max_planning_time Maximum time (in seconds) to wait for a plan, createPath returns
9293
* false after this timeout
9394
*/
9495
void initialize(
9596
const bool & allow_unknown,
9697
int & max_iterations,
9798
const int & max_on_approach_iterations,
99+
const int & terminal_checking_interval,
98100
const double & max_planning_time,
99101
const float & lookup_table_size,
100102
const unsigned int & dim_3_size);
@@ -253,12 +255,12 @@ class AStarAlgorithm
253255
void clearStart();
254256

255257
int _timing_interval = 5000;
256-
int _cancel_check_interval = 500;
257258

258259

259260
bool _traverse_unknown;
260261
int _max_iterations;
261262
int _max_on_approach_iterations;
263+
int _terminal_checking_interval;
262264
double _max_planning_time;
263265
float _tolerance;
264266
unsigned int _x_size;

nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -114,6 +114,7 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner
114114
bool _allow_unknown;
115115
int _max_iterations;
116116
int _max_on_approach_iterations;
117+
int _terminal_checking_interval;
117118
bool _use_final_approach_orientation;
118119
SearchInfo _search_info;
119120
std::string _motion_model_for_search;

nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -115,6 +115,7 @@ class SmacPlannerHybrid : public nav2_core::GlobalPlanner
115115
bool _allow_unknown;
116116
int _max_iterations;
117117
int _max_on_approach_iterations;
118+
int _terminal_checking_interval;
118119
SearchInfo _search_info;
119120
double _max_planning_time;
120121
double _lookup_table_size;

nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -110,6 +110,7 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner
110110
bool _allow_unknown;
111111
int _max_iterations;
112112
int _max_on_approach_iterations;
113+
int _terminal_checking_interval;
113114
float _tolerance;
114115
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr _raw_plan_publisher;
115116
double _max_planning_time;

nav2_smac_planner/src/a_star.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@ AStarAlgorithm<NodeT>::AStarAlgorithm(
3737
const SearchInfo & search_info)
3838
: _traverse_unknown(true),
3939
_max_iterations(0),
40+
_terminal_checking_interval(500),
4041
_max_planning_time(0),
4142
_x_size(0),
4243
_y_size(0),
@@ -59,13 +60,15 @@ void AStarAlgorithm<NodeT>::initialize(
5960
const bool & allow_unknown,
6061
int & max_iterations,
6162
const int & max_on_approach_iterations,
63+
const int & terminal_checking_interval,
6264
const double & max_planning_time,
6365
const float & lookup_table_size,
6466
const unsigned int & dim_3_size)
6567
{
6668
_traverse_unknown = allow_unknown;
6769
_max_iterations = max_iterations;
6870
_max_on_approach_iterations = max_on_approach_iterations;
71+
_terminal_checking_interval = terminal_checking_interval;
6972
_max_planning_time = max_planning_time;
7073
NodeT::precomputeDistanceHeuristic(lookup_table_size, _motion_model, dim_3_size, _search_info);
7174
_dim3_size = dim_3_size;
@@ -78,13 +81,15 @@ void AStarAlgorithm<Node2D>::initialize(
7881
const bool & allow_unknown,
7982
int & max_iterations,
8083
const int & max_on_approach_iterations,
84+
const int & terminal_checking_interval,
8185
const double & max_planning_time,
8286
const float & /*lookup_table_size*/,
8387
const unsigned int & dim_3_size)
8488
{
8589
_traverse_unknown = allow_unknown;
8690
_max_iterations = max_iterations;
8791
_max_on_approach_iterations = max_on_approach_iterations;
92+
_terminal_checking_interval = terminal_checking_interval;
8893
_max_planning_time = max_planning_time;
8994

9095
if (dim_3_size != 1) {
@@ -296,7 +301,7 @@ bool AStarAlgorithm<NodeT>::createPath(
296301
}
297302

298303
// Check for cancel every Nth iteration
299-
if (iterations % _cancel_check_interval == 0 && cancel_checker()) {
304+
if (iterations % _terminal_checking_interval == 0 && cancel_checker()) {
300305
throw nav2_core::PlannerCancelled("Planner was cancelled");
301306
}
302307

nav2_smac_planner/src/smac_planner_2d.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,9 @@ void SmacPlanner2D::configure(
8383
nav2_util::declare_parameter_if_not_declared(
8484
node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000));
8585
node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations);
86+
nav2_util::declare_parameter_if_not_declared(
87+
node, name + ".terminal_checking_interval", rclcpp::ParameterValue(500));
88+
node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval);
8689
nav2_util::declare_parameter_if_not_declared(
8790
node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false));
8891
node->get_parameter(name + ".use_final_approach_orientation", _use_final_approach_orientation);
@@ -120,6 +123,7 @@ void SmacPlanner2D::configure(
120123
_allow_unknown,
121124
_max_iterations,
122125
_max_on_approach_iterations,
126+
_terminal_checking_interval,
123127
_max_planning_time,
124128
0.0 /*unused for 2D*/,
125129
1.0 /*unused for 2D*/);
@@ -378,6 +382,9 @@ SmacPlanner2D::dynamicParametersCallback(std::vector<rclcpp::Parameter> paramete
378382
"disabling tolerance and on approach iterations.");
379383
_max_on_approach_iterations = std::numeric_limits<int>::max();
380384
}
385+
} else if (name == _name + ".terminal_checking_interval") {
386+
reinit_a_star = true;
387+
_terminal_checking_interval = parameter.as_int();
381388
}
382389
}
383390
}
@@ -391,6 +398,7 @@ SmacPlanner2D::dynamicParametersCallback(std::vector<rclcpp::Parameter> paramete
391398
_allow_unknown,
392399
_max_iterations,
393400
_max_on_approach_iterations,
401+
_terminal_checking_interval,
394402
_max_planning_time,
395403
0.0 /*unused for 2D*/,
396404
1.0 /*unused for 2D*/);

nav2_smac_planner/src/smac_planner_hybrid.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -94,6 +94,9 @@ void SmacPlannerHybrid::configure(
9494
nav2_util::declare_parameter_if_not_declared(
9595
node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000));
9696
node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations);
97+
nav2_util::declare_parameter_if_not_declared(
98+
node, name + ".terminal_checking_interval", rclcpp::ParameterValue(500));
99+
node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval);
97100
nav2_util::declare_parameter_if_not_declared(
98101
node, name + ".smooth_path", rclcpp::ParameterValue(true));
99102
node->get_parameter(name + ".smooth_path", smooth_path);
@@ -228,6 +231,7 @@ void SmacPlannerHybrid::configure(
228231
_allow_unknown,
229232
_max_iterations,
230233
_max_on_approach_iterations,
234+
_terminal_checking_interval,
231235
_max_planning_time,
232236
_lookup_table_dim,
233237
_angle_quantizations);
@@ -599,6 +603,9 @@ SmacPlannerHybrid::dynamicParametersCallback(std::vector<rclcpp::Parameter> para
599603
"disabling tolerance and on approach iterations.");
600604
_max_on_approach_iterations = std::numeric_limits<int>::max();
601605
}
606+
} else if (name == _name + ".terminal_checking_interval") {
607+
reinit_a_star = true;
608+
_terminal_checking_interval = parameter.as_int();
602609
} else if (name == _name + ".angle_quantization_bins") {
603610
reinit_collision_checker = true;
604611
reinit_a_star = true;
@@ -654,6 +661,7 @@ SmacPlannerHybrid::dynamicParametersCallback(std::vector<rclcpp::Parameter> para
654661
_allow_unknown,
655662
_max_iterations,
656663
_max_on_approach_iterations,
664+
_terminal_checking_interval,
657665
_max_planning_time,
658666
_lookup_table_dim,
659667
_angle_quantizations);

0 commit comments

Comments
 (0)