00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046 #include <navfn/navfn.h>
00047 #include <ros/console.h>
00048
00049 namespace navfn {
00050
00051
00052
00053
00054
00055
00056
00057 int
00058 create_nav_plan_astar(COSTTYPE *costmap, int nx, int ny,
00059 int* goal, int* start,
00060 float *plan, int nplan)
00061 {
00062 static NavFn *nav = NULL;
00063
00064 if (nav == NULL)
00065 nav = new NavFn(nx,ny);
00066
00067 if (nav->nx != nx || nav->ny != ny)
00068 {
00069 delete nav;
00070 nav = new NavFn(nx,ny);
00071 }
00072
00073 nav->setGoal(goal);
00074 nav->setStart(start);
00075
00076 nav->costarr = costmap;
00077 nav->setupNavFn(true);
00078
00079
00080 nav->priInc = 2*COST_NEUTRAL;
00081 nav->propNavFnAstar(std::max(nx*ny/20,nx+ny));
00082
00083
00084 int len = nav->calcPath(nplan);
00085
00086 if (len > 0)
00087 ROS_DEBUG("[NavFn] Path found, %d steps\n", len);
00088 else
00089 ROS_DEBUG("[NavFn] No path found\n");
00090
00091 if (len > 0)
00092 {
00093 for (int i=0; i<len; i++)
00094 {
00095 plan[i*2] = nav->pathx[i];
00096 plan[i*2+1] = nav->pathy[i];
00097 }
00098 }
00099
00100 return len;
00101 }
00102
00103
00104
00105
00106
00107
00108
00109
00110 NavFn::NavFn(int xs, int ys)
00111 {
00112
00113 obsarr = costarr = NULL;
00114 potarr = NULL;
00115 pending = NULL;
00116 gradx = grady = NULL;
00117 setNavArr(xs,ys);
00118
00119
00120 pb1 = new int[PRIORITYBUFSIZE];
00121 pb2 = new int[PRIORITYBUFSIZE];
00122 pb3 = new int[PRIORITYBUFSIZE];
00123
00124
00125
00126 priInc = 2*COST_NEUTRAL;
00127
00128
00129 goal[0] = goal[1] = 0;
00130 start[0] = start[1] = 0;
00131
00132
00133 displayFn = NULL;
00134 displayInt = 0;
00135
00136
00137 npathbuf = npath = 0;
00138 pathx = pathy = NULL;
00139 pathStep = 0.5;
00140 }
00141
00142
00143 NavFn::~NavFn()
00144 {
00145 if(obsarr)
00146 delete[] obsarr;
00147 if(costarr)
00148 delete[] costarr;
00149 if(potarr)
00150 delete[] potarr;
00151 if(pending)
00152 delete[] pending;
00153 if(gradx)
00154 delete[] gradx;
00155 if(grady)
00156 delete[] grady;
00157 if(pathx)
00158 delete[] pathx;
00159 if(pathy)
00160 delete[] pathy;
00161 if(pb1)
00162 delete[] pb1;
00163 if(pb2)
00164 delete[] pb2;
00165 if(pb3)
00166 delete[] pb3;
00167 }
00168
00169
00170
00171
00172
00173
00174 void
00175 NavFn::setGoal(int *g)
00176 {
00177 goal[0] = g[0];
00178 goal[1] = g[1];
00179 ROS_DEBUG("[NavFn] Setting goal to %d,%d\n", goal[0], goal[1]);
00180 }
00181
00182 void
00183 NavFn::setStart(int *g)
00184 {
00185 start[0] = g[0];
00186 start[1] = g[1];
00187 ROS_DEBUG("[NavFn] Setting start to %d,%d\n", start[0], start[1]);
00188 }
00189
00190
00191
00192
00193
00194 void
00195 NavFn::setNavArr(int xs, int ys)
00196 {
00197 ROS_DEBUG("[NavFn] Array is %d x %d\n", xs, ys);
00198
00199 nx = xs;
00200 ny = ys;
00201 ns = nx*ny;
00202
00203 if(obsarr)
00204 delete[] obsarr;
00205 if(costarr)
00206 delete[] costarr;
00207 if(potarr)
00208 delete[] potarr;
00209 if(pending)
00210 delete[] pending;
00211
00212 if(gradx)
00213 delete[] gradx;
00214 if(grady)
00215 delete[] grady;
00216
00217 obsarr = new COSTTYPE[ns];
00218 memset(obsarr, 0, ns*sizeof(COSTTYPE));
00219 costarr = new COSTTYPE[ns];
00220 memset(costarr, 0, ns*sizeof(COSTTYPE));
00221 potarr = new float[ns];
00222 pending = new bool[ns];
00223 memset(pending, 0, ns*sizeof(bool));
00224 gradx = new float[ns];
00225 grady = new float[ns];
00226 }
00227
00228
00229
00230
00231
00232
00233 void
00234 NavFn::setCostmap(const COSTTYPE *cmap, bool isROS, bool allow_unknown)
00235 {
00236 COSTTYPE *cm = costarr;
00237 if (isROS)
00238 {
00239 for (int i=0; i<ny; i++)
00240 {
00241 int k=i*nx;
00242 for (int j=0; j<nx; j++, k++, cmap++, cm++)
00243 {
00244
00245
00246
00247
00248 *cm = COST_OBS;
00249 int v = *cmap;
00250 if (v < COST_OBS_ROS)
00251 {
00252 v = COST_NEUTRAL+COST_FACTOR*v;
00253 if (v >= COST_OBS)
00254 v = COST_OBS-1;
00255 *cm = v;
00256 }
00257 else if(v == COST_UNKNOWN_ROS && allow_unknown)
00258 {
00259 v = COST_OBS-1;
00260 *cm = v;
00261 }
00262 }
00263 }
00264 }
00265
00266 else
00267 {
00268 for (int i=0; i<ny; i++)
00269 {
00270 int k=i*nx;
00271 for (int j=0; j<nx; j++, k++, cmap++, cm++)
00272 {
00273 *cm = COST_OBS;
00274 if (i<7 || i > ny-8 || j<7 || j > nx-8)
00275 continue;
00276 int v = *cmap;
00277 if (v < COST_OBS_ROS)
00278 {
00279 v = COST_NEUTRAL+COST_FACTOR*v;
00280 if (v >= COST_OBS)
00281 v = COST_OBS-1;
00282 *cm = v;
00283 }
00284 else if(v == COST_UNKNOWN_ROS)
00285 {
00286 v = COST_OBS-1;
00287 *cm = v;
00288 }
00289 }
00290 }
00291
00292 }
00293 }
00294
00295 bool
00296 NavFn::calcNavFnDijkstra(bool atStart)
00297 {
00298 #if 0
00299 static char costmap_filename[1000];
00300 static int file_number = 0;
00301 snprintf( costmap_filename, 1000, "navfn-dijkstra-costmap-%04d", file_number++ );
00302 savemap( costmap_filename );
00303 #endif
00304 setupNavFn(true);
00305
00306
00307 propNavFnDijkstra(std::max(nx*ny/20,nx+ny),atStart);
00308
00309
00310 int len = calcPath(nx*ny/2);
00311
00312 if (len > 0)
00313 {
00314 ROS_DEBUG("[NavFn] Path found, %d steps\n", len);
00315 return true;
00316 }
00317 else
00318 {
00319 ROS_DEBUG("[NavFn] No path found\n");
00320 return false;
00321 }
00322
00323 }
00324
00325
00326
00327
00328
00329
00330 bool
00331 NavFn::calcNavFnAstar()
00332 {
00333 setupNavFn(true);
00334
00335
00336 propNavFnAstar(std::max(nx*ny/20,nx+ny));
00337
00338
00339 int len = calcPath(nx*4);
00340
00341 if (len > 0)
00342 {
00343 ROS_DEBUG("[NavFn] Path found, %d steps\n", len);
00344 return true;
00345 }
00346 else
00347 {
00348 ROS_DEBUG("[NavFn] No path found\n");
00349 return false;
00350 }
00351 }
00352
00353
00354
00355
00356
00357
00358 float *NavFn::getPathX() { return pathx; }
00359 float *NavFn::getPathY() { return pathy; }
00360 int NavFn::getPathLen() { return npath; }
00361
00362
00363
00364
00365
00366
00367 void
00368 NavFn::setObs()
00369 {
00370 #if 0
00371
00372 ROS_INFO("[NavFn] Setting simple obstacle\n");
00373 int xx = nx/3;
00374 for (int i=ny/3; i<ny; i++)
00375 costarr[i*nx + xx] = COST_OBS;
00376 xx = 2*nx/3;
00377 for (int i=ny/3; i<ny; i++)
00378 costarr[i*nx + xx] = COST_OBS;
00379
00380 xx = nx/4;
00381 for (int i=20; i<ny-ny/3; i++)
00382 costarr[i*nx + xx] = COST_OBS;
00383 xx = nx/2;
00384 for (int i=20; i<ny-ny/3; i++)
00385 costarr[i*nx + xx] = COST_OBS;
00386 xx = 3*nx/4;
00387 for (int i=20; i<ny-ny/3; i++)
00388 costarr[i*nx + xx] = COST_OBS;
00389 #endif
00390 }
00391
00392
00393
00394 #define push_cur(n) { if (n>=0 && n<ns && !pending[n] && \
00395 costarr[n]<COST_OBS && curPe<PRIORITYBUFSIZE) \
00396 { curP[curPe++]=n; pending[n]=true; }}
00397 #define push_next(n) { if (n>=0 && n<ns && !pending[n] && \
00398 costarr[n]<COST_OBS && nextPe<PRIORITYBUFSIZE) \
00399 { nextP[nextPe++]=n; pending[n]=true; }}
00400 #define push_over(n) { if (n>=0 && n<ns && !pending[n] && \
00401 costarr[n]<COST_OBS && overPe<PRIORITYBUFSIZE) \
00402 { overP[overPe++]=n; pending[n]=true; }}
00403
00404
00405
00406
00407 void
00408 NavFn::setupNavFn(bool keepit)
00409 {
00410
00411 for (int i=0; i<ns; i++)
00412 {
00413 potarr[i] = POT_HIGH;
00414 if (!keepit) costarr[i] = COST_NEUTRAL;
00415 gradx[i] = grady[i] = 0.0;
00416 }
00417
00418
00419 COSTTYPE *pc;
00420 pc = costarr;
00421 for (int i=0; i<nx; i++)
00422 *pc++ = COST_OBS;
00423 pc = costarr + (ny-1)*nx;
00424 for (int i=0; i<nx; i++)
00425 *pc++ = COST_OBS;
00426 pc = costarr;
00427 for (int i=0; i<ny; i++, pc+=nx)
00428 *pc = COST_OBS;
00429 pc = costarr + nx - 1;
00430 for (int i=0; i<ny; i++, pc+=nx)
00431 *pc = COST_OBS;
00432
00433
00434 curT = COST_OBS;
00435 curP = pb1;
00436 curPe = 0;
00437 nextP = pb2;
00438 nextPe = 0;
00439 overP = pb3;
00440 overPe = 0;
00441 memset(pending, 0, ns*sizeof(bool));
00442
00443
00444 int k = goal[0] + goal[1]*nx;
00445 initCost(k,0);
00446
00447
00448 pc = costarr;
00449 int ntot = 0;
00450 for (int i=0; i<ns; i++, pc++)
00451 {
00452 if (*pc >= COST_OBS)
00453 ntot++;
00454 }
00455 nobs = ntot;
00456 }
00457
00458
00459
00460
00461 void
00462 NavFn::initCost(int k, float v)
00463 {
00464 potarr[k] = v;
00465 push_cur(k+1);
00466 push_cur(k-1);
00467 push_cur(k-nx);
00468 push_cur(k+nx);
00469 }
00470
00471
00472
00473
00474
00475
00476
00477
00478
00479
00480 #define INVSQRT2 0.707106781
00481
00482 inline void
00483 NavFn::updateCell(int n)
00484 {
00485
00486 float u,d,l,r;
00487 l = potarr[n-1];
00488 r = potarr[n+1];
00489 u = potarr[n-nx];
00490 d = potarr[n+nx];
00491
00492
00493
00494
00495
00496 float ta, tc;
00497 if (l<r) tc=l; else tc=r;
00498 if (u<d) ta=u; else ta=d;
00499
00500
00501 if (costarr[n] < COST_OBS)
00502 {
00503 float hf = (float)costarr[n];
00504 float dc = tc-ta;
00505 if (dc < 0)
00506 {
00507 dc = -dc;
00508 ta = tc;
00509 }
00510
00511
00512 float pot;
00513 if (dc >= hf)
00514 pot = ta+hf;
00515 else
00516 {
00517
00518
00519
00520 float d = dc/hf;
00521 float v = -0.2301*d*d + 0.5307*d + 0.7040;
00522 pot = ta + hf*v;
00523 }
00524
00525
00526
00527
00528 if (pot < potarr[n])
00529 {
00530 float le = INVSQRT2*(float)costarr[n-1];
00531 float re = INVSQRT2*(float)costarr[n+1];
00532 float ue = INVSQRT2*(float)costarr[n-nx];
00533 float de = INVSQRT2*(float)costarr[n+nx];
00534 potarr[n] = pot;
00535 if (pot < curT)
00536 {
00537 if (l > pot+le) push_next(n-1);
00538 if (r > pot+re) push_next(n+1);
00539 if (u > pot+ue) push_next(n-nx);
00540 if (d > pot+de) push_next(n+nx);
00541 }
00542 else
00543 {
00544 if (l > pot+le) push_over(n-1);
00545 if (r > pot+re) push_over(n+1);
00546 if (u > pot+ue) push_over(n-nx);
00547 if (d > pot+de) push_over(n+nx);
00548 }
00549 }
00550
00551 }
00552
00553 }
00554
00555
00556
00557
00558
00559
00560
00561
00562
00563
00564
00565 #define INVSQRT2 0.707106781
00566
00567 inline void
00568 NavFn::updateCellAstar(int n)
00569 {
00570
00571 float u,d,l,r;
00572 l = potarr[n-1];
00573 r = potarr[n+1];
00574 u = potarr[n-nx];
00575 d = potarr[n+nx];
00576
00577
00578
00579
00580
00581 float ta, tc;
00582 if (l<r) tc=l; else tc=r;
00583 if (u<d) ta=u; else ta=d;
00584
00585
00586 if (costarr[n] < COST_OBS)
00587 {
00588 float hf = (float)costarr[n];
00589 float dc = tc-ta;
00590 if (dc < 0)
00591 {
00592 dc = -dc;
00593 ta = tc;
00594 }
00595
00596
00597 float pot;
00598 if (dc >= hf)
00599 pot = ta+hf;
00600 else
00601 {
00602
00603
00604
00605 float d = dc/hf;
00606 float v = -0.2301*d*d + 0.5307*d + 0.7040;
00607 pot = ta + hf*v;
00608 }
00609
00610
00611
00612
00613 if (pot < potarr[n])
00614 {
00615 float le = INVSQRT2*(float)costarr[n-1];
00616 float re = INVSQRT2*(float)costarr[n+1];
00617 float ue = INVSQRT2*(float)costarr[n-nx];
00618 float de = INVSQRT2*(float)costarr[n+nx];
00619
00620
00621 int x = n%nx;
00622 int y = n/nx;
00623 float dist = (x-start[0])*(x-start[0]) + (y-start[1])*(y-start[1]);
00624 dist = sqrtf(dist)*(float)COST_NEUTRAL;
00625
00626 potarr[n] = pot;
00627 pot += dist;
00628 if (pot < curT)
00629 {
00630 if (l > pot+le) push_next(n-1);
00631 if (r > pot+re) push_next(n+1);
00632 if (u > pot+ue) push_next(n-nx);
00633 if (d > pot+de) push_next(n+nx);
00634 }
00635 else
00636 {
00637 if (l > pot+le) push_over(n-1);
00638 if (r > pot+re) push_over(n+1);
00639 if (u > pot+ue) push_over(n-nx);
00640 if (d > pot+de) push_over(n+nx);
00641 }
00642 }
00643
00644 }
00645
00646 }
00647
00648
00649
00650
00651
00652
00653
00654
00655
00656
00657
00658 bool
00659 NavFn::propNavFnDijkstra(int cycles, bool atStart)
00660 {
00661 int nwv = 0;
00662 int nc = 0;
00663 int cycle = 0;
00664
00665
00666 int startCell = start[1]*nx + start[0];
00667
00668 for (; cycle < cycles; cycle++)
00669 {
00670
00671 if (curPe == 0 && nextPe == 0)
00672 break;
00673
00674
00675 nc += curPe;
00676 if (curPe > nwv)
00677 nwv = curPe;
00678
00679
00680 int *pb = curP;
00681 int i = curPe;
00682 while (i-- > 0)
00683 pending[*(pb++)] = false;
00684
00685
00686 pb = curP;
00687 i = curPe;
00688 while (i-- > 0)
00689 updateCell(*pb++);
00690
00691 if (displayInt > 0 && (cycle % displayInt) == 0)
00692 displayFn(this);
00693
00694
00695 curPe = nextPe;
00696 nextPe = 0;
00697 pb = curP;
00698 curP = nextP;
00699 nextP = pb;
00700
00701
00702 if (curPe == 0)
00703 {
00704 curT += priInc;
00705 curPe = overPe;
00706 overPe = 0;
00707 pb = curP;
00708 curP = overP;
00709 overP = pb;
00710 }
00711
00712
00713 if (atStart)
00714 if (potarr[startCell] < POT_HIGH)
00715 break;
00716 }
00717
00718 ROS_DEBUG("[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n",
00719 cycle,nc,(int)((nc*100.0)/(ns-nobs)),nwv);
00720
00721 if (cycle < cycles) return true;
00722 else return false;
00723 }
00724
00725
00726
00727
00728
00729
00730
00731
00732
00733
00734
00735 bool
00736 NavFn::propNavFnAstar(int cycles)
00737 {
00738 int nwv = 0;
00739 int nc = 0;
00740 int cycle = 0;
00741
00742
00743 float dist = (goal[0]-start[0])*(goal[0]-start[0]) + (goal[1]-start[1])*(goal[1]-start[1]);
00744 dist = sqrtf(dist)*(float)COST_NEUTRAL;
00745 curT = dist + curT;
00746
00747
00748 int startCell = start[1]*nx + start[0];
00749
00750
00751 for (; cycle < cycles; cycle++)
00752 {
00753
00754 if (curPe == 0 && nextPe == 0)
00755 break;
00756
00757
00758 nc += curPe;
00759 if (curPe > nwv)
00760 nwv = curPe;
00761
00762
00763 int *pb = curP;
00764 int i = curPe;
00765 while (i-- > 0)
00766 pending[*(pb++)] = false;
00767
00768
00769 pb = curP;
00770 i = curPe;
00771 while (i-- > 0)
00772 updateCellAstar(*pb++);
00773
00774 if (displayInt > 0 && (cycle % displayInt) == 0)
00775 displayFn(this);
00776
00777
00778 curPe = nextPe;
00779 nextPe = 0;
00780 pb = curP;
00781 curP = nextP;
00782 nextP = pb;
00783
00784
00785 if (curPe == 0)
00786 {
00787 curT += priInc;
00788 curPe = overPe;
00789 overPe = 0;
00790 pb = curP;
00791 curP = overP;
00792 overP = pb;
00793 }
00794
00795
00796 if (potarr[startCell] < POT_HIGH)
00797 break;
00798
00799 }
00800
00801 last_path_cost_ = potarr[startCell];
00802
00803 ROS_DEBUG("[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n",
00804 cycle,nc,(int)((nc*100.0)/(ns-nobs)),nwv);
00805
00806
00807 if (potarr[startCell] < POT_HIGH) return true;
00808 else return false;
00809 }
00810
00811
00812 float NavFn::getLastPathCost()
00813 {
00814 return last_path_cost_;
00815 }
00816
00817
00818
00819
00820
00821
00822
00823
00824
00825
00826
00827
00828
00829 int
00830 NavFn::calcPath(int n, int *st)
00831 {
00832
00833
00834
00835
00836 if (npathbuf < n)
00837 {
00838 if (pathx) delete [] pathx;
00839 if (pathy) delete [] pathy;
00840 pathx = new float[n];
00841 pathy = new float[n];
00842 npathbuf = n;
00843 }
00844
00845
00846
00847 if (st == NULL) st = start;
00848 int stc = st[1]*nx + st[0];
00849
00850
00851 float dx=0;
00852 float dy=0;
00853 npath = 0;
00854
00855
00856 for (int i=0; i<n; i++)
00857 {
00858
00859 int nearest_point=std::max(0,std::min(nx*ny-1,stc+(int)round(dx)+(int)(nx*round(dy))));
00860 if (potarr[nearest_point] < COST_NEUTRAL)
00861 {
00862 pathx[npath] = (float)goal[0];
00863 pathy[npath] = (float)goal[1];
00864 return ++npath;
00865 }
00866
00867 if (stc < nx || stc > ns-nx)
00868 {
00869 ROS_DEBUG("[PathCalc] Out of bounds");
00870 return 0;
00871 }
00872
00873
00874 pathx[npath] = stc%nx + dx;
00875 pathy[npath] = stc/nx + dy;
00876 npath++;
00877
00878 bool oscillation_detected = false;
00879 if( npath > 2 &&
00880 pathx[npath-1] == pathx[npath-3] &&
00881 pathy[npath-1] == pathy[npath-3] )
00882 {
00883 ROS_DEBUG("[PathCalc] oscillation detected, attempting fix.");
00884 oscillation_detected = true;
00885 }
00886
00887 int stcnx = stc+nx;
00888 int stcpx = stc-nx;
00889
00890
00891 if (potarr[stc] >= POT_HIGH ||
00892 potarr[stc+1] >= POT_HIGH ||
00893 potarr[stc-1] >= POT_HIGH ||
00894 potarr[stcnx] >= POT_HIGH ||
00895 potarr[stcnx+1] >= POT_HIGH ||
00896 potarr[stcnx-1] >= POT_HIGH ||
00897 potarr[stcpx] >= POT_HIGH ||
00898 potarr[stcpx+1] >= POT_HIGH ||
00899 potarr[stcpx-1] >= POT_HIGH ||
00900 oscillation_detected)
00901 {
00902 ROS_DEBUG("[Path] Pot fn boundary, following grid (%0.1f/%d)", potarr[stc], npath);
00903
00904 int minc = stc;
00905 int minp = potarr[stc];
00906 int st = stcpx - 1;
00907 if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00908 st++;
00909 if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00910 st++;
00911 if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00912 st = stc-1;
00913 if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00914 st = stc+1;
00915 if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00916 st = stcnx-1;
00917 if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00918 st++;
00919 if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00920 st++;
00921 if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00922 stc = minc;
00923 dx = 0;
00924 dy = 0;
00925
00926 ROS_DEBUG("[Path] Pot: %0.1f pos: %0.1f,%0.1f",
00927 potarr[stc], pathx[npath-1], pathy[npath-1]);
00928
00929 if (potarr[stc] >= POT_HIGH)
00930 {
00931 ROS_DEBUG("[PathCalc] No path found, high potential");
00932
00933 return 0;
00934 }
00935 }
00936
00937
00938 else
00939 {
00940
00941
00942 gradCell(stc);
00943 gradCell(stc+1);
00944 gradCell(stcnx);
00945 gradCell(stcnx+1);
00946
00947
00948
00949 float x1 = (1.0-dx)*gradx[stc] + dx*gradx[stc+1];
00950 float x2 = (1.0-dx)*gradx[stcnx] + dx*gradx[stcnx+1];
00951 float x = (1.0-dy)*x1 + dy*x2;
00952 float y1 = (1.0-dx)*grady[stc] + dx*grady[stc+1];
00953 float y2 = (1.0-dx)*grady[stcnx] + dx*grady[stcnx+1];
00954 float y = (1.0-dy)*y1 + dy*y2;
00955
00956
00957 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",
00958 gradx[stc], grady[stc], gradx[stc+1], grady[stc+1],
00959 gradx[stcnx], grady[stcnx], gradx[stcnx+1], grady[stcnx+1],
00960 x, y);
00961
00962
00963 if (x == 0.0 && y == 0.0)
00964 {
00965 ROS_DEBUG("[PathCalc] Zero gradient");
00966 return 0;
00967 }
00968
00969
00970 float ss = pathStep/sqrt(x*x+y*y);
00971 dx += x*ss;
00972 dy += y*ss;
00973
00974
00975 if (dx > 1.0) { stc++; dx -= 1.0; }
00976 if (dx < -1.0) { stc--; dx += 1.0; }
00977 if (dy > 1.0) { stc+=nx; dy -= 1.0; }
00978 if (dy < -1.0) { stc-=nx; dy += 1.0; }
00979
00980 }
00981
00982
00983
00984 }
00985
00986
00987 ROS_DEBUG("[PathCalc] No path found, path too long");
00988
00989 return 0;
00990 }
00991
00992
00993
00994
00995
00996
00997
00998
00999 float
01000 NavFn::gradCell(int n)
01001 {
01002 if (gradx[n]+grady[n] > 0.0)
01003 return 1.0;
01004
01005 if (n < nx || n > ns-nx)
01006 return 0.0;
01007
01008 float cv = potarr[n];
01009 float dx = 0.0;
01010 float dy = 0.0;
01011
01012
01013 if (cv >= POT_HIGH)
01014 {
01015 if (potarr[n-1] < POT_HIGH)
01016 dx = -COST_OBS;
01017 else if (potarr[n+1] < POT_HIGH)
01018 dx = COST_OBS;
01019
01020 if (potarr[n-nx] < POT_HIGH)
01021 dy = -COST_OBS;
01022 else if (potarr[nx+1] < POT_HIGH)
01023 dy = COST_OBS;
01024 }
01025
01026 else
01027 {
01028
01029 if (potarr[n-1] < POT_HIGH)
01030 dx += potarr[n-1]- cv;
01031 if (potarr[n+1] < POT_HIGH)
01032 dx += cv - potarr[n+1];
01033
01034
01035 if (potarr[n-nx] < POT_HIGH)
01036 dy += potarr[n-nx]- cv;
01037 if (potarr[n+nx] < POT_HIGH)
01038 dy += cv - potarr[n+nx];
01039 }
01040
01041
01042 float norm = sqrtf(dx*dx+dy*dy);
01043 if (norm > 0)
01044 {
01045 norm = 1.0/norm;
01046 gradx[n] = norm*dx;
01047 grady[n] = norm*dy;
01048 }
01049 return norm;
01050 }
01051
01052
01053
01054
01055
01056
01057
01058 void
01059 NavFn::display(void fn(NavFn *nav), int n)
01060 {
01061 displayFn = fn;
01062 displayInt = n;
01063 }
01064
01065
01066
01067
01068
01069
01070
01071 void
01072 NavFn::savemap(const char *fname)
01073 {
01074 char fn[4096];
01075
01076 ROS_DEBUG("[NavFn] Saving costmap and start/goal points");
01077
01078 sprintf(fn,"%s.txt",fname);
01079 FILE *fp = fopen(fn,"w");
01080 if (!fp)
01081 {
01082 ROS_WARN("Can't open file %s", fn);
01083 return;
01084 }
01085 fprintf(fp,"Goal: %d %d\nStart: %d %d\n",goal[0],goal[1],start[0],start[1]);
01086 fclose(fp);
01087
01088
01089 if (!costarr) return;
01090 sprintf(fn,"%s.pgm",fname);
01091 fp = fopen(fn,"wb");
01092 if (!fp)
01093 {
01094 ROS_WARN("Can't open file %s", fn);
01095 return;
01096 }
01097 fprintf(fp,"P5\n%d\n%d\n%d\n", nx, ny, 0xff);
01098 fwrite(costarr,1,nx*ny,fp);
01099 fclose(fp);
01100 }
01101 };