60 float *plan,
int nplan)
62 static NavFn *nav = NULL;
65 nav =
new NavFn(nx,ny);
67 if (nav->
nx != nx || nav->
ny != ny)
70 nav =
new NavFn(nx,ny);
87 ROS_DEBUG(
"[NavFn] Path found, %d steps\n", len);
93 for (
int i=0; i<len; i++)
95 plan[i*2] = nav->
pathx[i];
96 plan[i*2+1] = nav->
pathy[i];
195 ROS_DEBUG(
"[NavFn] Array is %d x %d\n", xs, ys);
233 for (
int i=0; i<
ny; i++)
236 for (
int j=0; j<
nx; j++, k++, cmap++, cm++)
262 for (
int i=0; i<
ny; i++)
265 for (
int j=0; j<
nx; j++, k++, cmap++, cm++)
268 if (i<7 || i > ny-8 || j<7 || j > nx-8)
302 ROS_DEBUG(
"[NavFn] Path found, %d steps\n", len);
331 ROS_DEBUG(
"[NavFn] Path found, %d steps\n", len);
351 #define push_cur(n) { if (n>=0 && n<ns && !pending[n] && \ 352 costarr[n]<COST_OBS && curPe<PRIORITYBUFSIZE) \ 353 { curP[curPe++]=n; pending[n]=true; }} 354 #define push_next(n) { if (n>=0 && n<ns && !pending[n] && \ 355 costarr[n]<COST_OBS && nextPe<PRIORITYBUFSIZE) \ 356 { nextP[nextPe++]=n; pending[n]=true; }} 357 #define push_over(n) { if (n>=0 && n<ns && !pending[n] && \ 358 costarr[n]<COST_OBS && overPe<PRIORITYBUFSIZE) \ 359 { overP[overPe++]=n; pending[n]=true; }} 368 for (
int i=0; i<
ns; i++)
378 for (
int i=0; i<
nx; i++)
381 for (
int i=0; i<
nx; i++)
384 for (
int i=0; i<
ny; i++, pc+=
nx)
387 for (
int i=0; i<
ny; i++, pc+=
nx)
398 memset(
pending, 0, ns*
sizeof(
bool));
407 for (
int i=0; i<
ns; i++, pc++)
437 #define INVSQRT2 0.707106781 454 if (l<r) tc=l;
else tc=r;
455 if (u<d) ta=u;
else ta=d;
478 float v = -0.2301*d*d + 0.5307*d + 0.7040;
522 #define INVSQRT2 0.707106781 539 if (l<r) tc=l;
else tc=r;
540 if (u<d) ta=u;
else ta=d;
563 float v = -0.2301*d*d + 0.5307*d + 0.7040;
624 for (; cycle < cycles; cycle++)
674 ROS_DEBUG(
"[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n",
675 cycle,nc,(
int)((nc*100.0)/(
ns-
nobs)),nwv);
677 if (cycle < cycles)
return true;
706 for (; cycle < cycles; cycle++)
758 ROS_DEBUG(
"[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n",
759 cycle,nc,(
int)((nc*100.0)/(
ns-
nobs)),nwv);
795 pathx =
new float[n];
796 pathy =
new float[n];
802 if (st == NULL) st =
start;
803 int stc = st[1]*
nx + st[0];
811 for (
int i=0; i<n; i++)
814 int nearest_point=std::max(0,std::min(
nx*
ny-1,stc+(
int)round(dx)+(
int)(
nx*round(dy))));
822 if (stc < nx || stc >
ns-
nx)
833 bool oscillation_detected =
false;
838 ROS_DEBUG(
"[PathCalc] oscillation detected, attempting fix.");
839 oscillation_detected =
true;
855 oscillation_detected)
881 ROS_DEBUG(
"[Path] Pot: %0.1f pos: %0.1f,%0.1f",
886 ROS_DEBUG(
"[PathCalc] No path found, high potential");
904 float x1 = (1.0-dx)*
gradx[stc] + dx*
gradx[stc+1];
905 float x2 = (1.0-dx)*
gradx[stcnx] + dx*
gradx[stcnx+1];
906 float x = (1.0-dy)*x1 + dy*x2;
907 float y1 = (1.0-dx)*
grady[stc] + dx*
grady[stc+1];
908 float y2 = (1.0-dx)*
grady[stcnx] + dx*
grady[stcnx+1];
909 float y = (1.0-dy)*y1 + dy*y2;
912 ROS_DEBUG(
"[Path] %0.2f,%0.2f %0.2f,%0.2f %0.2f,%0.2f %0.2f,%0.2f; final x=%.3f, y=%.3f\n",
918 if (x == 0.0 && y == 0.0)
930 if (dx > 1.0) { stc++; dx -= 1.0; }
931 if (dx < -1.0) { stc--; dx += 1.0; }
932 if (dy > 1.0) { stc+=
nx; dy -= 1.0; }
933 if (dy < -1.0) { stc-=
nx; dy += 1.0; }
942 ROS_DEBUG(
"[PathCalc] No path found, path too long");
960 if (n < nx || n >
ns-
nx)
991 dy += potarr[n-
nx]- cv;
993 dy += cv - potarr[n+
nx];
997 float norm = hypot(dx, dy);
1031 ROS_DEBUG(
"[NavFn] Saving costmap and start/goal points");
1033 sprintf(fn,
"%s.txt",fname);
1034 FILE *fp = fopen(fn,
"w");
1037 ROS_WARN(
"Can't open file %s", fn);
1045 sprintf(fn,
"%s.pgm",fname);
1046 fp = fopen(fn,
"wb");
1049 ROS_WARN(
"Can't open file %s", fn);
1052 fprintf(fp,
"P5\n%d\n%d\n%d\n",
nx,
ny, 0xff);
void updateCell(int n)
Updates the cell at index n.
void setupNavFn(bool keepit=false)
NavFn(int nx, int ny)
Constructs the planner.
float * getPathY()
Accessor for the y-coordinates of a path.
int create_nav_plan_astar(const COSTTYPE *costmap, int nx, int ny, int *goal, int *start, float *plan, int nplan)
void(* displayFn)(NavFn *nav)
void updateCellAstar(int n)
Updates the cell at index n using the A* heuristic.
void setStart(int *start)
Sets the start position for the planner. Note: the navigation cost field computed gives the cost to g...
void setCostmap(const COSTTYPE *cmap, bool isROS=true, bool allow_unknown=true)
Set up the cost array for the planner, usually from ROS.
bool calcNavFnDijkstra(bool atStart=false)
Caclulates the full navigation function using Dijkstra.
TFSIMD_FORCE_INLINE const tfScalar & y() const
float getLastPathCost()
Gets the cost of the path found the last time a navigation function was computed. ...
void setGoal(int *goal)
Sets the goal position for the planner. Note: the navigation cost field computed gives the cost to ge...
Navigation function class. Holds buffers for costmap, navfn map. Maps are pixel-based. Origin is upper left, x is right, y is down.
TFSIMD_FORCE_INLINE const tfScalar & x() const
int calcPath(int n, int *st=NULL)
Calculates the path for at mose <n> cycles.
void initCost(int k, float v)
Initialize cell k with cost v for propagation.
void savemap(const char *fname)
bool propNavFnDijkstra(int cycles, bool atStart=false)
Run propagation for <cycles> iterations, or until start is reached using breadth-first Dijkstra metho...
void display(void fn(NavFn *nav), int n=100)
int getPathLen()
Accessor for the length of a path.
void setNavArr(int nx, int ny)
Sets or resets the size of the map.
float * getPathX()
Accessor for the x-coordinates of a path.
bool calcNavFnAstar()
Calculates a plan using the A* heuristic, returns true if one is found.
bool propNavFnAstar(int cycles)
Run propagation for <cycles> iterations, or until start is reached using the best-first A* method wit...