Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
navfn.cpp
1 // Copyright (c) 2008, Willow Garage, Inc.
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD License 2.0)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of the Willow Garage nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
33 //
34 // Navigation function computation
35 // Uses Dijkstra's method
36 // Modified for Euclidean-distance computation
37 //
38 // Path calculation uses no interpolation when pot field is at max in
39 // nearby cells
40 //
41 // Path calc has sanity check that it succeeded
42 //
43 
44 #include "nav2_navfn_planner/navfn.hpp"
45 
46 #include <algorithm>
47 #include "nav2_core/planner_exceptions.hpp"
48 #include "rclcpp/rclcpp.hpp"
49 
50 namespace nav2_navfn_planner
51 {
52 
53 //
54 // function to perform nav fn calculation
55 // keeps track of internal buffers, will be more efficient
56 // if the size of the environment does not change
57 //
58 
59 // Example usage:
60 /*
61 int
62 create_nav_plan_astar(
63  COSTTYPE * costmap, int nx, int ny,
64  int * goal, int * start,
65  float * plan, int nplan)
66 {
67  static NavFn * nav = NULL;
68 
69  if (nav == NULL) {
70  nav = new NavFn(nx, ny);
71  }
72 
73  if (nav->nx != nx || nav->ny != ny) { // check for compatibility with previous call
74  delete nav;
75  nav = new NavFn(nx, ny);
76  }
77 
78  nav->setGoal(goal);
79  nav->setStart(start);
80 
81  nav->costarr = costmap;
82  nav->setupNavFn(true);
83 
84  // calculate the nav fn and path
85  nav->priInc = 2 * COST_NEUTRAL;
86  nav->propNavFnAstar(std::max(nx * ny / 20, nx + ny));
87 
88  // path
89  int len = nav->calcPath(nplan);
90 
91  if (len > 0) { // found plan
92  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "[NavFn] Path found, %d steps\n", len);
93  } else {
94  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "[NavFn] No path found\n");
95  }
96 
97  if (len > 0) {
98  for (int i = 0; i < len; i++) {
99  plan[i * 2] = nav->pathx[i];
100  plan[i * 2 + 1] = nav->pathy[i];
101  }
102  }
103 
104  return len;
105 }
106 */
107 
108 //
109 // create nav fn buffers
110 //
111 
112 NavFn::NavFn(int xs, int ys)
113 {
114  // create cell arrays
115  costarr = NULL;
116  potarr = NULL;
117  pending = NULL;
118  gradx = grady = NULL;
119  setNavArr(xs, ys);
120 
121  // priority buffers
122  pb1 = new int[PRIORITYBUFSIZE];
123  pb2 = new int[PRIORITYBUFSIZE];
124  pb3 = new int[PRIORITYBUFSIZE];
125 
126  // for Dijkstra (breadth-first), set to COST_NEUTRAL
127  // for A* (best-first), set to COST_NEUTRAL
128  priInc = 2 * COST_NEUTRAL;
129 
130  // goal and start
131  goal[0] = goal[1] = 0;
132  start[0] = start[1] = 0;
133 
134  // display function
135  // displayFn = NULL;
136  // displayInt = 0;
137 
138  // path buffers
139  npathbuf = npath = 0;
140  pathx = pathy = NULL;
141  pathStep = 0.5;
142 }
143 
144 
145 NavFn::~NavFn()
146 {
147  if (costarr) {
148  delete[] costarr;
149  }
150  if (potarr) {
151  delete[] potarr;
152  }
153  if (pending) {
154  delete[] pending;
155  }
156  if (gradx) {
157  delete[] gradx;
158  }
159  if (grady) {
160  delete[] grady;
161  }
162  if (pathx) {
163  delete[] pathx;
164  }
165  if (pathy) {
166  delete[] pathy;
167  }
168  if (pb1) {
169  delete[] pb1;
170  }
171  if (pb2) {
172  delete[] pb2;
173  }
174  if (pb3) {
175  delete[] pb3;
176  }
177 }
178 
179 
180 //
181 // set goal, start positions for the nav fn
182 //
183 
184 void
186 {
187  goal[0] = g[0];
188  goal[1] = g[1];
189  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "[NavFn] Setting goal to %d,%d\n", goal[0], goal[1]);
190 }
191 
192 void
194 {
195  start[0] = g[0];
196  start[1] = g[1];
197  RCLCPP_DEBUG(
198  rclcpp::get_logger("rclcpp"), "[NavFn] Setting start to %d,%d\n", start[0],
199  start[1]);
200 }
201 
202 //
203 // Set/Reset map size
204 //
205 
206 void
207 NavFn::setNavArr(int xs, int ys)
208 {
209  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "[NavFn] Array is %d x %d\n", xs, ys);
210 
211  nx = xs;
212  ny = ys;
213  ns = nx * ny;
214 
215  if (costarr) {
216  delete[] costarr;
217  }
218  if (potarr) {
219  delete[] potarr;
220  }
221  if (pending) {
222  delete[] pending;
223  }
224 
225  if (gradx) {
226  delete[] gradx;
227  }
228  if (grady) {
229  delete[] grady;
230  }
231 
232  costarr = new COSTTYPE[ns]; // cost array, 2d config space
233  memset(costarr, 0, ns * sizeof(COSTTYPE));
234  potarr = new float[ns]; // navigation potential array
235  pending = new bool[ns];
236  memset(pending, 0, ns * sizeof(bool));
237  gradx = new float[ns];
238  grady = new float[ns];
239 }
240 
241 
242 //
243 // set up cost array, usually from ROS
244 //
245 
246 void
247 NavFn::setCostmap(const COSTTYPE * cmap, bool isROS, bool allow_unknown)
248 {
249  COSTTYPE * cm = costarr;
250  if (isROS) { // ROS-type cost array
251  for (int i = 0; i < ny; i++) {
252  int k = i * nx;
253  for (int j = 0; j < nx; j++, k++, cmap++, cm++) {
254  // This transforms the incoming cost values:
255  // COST_OBS -> COST_OBS (incoming "lethal obstacle")
256  // COST_OBS_ROS -> COST_OBS (incoming "inscribed inflated obstacle")
257  // values in range 0 to 252 -> values from COST_NEUTRAL to COST_OBS_ROS.
258  *cm = COST_OBS;
259  int v = *cmap;
260  if (v < COST_OBS_ROS) {
261  v = COST_NEUTRAL + COST_FACTOR * v;
262  if (v >= COST_OBS) {
263  v = COST_OBS - 1;
264  }
265  *cm = v;
266  } else if (v == COST_UNKNOWN_ROS && allow_unknown) {
267  v = COST_OBS - 1;
268  *cm = v;
269  }
270  }
271  }
272  } else { // not a ROS map, just a PGM
273  for (int i = 0; i < ny; i++) {
274  int k = i * nx;
275  for (int j = 0; j < nx; j++, k++, cmap++, cm++) {
276  *cm = COST_OBS;
277  if (i < 7 || i > ny - 8 || j < 7 || j > nx - 8) {
278  continue; // don't do borders
279  }
280  int v = *cmap;
281  if (v < COST_OBS_ROS) {
282  v = COST_NEUTRAL + COST_FACTOR * v;
283  if (v >= COST_OBS) {
284  v = COST_OBS - 1;
285  }
286  *cm = v;
287  } else if (v == COST_UNKNOWN_ROS) {
288  v = COST_OBS - 1;
289  *cm = v;
290  }
291  }
292  }
293  }
294 }
295 
296 bool
297 NavFn::calcNavFnDijkstra(std::function<bool()> cancelChecker, bool atStart)
298 {
299  setupNavFn(true);
300 
301  // calculate the nav fn and path
302  return propNavFnDijkstra(std::max(nx * ny / 20, nx + ny), cancelChecker, atStart);
303 }
304 
305 
306 //
307 // calculate navigation function, given a costmap, goal, and start
308 //
309 
310 bool
311 NavFn::calcNavFnAstar(std::function<bool()> cancelChecker)
312 {
313  setupNavFn(true);
314 
315  // calculate the nav fn and path
316  return propNavFnAstar(std::max(nx * ny / 20, nx + ny), cancelChecker);
317 }
318 
319 //
320 // returning values
321 //
322 
323 float * NavFn::getPathX() {return pathx;}
324 float * NavFn::getPathY() {return pathy;}
325 int NavFn::getPathLen() {return npath;}
326 
327 // inserting onto the priority blocks
328 #define push_cur(n) {if (n >= 0 && n < ns && !pending[n] && \
329  costarr[n] < COST_OBS && curPe < PRIORITYBUFSIZE) \
330  {curP[curPe++] = n; pending[n] = true;}}
331 #define push_next(n) {if (n >= 0 && n < ns && !pending[n] && \
332  costarr[n] < COST_OBS && nextPe < PRIORITYBUFSIZE) \
333  {nextP[nextPe++] = n; pending[n] = true;}}
334 #define push_over(n) {if (n >= 0 && n < ns && !pending[n] && \
335  costarr[n] < COST_OBS && overPe < PRIORITYBUFSIZE) \
336  {overP[overPe++] = n; pending[n] = true;}}
337 
338 
339 // Set up navigation potential arrays for new propagation
340 
341 void
342 NavFn::setupNavFn(bool keepit)
343 {
344  // reset values in propagation arrays
345  for (int i = 0; i < ns; i++) {
346  potarr[i] = POT_HIGH;
347  if (!keepit) {
348  costarr[i] = COST_NEUTRAL;
349  }
350  gradx[i] = grady[i] = 0.0;
351  }
352 
353  // outer bounds of cost array
354  COSTTYPE * pc;
355  pc = costarr;
356  for (int i = 0; i < nx; i++) {
357  *pc++ = COST_OBS;
358  }
359  pc = costarr + (ny - 1) * nx;
360  for (int i = 0; i < nx; i++) {
361  *pc++ = COST_OBS;
362  }
363  pc = costarr;
364  for (int i = 0; i < ny; i++, pc += nx) {
365  *pc = COST_OBS;
366  }
367  pc = costarr + nx - 1;
368  for (int i = 0; i < ny; i++, pc += nx) {
369  *pc = COST_OBS;
370  }
371 
372  // priority buffers
373  curT = COST_OBS;
374  curP = pb1;
375  curPe = 0;
376  nextP = pb2;
377  nextPe = 0;
378  overP = pb3;
379  overPe = 0;
380  memset(pending, 0, ns * sizeof(bool));
381 
382  // set goal
383  int k = goal[0] + goal[1] * nx;
384  initCost(k, 0);
385 
386  // find # of obstacle cells
387  pc = costarr;
388  int ntot = 0;
389  for (int i = 0; i < ns; i++, pc++) {
390  if (*pc >= COST_OBS) {
391  ntot++; // number of cells that are obstacles
392  }
393  }
394  nobs = ntot;
395 }
396 
397 
398 // initialize a goal-type cost for starting propagation
399 
400 void
401 NavFn::initCost(int k, float v)
402 {
403  potarr[k] = v;
404  push_cur(k + 1);
405  push_cur(k - 1);
406  push_cur(k - nx);
407  push_cur(k + nx);
408 }
409 
410 
411 //
412 // Critical function: calculate updated potential value of a cell,
413 // given its neighbors' values
414 // Planar-wave update calculation from two lowest neighbors in a 4-grid
415 // Quadratic approximation to the interpolated value
416 // No checking of bounds here, this function should be fast
417 //
418 
419 #define INVSQRT2 0.707106781
420 
421 inline void
423 {
424  // get neighbors
425  const float l = potarr[n - 1];
426  const float r = potarr[n + 1];
427  const float u = potarr[n - nx];
428  const float d = potarr[n + nx];
429  // ROS_INFO("[Update] c: %0.1f l: %0.1f r: %0.1f u: %0.1f d: %0.1f\n",
430  // potarr[n], l, r, u, d);
431  // ROS_INFO("[Update] cost: %d\n", costarr[n]);
432 
433  // find lowest, and its lowest neighbor
434  float ta, tc;
435  if (l < r) {tc = l;} else {tc = r;}
436  if (u < d) {ta = u;} else {ta = d;}
437 
438  // do planar wave update
439  if (costarr[n] < COST_OBS) { // don't propagate into obstacles
440  float hf = static_cast<float>(costarr[n]); // traversability factor
441  float dc = tc - ta; // relative cost between ta,tc
442  if (dc < 0) { // ta is lowest
443  dc = -dc;
444  ta = tc;
445  }
446 
447  // calculate new potential
448  float pot;
449  if (dc >= hf) { // if too large, use ta-only update
450  pot = ta + hf;
451  } else { // two-neighbor interpolation update
452  // use quadratic approximation
453  // might speed this up through table lookup, but still have to
454  // do the divide
455  const float div = dc / hf;
456  const float v = -0.2301 * div * div + 0.5307 * div + 0.7040;
457  pot = ta + hf * v;
458  }
459 
460  // ROS_INFO("[Update] new pot: %d\n", costarr[n]);
461 
462  // now add affected neighbors to priority blocks
463  if (pot < potarr[n]) {
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]);
468  potarr[n] = pot;
469  if (pot < curT) { // low-cost buffer block
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);}
474  } else { // overflow block
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);}
479  }
480  }
481  }
482 }
483 
484 //
485 // Use A* method for setting priorities
486 // Critical function: calculate updated potential value of a cell,
487 // given its neighbors' values
488 // Planar-wave update calculation from two lowest neighbors in a 4-grid
489 // Quadratic approximation to the interpolated value
490 // No checking of bounds here, this function should be fast
491 //
492 
493 #define INVSQRT2 0.707106781
494 
495 inline void
497 {
498  // get neighbors
499  float l = potarr[n - 1];
500  float r = potarr[n + 1];
501  float u = potarr[n - nx];
502  float d = potarr[n + nx];
503  // ROS_INFO("[Update] c: %0.1f l: %0.1f r: %0.1f u: %0.1f d: %0.1f\n",
504  // potarr[n], l, r, u, d);
505  // ROS_INFO("[Update] cost of %d: %d\n", n, costarr[n]);
506 
507  // find lowest, and its lowest neighbor
508  float ta, tc;
509  if (l < r) {tc = l;} else {tc = r;}
510  if (u < d) {ta = u;} else {ta = d;}
511 
512  // do planar wave update
513  if (costarr[n] < COST_OBS) { // don't propagate into obstacles
514  float hf = static_cast<float>(costarr[n]); // traversability factor
515  float dc = tc - ta; // relative cost between ta,tc
516  if (dc < 0) { // ta is lowest
517  dc = -dc;
518  ta = tc;
519  }
520 
521  // calculate new potential
522  float pot;
523  if (dc >= hf) { // if too large, use ta-only update
524  pot = ta + hf;
525  } else { // two-neighbor interpolation update
526  // use quadratic approximation
527  // might speed this up through table lookup, but still have to
528  // do the divide
529  const float div = dc / hf;
530  const float v = -0.2301 * div * div + 0.5307 * div + 0.7040;
531  pot = ta + hf * v;
532  }
533 
534  // ROS_INFO("[Update] new pot: %d\n", costarr[n]);
535 
536  // now add affected neighbors to priority blocks
537  if (pot < potarr[n]) {
538  float le = INVSQRT2 * static_cast<float>(costarr[n - 1]);
539  float re = INVSQRT2 * static_cast<float>(costarr[n + 1]);
540  float ue = INVSQRT2 * static_cast<float>(costarr[n - nx]);
541  float de = INVSQRT2 * static_cast<float>(costarr[n + nx]);
542 
543  // calculate distance
544  int x = n % nx;
545  int y = n / nx;
546  float dist = hypot(x - start[0], y - start[1]) * static_cast<float>(COST_NEUTRAL);
547 
548  potarr[n] = pot;
549  pot += dist;
550  if (pot < curT) { // low-cost buffer block
551  if (l > pot + le) {push_next(n - 1);}
552  if (r > pot + re) {push_next(n + 1);}
553  if (u > pot + ue) {push_next(n - nx);}
554  if (d > pot + de) {push_next(n + nx);}
555  } else {
556  if (l > pot + le) {push_over(n - 1);}
557  if (r > pot + re) {push_over(n + 1);}
558  if (u > pot + ue) {push_over(n - nx);}
559  if (d > pot + de) {push_over(n + nx);}
560  }
561  }
562  }
563 }
564 
565 
566 //
567 // main propagation function
568 // Dijkstra method, breadth-first
569 // runs for a specified number of cycles,
570 // or until it runs out of cells to update,
571 // or until the Start cell is found (atStart = true)
572 //
573 
574 bool
575 NavFn::propNavFnDijkstra(int cycles, std::function<bool()> cancelChecker, bool atStart)
576 {
577  int nwv = 0; // max priority block size
578  int nc = 0; // number of cells put into priority blocks
579  int cycle = 0; // which cycle we're on
580 
581  // set up start cell
582  int startCell = start[1] * nx + start[0];
583 
584  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 
589  if (curPe == 0 && nextPe == 0) { // priority blocks empty
590  break;
591  }
592 
593  // stats
594  nc += curPe;
595  if (curPe > nwv) {
596  nwv = curPe;
597  }
598 
599  // reset pending flags on current priority buffer
600  int * pb = curP;
601  int i = curPe;
602  while (i-- > 0) {
603  pending[*(pb++)] = false;
604  }
605 
606  // process current priority buffer
607  pb = curP;
608  i = curPe;
609  while (i-- > 0) {
610  updateCell(*pb++);
611  }
612 
613  // if (displayInt > 0 && (cycle % displayInt) == 0) {
614  // displayFn(this);
615  // }
616 
617  // swap priority blocks curP <=> nextP
618  curPe = nextPe;
619  nextPe = 0;
620  pb = curP; // swap buffers
621  curP = nextP;
622  nextP = pb;
623 
624  // see if we're done with this priority level
625  if (curPe == 0) {
626  curT += priInc; // increment priority threshold
627  curPe = overPe; // set current to overflow block
628  overPe = 0;
629  pb = curP; // swap buffers
630  curP = overP;
631  overP = pb;
632  }
633 
634  // check if we've hit the Start cell
635  if (atStart) {
636  if (potarr[startCell] < POT_HIGH) {
637  break;
638  }
639  }
640  }
641 
642  RCLCPP_DEBUG(
643  rclcpp::get_logger("rclcpp"),
644  "[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n",
645  cycle, nc, (int)((nc * 100.0) / (ns - nobs)), nwv);
646 
647  return (cycle < cycles) ? true : false;
648 }
649 
650 //
651 // main propagation function
652 // A* method, best-first
653 // uses Euclidean distance heuristic
654 // runs for a specified number of cycles,
655 // or until it runs out of cells to update,
656 // or until the Start cell is found (atStart = true)
657 //
658 
659 bool
660 NavFn::propNavFnAstar(int cycles, std::function<bool()> cancelChecker)
661 {
662  int nwv = 0; // max priority block size
663  int nc = 0; // number of cells put into priority blocks
664  int cycle = 0; // which cycle we're on
665 
666  // set initial threshold, based on distance
667  float dist = hypot(goal[0] - start[0], goal[1] - start[1]) * static_cast<float>(COST_NEUTRAL);
668  curT = dist + curT;
669 
670  // set up start cell
671  int startCell = start[1] * nx + start[0];
672 
673  // do main cycle
674  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 
679  if (curPe == 0 && nextPe == 0) { // priority blocks empty
680  break;
681  }
682 
683  // stats
684  nc += curPe;
685  if (curPe > nwv) {
686  nwv = curPe;
687  }
688 
689  // reset pending flags on current priority buffer
690  int * pb = curP;
691  int i = curPe;
692  while (i-- > 0) {
693  pending[*(pb++)] = false;
694  }
695 
696  // process current priority buffer
697  pb = curP;
698  i = curPe;
699  while (i-- > 0) {
700  updateCellAstar(*pb++);
701  }
702 
703  // if (displayInt > 0 && (cycle % displayInt) == 0) {
704  // displayFn(this);
705  // }
706 
707  // swap priority blocks curP <=> nextP
708  curPe = nextPe;
709  nextPe = 0;
710  pb = curP; // swap buffers
711  curP = nextP;
712  nextP = pb;
713 
714  // see if we're done with this priority level
715  if (curPe == 0) {
716  curT += priInc; // increment priority threshold
717  curPe = overPe; // set current to overflow block
718  overPe = 0;
719  pb = curP; // swap buffers
720  curP = overP;
721  overP = pb;
722  }
723 
724  // check if we've hit the Start cell
725  if (potarr[startCell] < POT_HIGH) {
726  break;
727  }
728  }
729 
730  last_path_cost_ = potarr[startCell];
731 
732  RCLCPP_DEBUG(
733  rclcpp::get_logger("rclcpp"),
734  "[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n",
735  cycle, nc, (int)((nc * 100.0) / (ns - nobs)), nwv);
736 
737  if (potarr[startCell] < POT_HIGH) {
738  return true; // finished up here}
739  } else {
740  return false;
741  }
742 }
743 
744 
746 {
747  return last_path_cost_;
748 }
749 
750 
751 //
752 // Path construction
753 // Find gradient at array points, interpolate path
754 // Use step size of pathStep, usually 0.5 pixel
755 //
756 // Some sanity checks:
757 // 1. Stuck at same index position
758 // 2. Doesn't get near goal
759 // 3. Surrounded by high potentials
760 //
761 
762 int
763 NavFn::calcPath(int n, int * st)
764 {
765  // test write
766  // savemap("test");
767 
768  // check path arrays
769  if (npathbuf < n) {
770  if (pathx) {delete[] pathx;}
771  if (pathy) {delete[] pathy;}
772  pathx = new float[n];
773  pathy = new float[n];
774  npathbuf = n;
775  }
776 
777  // set up start position at cell
778  // st is always upper left corner for 4-point bilinear interpolation
779  if (st == NULL) {st = start;}
780  int stc = st[1] * nx + st[0];
781 
782  // set up offset
783  float dx = 0;
784  float dy = 0;
785  npath = 0;
786 
787  // go for <n> cycles at most
788  for (int i = 0; i < n; i++) {
789  // check if near goal
790  int nearest_point = std::max(
791  0,
792  std::min(
793  nx * ny - 1, stc + static_cast<int>(round(dx)) +
794  static_cast<int>(nx * round(dy))));
795  if (potarr[nearest_point] < COST_NEUTRAL) {
796  pathx[npath] = static_cast<float>(goal[0]);
797  pathy[npath] = static_cast<float>(goal[1]);
798  return ++npath; // done!
799  }
800 
801  if (stc < nx || stc > ns - nx) { // would be out of bounds
802  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "[PathCalc] Out of bounds");
803  return 0;
804  }
805 
806  // add to path
807  pathx[npath] = stc % nx + dx;
808  pathy[npath] = stc / nx + dy;
809  npath++;
810 
811  bool oscillation_detected = false;
812  if (npath > 2 &&
813  pathx[npath - 1] == pathx[npath - 3] &&
814  pathy[npath - 1] == pathy[npath - 3])
815  {
816  RCLCPP_DEBUG(
817  rclcpp::get_logger("rclcpp"),
818  "[PathCalc] oscillation detected, attempting fix.");
819  oscillation_detected = true;
820  }
821 
822  int stcnx = stc + nx;
823  int stcpx = stc - nx;
824 
825  // check for potentials at eight positions near cell
826  if (potarr[stc] >= POT_HIGH ||
827  potarr[stc + 1] >= POT_HIGH ||
828  potarr[stc - 1] >= POT_HIGH ||
829  potarr[stcnx] >= POT_HIGH ||
830  potarr[stcnx + 1] >= POT_HIGH ||
831  potarr[stcnx - 1] >= POT_HIGH ||
832  potarr[stcpx] >= POT_HIGH ||
833  potarr[stcpx + 1] >= POT_HIGH ||
834  potarr[stcpx - 1] >= POT_HIGH ||
835  oscillation_detected)
836  {
837  RCLCPP_DEBUG(
838  rclcpp::get_logger("rclcpp"),
839  "[Path] Pot fn boundary, following grid (%0.1f/%d)", potarr[stc], npath);
840 
841  // check eight neighbors to find the lowest
842  int minc = stc;
843  int minp = potarr[stc];
844  int sti = stcpx - 1;
845  if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
846  sti++;
847  if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
848  sti++;
849  if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
850  sti = stc - 1;
851  if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
852  sti = stc + 1;
853  if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
854  sti = stcnx - 1;
855  if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
856  sti++;
857  if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
858  sti++;
859  if (potarr[sti] < minp) {minp = potarr[sti]; minc = sti;}
860  stc = minc;
861  dx = 0;
862  dy = 0;
863 
864  RCLCPP_DEBUG(
865  rclcpp::get_logger("rclcpp"), "[Path] Pot: %0.1f pos: %0.1f,%0.1f",
866  potarr[stc], pathx[npath - 1], pathy[npath - 1]);
867 
868  if (potarr[stc] >= POT_HIGH) {
869  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "[PathCalc] No path found, high potential");
870  // savemap("navfn_highpot");
871  return 0;
872  }
873  } else { // have a good gradient here
874  // get grad at four positions near cell
875  gradCell(stc);
876  gradCell(stc + 1);
877  gradCell(stcnx);
878  gradCell(stcnx + 1);
879 
880 
881  // get interpolated gradient
882  float x1 = (1.0 - dx) * gradx[stc] + dx * gradx[stc + 1];
883  float x2 = (1.0 - dx) * gradx[stcnx] + dx * gradx[stcnx + 1];
884  float x = (1.0 - dy) * x1 + dy * x2; // interpolated x
885  float y1 = (1.0 - dx) * grady[stc] + dx * grady[stc + 1];
886  float y2 = (1.0 - dx) * grady[stcnx] + dx * grady[stcnx + 1];
887  float y = (1.0 - dy) * y1 + dy * y2; // interpolated y
888 
889 #if 0
890  // show gradients
891  RCLCPP_DEBUG(
892  rclcpp::get_logger("rclcpp"),
893  "[Path] %0.2f,%0.2f %0.2f,%0.2f %0.2f,%0.2f %0.2f,%0.2f; final x=%.3f, y=%.3f\n",
894  gradx[stc], grady[stc], gradx[stc + 1], grady[stc + 1],
895  gradx[stcnx], grady[stcnx], gradx[stcnx + 1], grady[stcnx + 1],
896  x, y);
897 #endif
898 
899  // check for zero gradient, failed
900  if (x == 0.0 && y == 0.0) {
901  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "[PathCalc] Zero gradient");
902  return 0;
903  }
904 
905  // move in the right direction
906  float ss = pathStep / hypot(x, y);
907  dx += x * ss;
908  dy += y * ss;
909 
910  // check for overflow
911  if (dx > 1.0) {stc++; dx -= 1.0;}
912  if (dx < -1.0) {stc--; dx += 1.0;}
913  if (dy > 1.0) {stc += nx; dy -= 1.0;}
914  if (dy < -1.0) {stc -= nx; dy += 1.0;}
915  }
916 
917  // ROS_INFO("[Path] Pot: %0.1f grad: %0.1f,%0.1f pos: %0.1f,%0.1f\n",
918  // potarr[stc], x, y, pathx[npath-1], pathy[npath-1]);
919  }
920 
921  // return npath; // out of cycles, return failure
922  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "[PathCalc] No path found, path too long");
923  // savemap("navfn_pathlong");
924  return 0; // out of cycles, return failure
925 }
926 
927 
928 //
929 // gradient calculations
930 //
931 
932 // calculate gradient at a cell
933 // positive value are to the right and down
934 float
936 {
937  if (gradx[n] + grady[n] > 0.0) { // check this cell
938  return 1.0;
939  }
940 
941  if (n < nx || n > ns - nx) { // would be out of bounds
942  return 0.0;
943  }
944 
945  float cv = potarr[n];
946  float dx = 0.0;
947  float dy = 0.0;
948 
949  // check for in an obstacle
950  if (cv >= POT_HIGH) {
951  if (potarr[n - 1] < POT_HIGH) {
952  dx = -COST_OBS;
953  } else if (potarr[n + 1] < POT_HIGH) {
954  dx = COST_OBS;
955  }
956  if (potarr[n - nx] < POT_HIGH) {
957  dy = -COST_OBS;
958  } else if (potarr[n + nx] < POT_HIGH) {
959  dy = COST_OBS;
960  }
961  } else { // not in an obstacle
962  // dx calc, average to sides
963  if (potarr[n - 1] < POT_HIGH) {
964  dx += potarr[n - 1] - cv;
965  }
966  if (potarr[n + 1] < POT_HIGH) {
967  dx += cv - potarr[n + 1];
968  }
969 
970  // dy calc, average to sides
971  if (potarr[n - nx] < POT_HIGH) {
972  dy += potarr[n - nx] - cv;
973  }
974  if (potarr[n + nx] < POT_HIGH) {
975  dy += cv - potarr[n + nx];
976  }
977  }
978 
979  // normalize
980  float norm = hypot(dx, dy);
981  if (norm > 0) {
982  norm = 1.0 / norm;
983  gradx[n] = norm * dx;
984  grady[n] = norm * dy;
985  }
986  return norm;
987 }
988 
989 
990 //
991 // display function setup
992 // <n> is the number of cycles to wait before displaying,
993 // use 0 to turn it off
994 
995 // void
996 // NavFn::display(void fn(NavFn * nav), int n)
997 // {
998 // displayFn = fn;
999 // displayInt = n;
1000 // }
1001 
1002 
1003 //
1004 // debug writes
1005 // saves costmap and start/goal
1006 //
1007 
1008 // void
1009 // NavFn::savemap(const char * fname)
1010 // {
1011 // char fn[4096];
1012 
1013 // RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "[NavFn] Saving costmap and start/goal points");
1014 // // write start and goal points
1015 // snprintf(fn, sizeof(fn), "%s.txt", fname);
1016 // FILE * fp = fopen(fn, "w");
1017 // if (!fp) {
1018 // RCLCPP_WARN(rclcpp::get_logger("rclcpp"), "Can't open file %s", fn);
1019 // return;
1020 // }
1021 // fprintf(fp, "Goal: %d %d\nStart: %d %d\n", goal[0], goal[1], start[0], start[1]);
1022 // fclose(fp);
1023 
1024 // // write cost array
1025 // if (!costarr) {
1026 // return;
1027 // }
1028 // snprintf(fn, sizeof(fn), "%s.pgm", fname);
1029 // fp = fopen(fn, "wb");
1030 // if (!fp) {
1031 // RCLCPP_WARN(rclcpp::get_logger("rclcpp"), "Can't open file %s", fn);
1032 // return;
1033 // }
1034 // fprintf(fp, "P5\n%d\n%d\n%d\n", nx, ny, 0xff);
1035 // fwrite(costarr, 1, nx * ny, fp);
1036 // fclose(fp);
1037 // }
1038 
1039 } // namespace nav2_navfn_planner
int getPathLen()
Accessor for the length of a path.
Definition: navfn.cpp:325
float * getPathX()
Accessor for the x-coordinates of a path.
Definition: navfn.cpp:323
bool calcNavFnAstar(std::function< bool()> cancelChecker)
Calculates a plan using the A* heuristic, returns true if one is found.
Definition: navfn.cpp:311
float gradCell(int n)
Calculate gradient at a cell.
Definition: navfn.cpp:935
void updateCell(int n)
Updates the cell at index n.
Definition: navfn.cpp:422
bool propNavFnDijkstra(int cycles, std::function< bool()> cancelChecker, bool atStart=false)
Run propagation for <cycles> iterations, or until start is reached using breadth-first Dijkstra metho...
Definition: navfn.cpp:575
int calcPath(int n, int *st=NULL)
Calculates the path for at mose <n> cycles.
Definition: navfn.cpp:763
float getLastPathCost()
Gets the cost of the path found the last time a navigation function was computed.
Definition: navfn.cpp:745
bool calcNavFnDijkstra(std::function< bool()> cancelChecker, bool atStart=false)
Calculates the full navigation function using Dijkstra.
Definition: navfn.cpp:297
bool propNavFnAstar(int cycles, std::function< bool()> cancelChecker)
Run propagation for <cycles> iterations, or until start is reached using the best-first A* method wit...
Definition: navfn.cpp:660
void updateCellAstar(int n)
Updates the cell at index n using the A* heuristic.
Definition: navfn.cpp:496
void initCost(int k, float v)
Initialize cell k with cost v for propagation.
Definition: navfn.cpp:401
void setNavArr(int nx, int ny)
Sets or resets the size of the map.
Definition: navfn.cpp:207
NavFn(int nx, int ny)
Constructs the planner.
Definition: navfn.cpp:112
void setCostmap(const COSTTYPE *cmap, bool isROS=true, bool allow_unknown=true)
Set up the cost array for the planner, usually from ROS.
Definition: navfn.cpp:247
void setupNavFn(bool keepit=false)
Set up navigation potential arrays for new propagation.
Definition: navfn.cpp:342
void setGoal(int *goal)
Sets the goal position for the planner. Note: the navigation cost field computed gives the cost to ge...
Definition: navfn.cpp:185
float * getPathY()
Accessor for the y-coordinates of a path.
Definition: navfn.cpp:324
void setStart(int *start)
Sets the start position for the planner. Note: the navigation cost field computed gives the cost to g...
Definition: navfn.cpp:193