Skip to content

Commit 81335bf

Browse files
bektaskemalKemal Bektas
authored andcommitted
Stop planner if the goal is cancelled (ros-navigation#4148)
* Add support for stopping planners when the action is cancelled Signed-off-by: Kemal Bektas <kemal.bektas@node-robotics.com> * Support cancel in Smac planner Signed-off-by: Kemal Bektas <kemal.bektas@node-robotics.com> * Support cancel in Theta* planner Signed-off-by: Kemal Bektas <kemal.bektas@node-robotics.com> * Support cancel in Navfn planner Signed-off-by: Kemal Bektas <kemal.bektas@node-robotics.com> * Update nav2_system_tests to use cancel checker Signed-off-by: Kemal Bektas <kemal.bektas@node-robotics.com> * Add terminal_checking_interval parameter Signed-off-by: Kemal Bektas <kemal.bektas@node-robotics.com> * Handle timeout and cancel check on the same branch and default to 5000 iterations Signed-off-by: Kemal Bektas <kemal.bektas@node-robotics.com> * Add system tests for cancel Signed-off-by: Kemal Bektas <kemal.bektas@node-robotics.com> --------- Signed-off-by: Kemal Bektas <kemal.bektas@node-robotics.com> Co-authored-by: Kemal Bektas <kemal.bektas@node-robotics.com>
1 parent c9c5303 commit 81335bf

34 files changed

+413
-91
lines changed

nav2_core/include/nav2_core/global_planner.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -71,11 +71,13 @@ class GlobalPlanner
7171
* @brief Method create the plan from a starting and ending goal.
7272
* @param start The starting pose of the robot
7373
* @param goal The goal pose of the robot
74+
* @param cancel_checker Function to check if the action has been canceled
7475
* @return The sequence of poses to get from start to goal, if any
7576
*/
7677
virtual nav_msgs::msg::Path createPlan(
7778
const geometry_msgs::msg::PoseStamped & start,
78-
const geometry_msgs::msg::PoseStamped & goal) = 0;
79+
const geometry_msgs::msg::PoseStamped & goal,
80+
std::function<bool()> cancel_checker) = 0;
7981
};
8082

8183
} // namespace nav2_core

nav2_core/include/nav2_core/planner_exceptions.hpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -113,6 +113,13 @@ class NoViapointsGiven : public PlannerException
113113
: PlannerException(description) {}
114114
};
115115

116+
class PlannerCancelled : public PlannerException
117+
{
118+
public:
119+
explicit PlannerCancelled(const std::string & description)
120+
: PlannerException(description) {}
121+
};
122+
116123
} // namespace nav2_core
117124

118125
#endif // NAV2_CORE__PLANNER_EXCEPTIONS_HPP_

nav2_navfn_planner/include/nav2_navfn_planner/navfn.hpp

Lines changed: 13 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343
#include <stdint.h>
4444
#include <string.h>
4545
#include <stdio.h>
46+
#include <functional>
4647

4748
namespace nav2_navfn_planner
4849
{
@@ -131,14 +132,16 @@ class NavFn
131132

132133
/**
133134
* @brief Calculates a plan using the A* heuristic, returns true if one is found
135+
* @param cancelChecker Function to check if the task has been canceled
134136
* @return True if a plan is found, false otherwise
135137
*/
136-
bool calcNavFnAstar();
138+
bool calcNavFnAstar(std::function<bool()> cancelChecker);
137139

138140
/**
139-
* @brief Caclulates the full navigation function using Dijkstra
141+
* @brief Calculates the full navigation function using Dijkstra
142+
* @param cancelChecker Function to check if the task has been canceled
140143
*/
141-
bool calcNavFnDijkstra(bool atStart = false);
144+
bool calcNavFnDijkstra(std::function<bool()> cancelChecker, bool atStart = false);
142145

143146
/**
144147
* @brief Accessor for the x-coordinates of a path
@@ -179,6 +182,9 @@ class NavFn
179182
float curT; /**< current threshold */
180183
float priInc; /**< priority threshold increment */
181184

185+
/**< number of cycles between checks for cancellation */
186+
static constexpr int terminal_checking_interval = 5000;
187+
182188
/** goal and start positions */
183189
/**
184190
* @brief Sets the goal position for the planner.
@@ -229,18 +235,20 @@ class NavFn
229235
* @brief Run propagation for <cycles> iterations, or until start is reached using
230236
* breadth-first Dijkstra method
231237
* @param cycles The maximum number of iterations to run for
238+
* @param cancelChecker Function to check if the task has been canceled
232239
* @param atStart Whether or not to stop when the start point is reached
233240
* @return true if the start point is reached
234241
*/
235-
bool propNavFnDijkstra(int cycles, bool atStart = false);
242+
bool propNavFnDijkstra(int cycles, std::function<bool()> cancelChecker, bool atStart = false);
236243

237244
/**
238245
* @brief Run propagation for <cycles> iterations, or until start is reached using
239246
* the best-first A* method with Euclidean distance heuristic
240247
* @param cycles The maximum number of iterations to run for
248+
* @param cancelChecker Function to check if the task has been canceled
241249
* @return true if the start point is reached
242250
*/
243-
bool propNavFnAstar(int cycles); /**< returns true if start point found */
251+
bool propNavFnAstar(int cycles, std::function<bool()> cancelChecker);
244252

245253
/** gradient and paths */
246254
float * gradx, * grady; /**< gradient arrays, size of potential array */

nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -81,24 +81,28 @@ class NavfnPlanner : public nav2_core::GlobalPlanner
8181
* @brief Creating a plan from start and goal poses
8282
* @param start Start pose
8383
* @param goal Goal pose
84+
* @param cancel_checker Function to check if the task has been canceled
8485
* @return nav_msgs::Path of the generated path
8586
*/
8687
nav_msgs::msg::Path createPlan(
8788
const geometry_msgs::msg::PoseStamped & start,
88-
const geometry_msgs::msg::PoseStamped & goal) override;
89+
const geometry_msgs::msg::PoseStamped & goal,
90+
std::function<bool()> cancel_checker) override;
8991

9092
protected:
9193
/**
9294
* @brief Compute a plan given start and goal poses, provided in global world frame.
9395
* @param start Start pose
9496
* @param goal Goal pose
9597
* @param tolerance Relaxation constraint in x and y
98+
* @param cancel_checker Function to check if the task has been canceled
9699
* @param plan Path to be computed
97100
* @return true if can find the path
98101
*/
99102
bool makePlan(
100103
const geometry_msgs::msg::Pose & start,
101104
const geometry_msgs::msg::Pose & goal, double tolerance,
105+
std::function<bool()> cancel_checker,
102106
nav_msgs::msg::Path & plan);
103107

104108
/**

nav2_navfn_planner/src/navfn.cpp

Lines changed: 15 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@
4444
#include "nav2_navfn_planner/navfn.hpp"
4545

4646
#include <algorithm>
47+
#include "nav2_core/planner_exceptions.hpp"
4748
#include "rclcpp/rclcpp.hpp"
4849

4950
namespace nav2_navfn_planner
@@ -293,12 +294,12 @@ NavFn::setCostmap(const COSTTYPE * cmap, bool isROS, bool allow_unknown)
293294
}
294295

295296
bool
296-
NavFn::calcNavFnDijkstra(bool atStart)
297+
NavFn::calcNavFnDijkstra(std::function<bool()> cancelChecker, bool atStart)
297298
{
298299
setupNavFn(true);
299300

300301
// calculate the nav fn and path
301-
return propNavFnDijkstra(std::max(nx * ny / 20, nx + ny), atStart);
302+
return propNavFnDijkstra(std::max(nx * ny / 20, nx + ny), cancelChecker, atStart);
302303
}
303304

304305

@@ -307,12 +308,12 @@ NavFn::calcNavFnDijkstra(bool atStart)
307308
//
308309

309310
bool
310-
NavFn::calcNavFnAstar()
311+
NavFn::calcNavFnAstar(std::function<bool()> cancelChecker)
311312
{
312313
setupNavFn(true);
313314

314315
// calculate the nav fn and path
315-
return propNavFnAstar(std::max(nx * ny / 20, nx + ny));
316+
return propNavFnAstar(std::max(nx * ny / 20, nx + ny), cancelChecker);
316317
}
317318

318319
//
@@ -571,7 +572,7 @@ NavFn::updateCellAstar(int n)
571572
//
572573

573574
bool
574-
NavFn::propNavFnDijkstra(int cycles, bool atStart)
575+
NavFn::propNavFnDijkstra(int cycles, std::function<bool()> cancelChecker, bool atStart)
575576
{
576577
int nwv = 0; // max priority block size
577578
int nc = 0; // number of cells put into priority blocks
@@ -581,6 +582,10 @@ NavFn::propNavFnDijkstra(int cycles, bool atStart)
581582
int startCell = start[1] * nx + start[0];
582583

583584
for (; cycle < cycles; cycle++) { // go for this many cycles, unless interrupted
585+
if (cycle % terminal_checking_interval == 0 && cancelChecker()) {
586+
throw nav2_core::PlannerCancelled("Planner was cancelled");
587+
}
588+
584589
if (curPe == 0 && nextPe == 0) { // priority blocks empty
585590
break;
586591
}
@@ -652,7 +657,7 @@ NavFn::propNavFnDijkstra(int cycles, bool atStart)
652657
//
653658

654659
bool
655-
NavFn::propNavFnAstar(int cycles)
660+
NavFn::propNavFnAstar(int cycles, std::function<bool()> cancelChecker)
656661
{
657662
int nwv = 0; // max priority block size
658663
int nc = 0; // number of cells put into priority blocks
@@ -667,6 +672,10 @@ NavFn::propNavFnAstar(int cycles)
667672

668673
// do main cycle
669674
for (; cycle < cycles; cycle++) { // go for this many cycles, unless interrupted
675+
if (cycle % terminal_checking_interval == 0 && cancelChecker()) {
676+
throw nav2_core::PlannerCancelled("Planner was cancelled");
677+
}
678+
670679
if (curPe == 0 && nextPe == 0) { // priority blocks empty
671680
break;
672681
}

nav2_navfn_planner/src/navfn_planner.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -129,7 +129,8 @@ NavfnPlanner::cleanup()
129129

130130
nav_msgs::msg::Path NavfnPlanner::createPlan(
131131
const geometry_msgs::msg::PoseStamped & start,
132-
const geometry_msgs::msg::PoseStamped & goal)
132+
const geometry_msgs::msg::PoseStamped & goal,
133+
std::function<bool()> cancel_checker)
133134
{
134135
#ifdef BENCHMARK_TESTING
135136
steady_clock::time_point a = steady_clock::now();
@@ -183,7 +184,7 @@ nav_msgs::msg::Path NavfnPlanner::createPlan(
183184
return path;
184185
}
185186

186-
if (!makePlan(start.pose, goal.pose, tolerance_, path)) {
187+
if (!makePlan(start.pose, goal.pose, tolerance_, cancel_checker, path)) {
187188
throw nav2_core::NoValidPathCouldBeFound(
188189
"Failed to create plan with tolerance of: " + std::to_string(tolerance_) );
189190
}
@@ -214,6 +215,7 @@ bool
214215
NavfnPlanner::makePlan(
215216
const geometry_msgs::msg::Pose & start,
216217
const geometry_msgs::msg::Pose & goal, double tolerance,
218+
std::function<bool()> cancel_checker,
217219
nav_msgs::msg::Path & plan)
218220
{
219221
// clear the plan, just in case
@@ -261,9 +263,9 @@ NavfnPlanner::makePlan(
261263
planner_->setStart(map_goal);
262264
planner_->setGoal(map_start);
263265
if (use_astar_) {
264-
planner_->calcNavFnAstar();
266+
planner_->calcNavFnAstar(cancel_checker);
265267
} else {
266-
planner_->calcNavFnDijkstra(true);
268+
planner_->calcNavFnDijkstra(cancel_checker, true);
267269
}
268270

269271
double resolution = costmap_->getResolution();

nav2_planner/include/nav2_planner/planner_server.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,12 +68,15 @@ class PlannerServer : public nav2_util::LifecycleNode
6868
* @brief Method to get plan from the desired plugin
6969
* @param start starting pose
7070
* @param goal goal request
71+
* @param planner_id The planner to plan with
72+
* @param cancel_checker A function to check if the action has been canceled
7173
* @return Path
7274
*/
7375
nav_msgs::msg::Path getPlan(
7476
const geometry_msgs::msg::PoseStamped & start,
7577
const geometry_msgs::msg::PoseStamped & goal,
76-
const std::string & planner_id);
78+
const std::string & planner_id,
79+
std::function<bool()> cancel_checker);
7780

7881
protected:
7982
/**

nav2_planner/src/planner_server.cpp

Lines changed: 22 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -396,6 +396,10 @@ void PlannerServer::computePlanThroughPoses()
396396
throw nav2_core::PlannerTFError("Unable to get start pose");
397397
}
398398

399+
auto cancel_checker = [this]() {
400+
return action_server_poses_->is_cancel_requested();
401+
};
402+
399403
// Get consecutive paths through these points
400404
for (unsigned int i = 0; i != goal->goals.size(); i++) {
401405
// Get starting point
@@ -415,7 +419,9 @@ void PlannerServer::computePlanThroughPoses()
415419
}
416420

417421
// Get plan from start -> goal
418-
nav_msgs::msg::Path curr_path = getPlan(curr_start, curr_goal, goal->planner_id);
422+
nav_msgs::msg::Path curr_path = getPlan(
423+
curr_start, curr_goal, goal->planner_id,
424+
cancel_checker);
419425

420426
if (!validatePath<ActionThroughPoses>(curr_goal, curr_path, goal->planner_id)) {
421427
throw nav2_core::NoValidPathCouldBeFound(goal->planner_id + " generated a empty path");
@@ -478,6 +484,9 @@ void PlannerServer::computePlanThroughPoses()
478484
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
479485
result->error_code = ActionThroughPosesResult::NO_VIAPOINTS_GIVEN;
480486
action_server_poses_->terminate_current(result);
487+
} catch (nav2_core::PlannerCancelled &) {
488+
RCLCPP_INFO(get_logger(), "Goal was canceled. Canceling planning action.");
489+
action_server_poses_->terminate_all();
481490
} catch (std::exception & ex) {
482491
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
483492
result->error_code = ActionThroughPosesResult::UNKNOWN;
@@ -518,7 +527,11 @@ PlannerServer::computePlan()
518527
throw nav2_core::PlannerTFError("Unable to transform poses to global frame");
519528
}
520529

521-
result->path = getPlan(start, goal_pose, goal->planner_id);
530+
auto cancel_checker = [this]() {
531+
return action_server_pose_->is_cancel_requested();
532+
};
533+
534+
result->path = getPlan(start, goal_pose, goal->planner_id, cancel_checker);
522535

523536
if (!validatePath<ActionThroughPoses>(goal_pose, result->path, goal->planner_id)) {
524537
throw nav2_core::NoValidPathCouldBeFound(goal->planner_id + " generated a empty path");
@@ -569,6 +582,9 @@ PlannerServer::computePlan()
569582
exceptionWarning(start, goal->goal, goal->planner_id, ex);
570583
result->error_code = ActionToPoseResult::TF_ERROR;
571584
action_server_pose_->terminate_current(result);
585+
} catch (nav2_core::PlannerCancelled &) {
586+
RCLCPP_INFO(get_logger(), "Goal was canceled. Canceling planning action.");
587+
action_server_pose_->terminate_all();
572588
} catch (std::exception & ex) {
573589
exceptionWarning(start, goal->goal, goal->planner_id, ex);
574590
result->error_code = ActionToPoseResult::UNKNOWN;
@@ -580,22 +596,23 @@ nav_msgs::msg::Path
580596
PlannerServer::getPlan(
581597
const geometry_msgs::msg::PoseStamped & start,
582598
const geometry_msgs::msg::PoseStamped & goal,
583-
const std::string & planner_id)
599+
const std::string & planner_id,
600+
std::function<bool()> cancel_checker)
584601
{
585602
RCLCPP_DEBUG(
586603
get_logger(), "Attempting to a find path from (%.2f, %.2f) to "
587604
"(%.2f, %.2f).", start.pose.position.x, start.pose.position.y,
588605
goal.pose.position.x, goal.pose.position.y);
589606

590607
if (planners_.find(planner_id) != planners_.end()) {
591-
return planners_[planner_id]->createPlan(start, goal);
608+
return planners_[planner_id]->createPlan(start, goal, cancel_checker);
592609
} else {
593610
if (planners_.size() == 1 && planner_id.empty()) {
594611
RCLCPP_WARN_ONCE(
595612
get_logger(), "No planners specified in action call. "
596613
"Server will use only plugin %s in server."
597614
" This warning will appear once.", planner_ids_concat_.c_str());
598-
return planners_[planners_.begin()->first]->createPlan(start, goal);
615+
return planners_[planners_.begin()->first]->createPlan(start, goal, cancel_checker);
599616
} else {
600617
RCLCPP_ERROR(
601618
get_logger(), "planner %s is not a valid planner. "

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: 5000 # number of iterations between checking if the goal has been cancelled or planner timed out
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: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -88,13 +88,16 @@ 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 or
92+
* or planning time exceeded
9193
* @param max_planning_time Maximum time (in seconds) to wait for a plan, createPath returns
9294
* false after this timeout
9395
*/
9496
void initialize(
9597
const bool & allow_unknown,
9698
int & max_iterations,
9799
const int & max_on_approach_iterations,
100+
const int & terminal_checking_interval,
98101
const double & max_planning_time,
99102
const float & lookup_table_size,
100103
const unsigned int & dim_3_size);
@@ -104,11 +107,13 @@ class AStarAlgorithm
104107
* @param path Reference to a vector of indicies of generated path
105108
* @param num_iterations Reference to number of iterations to create plan
106109
* @param tolerance Reference to tolerance in costmap nodes
110+
* @param cancel_checker Function to check if the task has been canceled
107111
* @param expansions_log Optional expansions logged for debug
108112
* @return if plan was successful
109113
*/
110114
bool createPath(
111115
CoordinateVector & path, int & num_iterations, const float & tolerance,
116+
std::function<bool()> cancel_checker,
112117
std::vector<std::tuple<float, float, float>> * expansions_log = nullptr);
113118

114119
/**
@@ -250,11 +255,11 @@ class AStarAlgorithm
250255
*/
251256
void clearStart();
252257

253-
int _timing_interval = 5000;
254258

255259
bool _traverse_unknown;
256260
int _max_iterations;
257261
int _max_on_approach_iterations;
262+
int _terminal_checking_interval;
258263
double _max_planning_time;
259264
float _tolerance;
260265
unsigned int _x_size;

0 commit comments

Comments
 (0)