Skip to content

Commit cecb3ff

Browse files
author
Kemal Bektas
committed
Support cancel in Navfn planner
1 parent a32971d commit cecb3ff

File tree

4 files changed

+39
-16
lines changed

4 files changed

+39
-16
lines changed

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+
int cancel_check_interval;
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 % cancel_check_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 % cancel_check_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();

0 commit comments

Comments
 (0)