44 #include "nav2_navfn_planner/navfn.hpp"
47 #include "rclcpp/rclcpp.hpp"
49 namespace nav2_navfn_planner
121 pb1 =
new int[PRIORITYBUFSIZE];
122 pb2 =
new int[PRIORITYBUFSIZE];
123 pb3 =
new int[PRIORITYBUFSIZE];
127 priInc = 2 * COST_NEUTRAL;
130 goal[0] = goal[1] = 0;
131 start[0] = start[1] = 0;
139 pathx =
pathy = NULL;
188 RCLCPP_DEBUG(rclcpp::get_logger(
"rclcpp"),
"[NavFn] Setting goal to %d,%d\n", goal[0], goal[1]);
197 rclcpp::get_logger(
"rclcpp"),
"[NavFn] Setting start to %d,%d\n", start[0],
208 RCLCPP_DEBUG(rclcpp::get_logger(
"rclcpp"),
"[NavFn] Array is %d x %d\n", xs, ys);
232 memset(
costarr, 0,
ns *
sizeof(COSTTYPE));
250 for (
int i = 0; i < ny; i++) {
252 for (
int j = 0; j < nx; j++, k++, cmap++, cm++) {
259 if (v < COST_OBS_ROS) {
260 v = COST_NEUTRAL + COST_FACTOR * v;
265 }
else if (v == COST_UNKNOWN_ROS && allow_unknown) {
272 for (
int i = 0; i < ny; i++) {
274 for (
int j = 0; j < nx; j++, k++, cmap++, cm++) {
276 if (i < 7 || i > ny - 8 || j < 7 || j > nx - 8) {
280 if (v < COST_OBS_ROS) {
281 v = COST_NEUTRAL + COST_FACTOR * v;
286 }
else if (v == COST_UNKNOWN_ROS) {
327 #define push_cur(n) {if (n >= 0 && n < ns && !pending[n] && \
328 costarr[n] < COST_OBS && curPe < PRIORITYBUFSIZE) \
329 {curP[curPe++] = n; pending[n] = true;}}
330 #define push_next(n) {if (n >= 0 && n < ns && !pending[n] && \
331 costarr[n] < COST_OBS && nextPe < PRIORITYBUFSIZE) \
332 {nextP[nextPe++] = n; pending[n] = true;}}
333 #define push_over(n) {if (n >= 0 && n < ns && !pending[n] && \
334 costarr[n] < COST_OBS && overPe < PRIORITYBUFSIZE) \
335 {overP[overPe++] = n; pending[n] = true;}}
344 for (
int i = 0; i <
ns; i++) {
355 for (
int i = 0; i < nx; i++) {
359 for (
int i = 0; i < nx; i++) {
363 for (
int i = 0; i < ny; i++, pc += nx) {
367 for (
int i = 0; i < ny; i++, pc += nx) {
382 int k = goal[0] + goal[1] * nx;
388 for (
int i = 0; i <
ns; i++, pc++) {
389 if (*pc >= COST_OBS) {
418 #define INVSQRT2 0.707106781
435 if (l < r) {tc = l;}
else {tc = r;}
436 if (u < d) {ta = u;}
else {ta = d;}
440 float hf =
static_cast<float>(
costarr[n]);
456 float v = -0.2301 * d * d + 0.5307 * d + 0.7040;
464 float le = INVSQRT2 *
static_cast<float>(
costarr[n - 1]);
465 float re = INVSQRT2 *
static_cast<float>(
costarr[n + 1]);
466 float ue = INVSQRT2 *
static_cast<float>(
costarr[n - nx]);
467 float de = INVSQRT2 *
static_cast<float>(
costarr[n + nx]);
470 if (l > pot + le) {push_next(n - 1);}
471 if (r > pot + re) {push_next(n + 1);}
472 if (u > pot + ue) {push_next(n - nx);}
473 if (d > pot + de) {push_next(n + nx);}
475 if (l > pot + le) {push_over(n - 1);}
476 if (r > pot + re) {push_over(n + 1);}
477 if (u > pot + ue) {push_over(n - nx);}
478 if (d > pot + de) {push_over(n + nx);}
493 #define INVSQRT2 0.707106781
510 if (l < r) {tc = l;}
else {tc = r;}
511 if (u < d) {ta = u;}
else {ta = d;}
515 float hf =
static_cast<float>(
costarr[n]);
531 float v = -0.2301 * d * d + 0.5307 * d + 0.7040;
539 float le = INVSQRT2 *
static_cast<float>(
costarr[n - 1]);
540 float re = INVSQRT2 *
static_cast<float>(
costarr[n + 1]);
541 float ue = INVSQRT2 *
static_cast<float>(
costarr[n - nx]);
542 float de = INVSQRT2 *
static_cast<float>(
costarr[n + nx]);
547 float dist = hypot(x - start[0], y - start[1]) *
static_cast<float>(COST_NEUTRAL);
552 if (l > pot + le) {push_next(n - 1);}
553 if (r > pot + re) {push_next(n + 1);}
554 if (u > pot + ue) {push_next(n - nx);}
555 if (d > pot + de) {push_next(n + nx);}
557 if (l > pot + le) {push_over(n - 1);}
558 if (r > pot + re) {push_over(n + 1);}
559 if (u > pot + ue) {push_over(n - nx);}
560 if (d > pot + de) {push_over(n + nx);}
583 int startCell = start[1] * nx + start[0];
585 for (; cycle < cycles; cycle++) {
586 if (curPe == 0 && nextPe == 0) {
633 if (
potarr[startCell] < POT_HIGH) {
640 rclcpp::get_logger(
"rclcpp"),
641 "[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n",
642 cycle, nc, (
int)((nc * 100.0) / (
ns -
nobs)), nwv);
644 return (cycle < cycles) ? true :
false;
664 float dist = hypot(goal[0] - start[0], goal[1] - start[1]) *
static_cast<float>(COST_NEUTRAL);
668 int startCell = start[1] * nx + start[0];
671 for (; cycle < cycles; cycle++) {
672 if (curPe == 0 && nextPe == 0) {
718 if (
potarr[startCell] < POT_HIGH) {
726 rclcpp::get_logger(
"rclcpp"),
727 "[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n",
728 cycle, nc, (
int)((nc * 100.0) / (
ns -
nobs)), nwv);
730 if (
potarr[startCell] < POT_HIGH) {
763 if (pathx) {
delete[] pathx;}
765 pathx =
new float[n];
766 pathy =
new float[n];
772 if (st == NULL) {st = start;}
773 int stc = st[1] * nx + st[0];
781 for (
int i = 0; i < n; i++) {
783 int nearest_point = std::max(
786 nx * ny - 1, stc +
static_cast<int>(round(dx)) +
787 static_cast<int>(nx * round(dy))));
788 if (
potarr[nearest_point] < COST_NEUTRAL) {
789 pathx[
npath] =
static_cast<float>(goal[0]);
794 if (stc < nx || stc >
ns - nx) {
795 RCLCPP_DEBUG(rclcpp::get_logger(
"rclcpp"),
"[PathCalc] Out of bounds");
800 pathx[
npath] = stc % nx + dx;
804 bool oscillation_detected =
false;
810 rclcpp::get_logger(
"rclcpp"),
811 "[PathCalc] oscillation detected, attempting fix.");
812 oscillation_detected =
true;
815 int stcnx = stc + nx;
816 int stcpx = stc - nx;
819 if (
potarr[stc] >= POT_HIGH ||
820 potarr[stc + 1] >= POT_HIGH ||
821 potarr[stc - 1] >= POT_HIGH ||
822 potarr[stcnx] >= POT_HIGH ||
823 potarr[stcnx + 1] >= POT_HIGH ||
824 potarr[stcnx - 1] >= POT_HIGH ||
825 potarr[stcpx] >= POT_HIGH ||
826 potarr[stcpx + 1] >= POT_HIGH ||
827 potarr[stcpx - 1] >= POT_HIGH ||
828 oscillation_detected)
831 rclcpp::get_logger(
"rclcpp"),
832 "[Path] Pot fn boundary, following grid (%0.1f/%d)",
potarr[stc],
npath);
858 rclcpp::get_logger(
"rclcpp"),
"[Path] Pot: %0.1f pos: %0.1f,%0.1f",
861 if (
potarr[stc] >= POT_HIGH) {
862 RCLCPP_DEBUG(rclcpp::get_logger(
"rclcpp"),
"[PathCalc] No path found, high potential");
875 float x1 = (1.0 - dx) *
gradx[stc] + dx *
gradx[stc + 1];
876 float x2 = (1.0 - dx) *
gradx[stcnx] + dx *
gradx[stcnx + 1];
877 float x = (1.0 - dy) * x1 + dy * x2;
878 float y1 = (1.0 - dx) *
grady[stc] + dx *
grady[stc + 1];
879 float y2 = (1.0 - dx) *
grady[stcnx] + dx *
grady[stcnx + 1];
880 float y = (1.0 - dy) * y1 + dy * y2;
885 rclcpp::get_logger(
"rclcpp"),
886 "[Path] %0.2f,%0.2f %0.2f,%0.2f %0.2f,%0.2f %0.2f,%0.2f; final x=%.3f, y=%.3f\n",
893 if (x == 0.0 && y == 0.0) {
894 RCLCPP_DEBUG(rclcpp::get_logger(
"rclcpp"),
"[PathCalc] Zero gradient");
904 if (dx > 1.0) {stc++; dx -= 1.0;}
905 if (dx < -1.0) {stc--; dx += 1.0;}
906 if (dy > 1.0) {stc += nx; dy -= 1.0;}
907 if (dy < -1.0) {stc -= nx; dy += 1.0;}
915 RCLCPP_DEBUG(rclcpp::get_logger(
"rclcpp"),
"[PathCalc] No path found, path too long");
934 if (n < nx || n >
ns - nx) {
943 if (cv >= POT_HIGH) {
944 if (
potarr[n - 1] < POT_HIGH) {
946 }
else if (
potarr[n + 1] < POT_HIGH) {
949 if (
potarr[n - nx] < POT_HIGH) {
951 }
else if (
potarr[n + nx] < POT_HIGH) {
956 if (
potarr[n - 1] < POT_HIGH) {
959 if (
potarr[n + 1] < POT_HIGH) {
964 if (
potarr[n - nx] < POT_HIGH) {
965 dy +=
potarr[n - nx] - cv;
967 if (
potarr[n + nx] < POT_HIGH) {
968 dy += cv -
potarr[n + nx];
973 float norm = hypot(dx, dy);
976 gradx[n] = norm * dx;
977 grady[n] = norm * dy;
int getPathLen()
Accessor for the length of a path.
bool propNavFnDijkstra(int cycles, bool atStart=false)
Run propagation for <cycles> iterations, or until start is reached using breadth-first Dijkstra metho...
float * getPathX()
Accessor for the x-coordinates of a path.
float gradCell(int n)
Calculate gradient at a cell.
void updateCell(int n)
Updates the cell at index n.
int calcPath(int n, int *st=NULL)
Calculates the path for at mose <n> cycles.
float getLastPathCost()
Gets the cost of the path found the last time a navigation function was computed.
bool calcNavFnDijkstra(bool atStart=false)
Caclulates the full navigation function using Dijkstra.
void updateCellAstar(int n)
Updates the cell at index n using the A* heuristic.
void initCost(int k, float v)
Initialize cell k with cost v for propagation.
void setNavArr(int nx, int ny)
Sets or resets the size of the map.
NavFn(int nx, int ny)
Constructs the planner.
void setCostmap(const COSTTYPE *cmap, bool isROS=true, bool allow_unknown=true)
Set up the cost array for the planner, usually from ROS.
void setupNavFn(bool keepit=false)
Set up navigation potential arrays for new propagation.
bool propNavFnAstar(int cycles)
Run propagation for <cycles> iterations, or until start is reached using the best-first A* method wit...
bool calcNavFnAstar()
Calculates a plan using the A* heuristic, returns true if one is found.
void setGoal(int *goal)
Sets the goal position for the planner. Note: the navigation cost field computed gives the cost to ge...
float * getPathY()
Accessor for the y-coordinates of a path.
void setStart(int *start)
Sets the start position for the planner. Note: the navigation cost field computed gives the cost to g...