Skip to content

Commit e391c6f

Browse files
author
Kemal Bektas
committed
Handle timeout and cancel check on the same branch and default to 5000 iterations
1 parent 8f16980 commit e391c6f

File tree

11 files changed

+20
-23
lines changed

11 files changed

+20
-23
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-
static constexpr int terminal_checking_interval = 500;
186+
static constexpr int terminal_checking_interval = 5000;
187187

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

nav2_smac_planner/README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -109,7 +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
112+
terminal_checking_interval: 5000 # number of iterations between checking if the goal has been cancelled or planner timed out
113113
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.
114114
motion_model_for_search: "DUBIN" # For Hybrid Dubin, Redds-Shepp
115115
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: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,8 @@ 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
91+
* @param terminal_checking_interval Number of iterations to check if the task has been canceled or
92+
* or planning time exceeded
9293
* @param max_planning_time Maximum time (in seconds) to wait for a plan, createPath returns
9394
* false after this timeout
9495
*/
@@ -254,8 +255,6 @@ class AStarAlgorithm
254255
*/
255256
void clearStart();
256257

257-
int _timing_interval = 5000;
258-
259258

260259
bool _traverse_unknown;
261260
int _max_iterations;

nav2_smac_planner/src/a_star.cpp

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ AStarAlgorithm<NodeT>::AStarAlgorithm(
3737
const SearchInfo & search_info)
3838
: _traverse_unknown(true),
3939
_max_iterations(0),
40-
_terminal_checking_interval(500),
40+
_terminal_checking_interval(5000),
4141
_max_planning_time(0),
4242
_x_size(0),
4343
_y_size(0),
@@ -291,20 +291,18 @@ bool AStarAlgorithm<NodeT>::createPath(
291291
};
292292

293293
while (iterations < getMaxIterations() && !_queue.empty()) {
294-
// Check for planning timeout only on every Nth iteration
295-
if (iterations % _timing_interval == 0) {
294+
// Check for planning timeout and cancel only on every Nth iteration
295+
if (iterations % _terminal_checking_interval == 0) {
296+
if (cancel_checker()) {
297+
throw nav2_core::PlannerCancelled("Planner was cancelled");
298+
}
296299
std::chrono::duration<double> planning_duration =
297300
std::chrono::duration_cast<std::chrono::duration<double>>(steady_clock::now() - start_time);
298301
if (static_cast<double>(planning_duration.count()) >= _max_planning_time) {
299302
return false;
300303
}
301304
}
302305

303-
// Check for cancel every Nth iteration
304-
if (iterations % _terminal_checking_interval == 0 && cancel_checker()) {
305-
throw nav2_core::PlannerCancelled("Planner was cancelled");
306-
}
307-
308306
// 1) Pick Nbest from O s.t. min(f(Nbest)), remove from queue
309307
current_node = getNextNode();
310308

nav2_smac_planner/src/smac_planner_2d.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,7 @@ void SmacPlanner2D::configure(
8484
node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000));
8585
node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations);
8686
nav2_util::declare_parameter_if_not_declared(
87-
node, name + ".terminal_checking_interval", rclcpp::ParameterValue(500));
87+
node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000));
8888
node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval);
8989
nav2_util::declare_parameter_if_not_declared(
9090
node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false));

nav2_smac_planner/src/smac_planner_hybrid.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -95,7 +95,7 @@ void SmacPlannerHybrid::configure(
9595
node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000));
9696
node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations);
9797
nav2_util::declare_parameter_if_not_declared(
98-
node, name + ".terminal_checking_interval", rclcpp::ParameterValue(500));
98+
node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000));
9999
node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval);
100100
nav2_util::declare_parameter_if_not_declared(
101101
node, name + ".smooth_path", rclcpp::ParameterValue(true));

nav2_smac_planner/src/smac_planner_lattice.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ void SmacPlannerLattice::configure(
7878
node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000));
7979
node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations);
8080
nav2_util::declare_parameter_if_not_declared(
81-
node, name + ".terminal_checking_interval", rclcpp::ParameterValue(500));
81+
node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000));
8282
node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval);
8383
nav2_util::declare_parameter_if_not_declared(
8484
node, name + ".smooth_path", rclcpp::ParameterValue(true));

nav2_smac_planner/test/test_a_star.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ TEST(AStarTest, test_a_star_2d)
4747
float tolerance = 0.0;
4848
float some_tolerance = 20.0;
4949
int it_on_approach = 10;
50-
int terminal_checking_interval = 500;
50+
int terminal_checking_interval = 5000;
5151
double max_planning_time = 120.0;
5252
int num_it = 0;
5353

@@ -159,7 +159,7 @@ TEST(AStarTest, test_a_star_se2)
159159
int max_iterations = 10000;
160160
float tolerance = 10.0;
161161
int it_on_approach = 10;
162-
int terminal_checking_interval = 500;
162+
int terminal_checking_interval = 5000;
163163
double max_planning_time = 120.0;
164164
int num_it = 0;
165165

@@ -239,7 +239,7 @@ TEST(AStarTest, test_a_star_lattice)
239239
int max_iterations = 10000;
240240
float tolerance = 10.0;
241241
int it_on_approach = 10;
242-
int terminal_checking_interval = 500;
242+
int terminal_checking_interval = 5000;
243243
double max_planning_time = 120.0;
244244
int num_it = 0;
245245

@@ -310,7 +310,7 @@ TEST(AStarTest, test_se2_single_pose_path)
310310
int max_iterations = 100;
311311
float tolerance = 10.0;
312312
int it_on_approach = 10;
313-
int terminal_checking_interval = 500;
313+
int terminal_checking_interval = 5000;
314314
double max_planning_time = 120.0;
315315
int num_it = 0;
316316

nav2_smac_planner/test/test_smoother.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,7 @@ TEST(SmootherTest, test_full_smoother)
8989
int max_iterations = 10000;
9090
float tolerance = 10.0;
9191
int it_on_approach = 10;
92-
int terminal_checking_interval = 500;
92+
int terminal_checking_interval = 5000;
9393
double max_planning_time = 120.0;
9494
int num_it = 0;
9595

nav2_theta_star_planner/src/theta_star.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ ThetaStar::ThetaStar()
2727
allow_unknown_(true),
2828
size_x_(0),
2929
size_y_(0),
30-
terminal_checking_interval_(500),
30+
terminal_checking_interval_(5000),
3131
index_generated_(0)
3232
{
3333
exp_node = new tree_node;

0 commit comments

Comments
 (0)