navfn.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 //
00035 // Navigation function computation
00036 // Uses Dijkstra's method
00037 // Modified for Euclidean-distance computation
00038 // 
00039 // Path calculation uses no interpolation when pot field is at max in
00040 //   nearby cells
00041 //
00042 // Path calc has sanity check that it succeeded
00043 //
00044 
00045 
00046 #include <navfn/navfn.h>
00047 #include <ros/console.h>
00048 
00049 namespace navfn {
00050 
00051   //
00052   // function to perform nav fn calculation
00053   // keeps track of internal buffers, will be more efficient
00054   //   if the size of the environment does not change
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) // check for compatibility with previous call
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       // calculate the nav fn and path
00080       nav->priInc = 2*COST_NEUTRAL;
00081       nav->propNavFnAstar(std::max(nx*ny/20,nx+ny));
00082 
00083       // path
00084       int len = nav->calcPath(nplan);
00085 
00086       if (len > 0)                      // found plan
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   // create nav fn buffers 
00108   //
00109 
00110   NavFn::NavFn(int xs, int ys)
00111   {  
00112     // create cell arrays
00113     obsarr = costarr = NULL;
00114     potarr = NULL;
00115     pending = NULL;
00116     gradx = grady = NULL;
00117     setNavArr(xs,ys);
00118 
00119     // priority buffers
00120     pb1 = new int[PRIORITYBUFSIZE];
00121     pb2 = new int[PRIORITYBUFSIZE];
00122     pb3 = new int[PRIORITYBUFSIZE];
00123 
00124     // for Dijkstra (breadth-first), set to COST_NEUTRAL
00125     // for A* (best-first), set to COST_NEUTRAL
00126     priInc = 2*COST_NEUTRAL;    
00127 
00128     // goal and start
00129     goal[0] = goal[1] = 0;
00130     start[0] = start[1] = 0;
00131 
00132     // display function
00133     displayFn = NULL;
00134     displayInt = 0;
00135 
00136     // path buffers
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   // set goal, start positions for the nav fn
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   // Set/Reset map size
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];        // obstacles, 255 is obstacle
00218       memset(obsarr, 0, ns*sizeof(COSTTYPE));
00219       costarr = new COSTTYPE[ns]; // cost array, 2d config space
00220       memset(costarr, 0, ns*sizeof(COSTTYPE));
00221       potarr = new float[ns];   // navigation potential array
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   // set up cost array, usually from ROS
00231   //
00232 
00233   void
00234     NavFn::setCostmap(const COSTTYPE *cmap, bool isROS, bool allow_unknown)
00235     {
00236       COSTTYPE *cm = costarr;
00237       if (isROS)                        // ROS-type cost array
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             // This transforms the incoming cost values:
00245             // COST_OBS                 -> COST_OBS (incoming "lethal obstacle")
00246             // COST_OBS_ROS             -> COST_OBS (incoming "inscribed inflated obstacle")
00247             // values in range 0 to 252 -> values from COST_NEUTRAL to COST_OBS_ROS.
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                              // not a ROS map, just a PGM
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; // don't do borders
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       // calculate the nav fn and path
00307       propNavFnDijkstra(std::max(nx*ny/20,nx+ny),atStart);
00308 
00309       // path
00310       int len = calcPath(nx*ny/2);
00311 
00312       if (len > 0)                      // found plan
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   // calculate navigation function, given a costmap, goal, and start
00328   //
00329 
00330   bool
00331     NavFn::calcNavFnAstar()
00332     {
00333       setupNavFn(true);
00334 
00335       // calculate the nav fn and path
00336       propNavFnAstar(std::max(nx*ny/20,nx+ny));
00337 
00338       // path
00339       int len = calcPath(nx*4);
00340 
00341       if (len > 0)                      // found plan
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   // returning values
00356   //
00357 
00358   float *NavFn::getPathX() { return pathx; }
00359   float *NavFn::getPathY() { return pathy; }
00360   int    NavFn::getPathLen() { return npath; }
00361 
00362 
00363   //
00364   // simple obstacle setup for tests
00365   //
00366 
00367   void
00368     NavFn::setObs()
00369     {
00370 #if 0
00371       // set up a simple obstacle
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   // inserting onto the priority blocks
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   // Set up navigation potential arrays for new propagation
00406 
00407   void
00408     NavFn::setupNavFn(bool keepit)
00409     {
00410       // reset values in propagation arrays
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       // outer bounds of cost array
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       // priority buffers
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       // set goal
00444       int k = goal[0] + goal[1]*nx;
00445       initCost(k,0);
00446 
00447       // find # of obstacle cells
00448       pc = costarr;
00449       int ntot = 0;
00450       for (int i=0; i<ns; i++, pc++)
00451       {
00452         if (*pc >= COST_OBS)
00453           ntot++;                       // number of cells that are obstacles
00454       }
00455       nobs = ntot;
00456     }
00457 
00458 
00459   // initialize a goal-type cost for starting propagation
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   // Critical function: calculate updated potential value of a cell,
00474   //   given its neighbors' values
00475   // Planar-wave update calculation from two lowest neighbors in a 4-grid
00476   // Quadratic approximation to the interpolated value 
00477   // No checking of bounds here, this function should be fast
00478   //
00479 
00480 #define INVSQRT2 0.707106781
00481 
00482   inline void
00483     NavFn::updateCell(int n)
00484     {
00485       // get neighbors
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       //  ROS_INFO("[Update] c: %0.1f  l: %0.1f  r: %0.1f  u: %0.1f  d: %0.1f\n", 
00492       //         potarr[n], l, r, u, d);
00493       //  ROS_INFO("[Update] cost: %d\n", costarr[n]);
00494 
00495       // find lowest, and its lowest neighbor
00496       float ta, tc;
00497       if (l<r) tc=l; else tc=r;
00498       if (u<d) ta=u; else ta=d;
00499 
00500       // do planar wave update
00501       if (costarr[n] < COST_OBS)        // don't propagate into obstacles
00502       {
00503         float hf = (float)costarr[n]; // traversability factor
00504         float dc = tc-ta;               // relative cost between ta,tc
00505         if (dc < 0)             // ta is lowest
00506         {
00507           dc = -dc;
00508           ta = tc;
00509         }
00510 
00511         // calculate new potential
00512         float pot;
00513         if (dc >= hf)           // if too large, use ta-only update
00514           pot = ta+hf;
00515         else                    // two-neighbor interpolation update
00516         {
00517           // use quadratic approximation
00518           // might speed this up through table lookup, but still have to 
00519           //   do the divide
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         //      ROS_INFO("[Update] new pot: %d\n", costarr[n]);
00526 
00527         // now add affected neighbors to priority blocks
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)       // low-cost buffer block 
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                  // overflow block
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   // Use A* method for setting priorities
00558   // Critical function: calculate updated potential value of a cell,
00559   //   given its neighbors' values
00560   // Planar-wave update calculation from two lowest neighbors in a 4-grid
00561   // Quadratic approximation to the interpolated value 
00562   // No checking of bounds here, this function should be fast
00563   //
00564 
00565 #define INVSQRT2 0.707106781
00566 
00567   inline void
00568     NavFn::updateCellAstar(int n)
00569     {
00570       // get neighbors
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       //ROS_INFO("[Update] c: %0.1f  l: %0.1f  r: %0.1f  u: %0.1f  d: %0.1f\n", 
00577       //         potarr[n], l, r, u, d);
00578       // ROS_INFO("[Update] cost of %d: %d\n", n, costarr[n]);
00579 
00580       // find lowest, and its lowest neighbor
00581       float ta, tc;
00582       if (l<r) tc=l; else tc=r;
00583       if (u<d) ta=u; else ta=d;
00584 
00585       // do planar wave update
00586       if (costarr[n] < COST_OBS)        // don't propagate into obstacles
00587       {
00588         float hf = (float)costarr[n]; // traversability factor
00589         float dc = tc-ta;               // relative cost between ta,tc
00590         if (dc < 0)             // ta is lowest
00591         {
00592           dc = -dc;
00593           ta = tc;
00594         }
00595 
00596         // calculate new potential
00597         float pot;
00598         if (dc >= hf)           // if too large, use ta-only update
00599           pot = ta+hf;
00600         else                    // two-neighbor interpolation update
00601         {
00602           // use quadratic approximation
00603           // might speed this up through table lookup, but still have to 
00604           //   do the divide
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         //ROS_INFO("[Update] new pot: %d\n", costarr[n]);
00611 
00612         // now add affected neighbors to priority blocks
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           // calculate distance
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)       // low-cost buffer block 
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   // main propagation function
00652   // Dijkstra method, breadth-first
00653   // runs for a specified number of cycles,
00654   //   or until it runs out of cells to update,
00655   //   or until the Start cell is found (atStart = true)
00656   //
00657 
00658   bool
00659     NavFn::propNavFnDijkstra(int cycles, bool atStart)  
00660     {
00661       int nwv = 0;                      // max priority block size
00662       int nc = 0;                       // number of cells put into priority blocks
00663       int cycle = 0;            // which cycle we're on
00664 
00665       // set up start cell
00666       int startCell = start[1]*nx + start[0];
00667 
00668       for (; cycle < cycles; cycle++) // go for this many cycles, unless interrupted
00669       {
00670         // 
00671         if (curPe == 0 && nextPe == 0) // priority blocks empty
00672           break;
00673 
00674         // stats
00675         nc += curPe;
00676         if (curPe > nwv)
00677           nwv = curPe;
00678 
00679         // reset pending flags on current priority buffer
00680         int *pb = curP;
00681         int i = curPe;                  
00682         while (i-- > 0)         
00683           pending[*(pb++)] = false;
00684 
00685         // process current priority buffer
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         // swap priority blocks curP <=> nextP
00695         curPe = nextPe;
00696         nextPe = 0;
00697         pb = curP;              // swap buffers
00698         curP = nextP;
00699         nextP = pb;
00700 
00701         // see if we're done with this priority level
00702         if (curPe == 0)
00703         {
00704           curT += priInc;       // increment priority threshold
00705           curPe = overPe;       // set current to overflow block
00706           overPe = 0;
00707           pb = curP;            // swap buffers
00708           curP = overP;
00709           overP = pb;
00710         }
00711 
00712         // check if we've hit the Start cell
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; // finished up here
00722       else return false;
00723     }
00724 
00725 
00726   //
00727   // main propagation function
00728   // A* method, best-first
00729   // uses Euclidean distance heuristic
00730   // runs for a specified number of cycles,
00731   //   or until it runs out of cells to update,
00732   //   or until the Start cell is found (atStart = true)
00733   //
00734 
00735   bool
00736     NavFn::propNavFnAstar(int cycles)   
00737     {
00738       int nwv = 0;                      // max priority block size
00739       int nc = 0;                       // number of cells put into priority blocks
00740       int cycle = 0;            // which cycle we're on
00741 
00742       // set initial threshold, based on distance
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       // set up start cell
00748       int startCell = start[1]*nx + start[0];
00749 
00750       // do main cycle
00751       for (; cycle < cycles; cycle++) // go for this many cycles, unless interrupted
00752       {
00753         // 
00754         if (curPe == 0 && nextPe == 0) // priority blocks empty
00755           break;
00756 
00757         // stats
00758         nc += curPe;
00759         if (curPe > nwv)
00760           nwv = curPe;
00761 
00762         // reset pending flags on current priority buffer
00763         int *pb = curP;
00764         int i = curPe;                  
00765         while (i-- > 0)         
00766           pending[*(pb++)] = false;
00767 
00768         // process current priority buffer
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         // swap priority blocks curP <=> nextP
00778         curPe = nextPe;
00779         nextPe = 0;
00780         pb = curP;              // swap buffers
00781         curP = nextP;
00782         nextP = pb;
00783 
00784         // see if we're done with this priority level
00785         if (curPe == 0)
00786         {
00787           curT += priInc;       // increment priority threshold
00788           curPe = overPe;       // set current to overflow block
00789           overPe = 0;
00790           pb = curP;            // swap buffers
00791           curP = overP;
00792           overP = pb;
00793         }
00794 
00795         // check if we've hit the Start cell
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; // finished up here
00808       else return false;
00809     }
00810 
00811 
00812   float NavFn::getLastPathCost()
00813   {
00814     return last_path_cost_;
00815   }
00816 
00817 
00818   //
00819   // Path construction
00820   // Find gradient at array points, interpolate path
00821   // Use step size of pathStep, usually 0.5 pixel
00822   //
00823   // Some sanity checks:
00824   //  1. Stuck at same index position
00825   //  2. Doesn't get near goal
00826   //  3. Surrounded by high potentials
00827   //
00828 
00829   int
00830     NavFn::calcPath(int n, int *st)
00831     {
00832       // test write
00833       //savemap("test");
00834 
00835       // check path arrays
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       // set up start position at cell
00846       // st is always upper left corner for 4-point bilinear interpolation 
00847       if (st == NULL) st = start;
00848       int stc = st[1]*nx + st[0];
00849 
00850       // set up offset
00851       float dx=0;
00852       float dy=0;
00853       npath = 0;
00854 
00855       // go for <n> cycles at most
00856       for (int i=0; i<n; i++)
00857       {
00858         // check if near goal
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;       // done!
00865         }
00866 
00867         if (stc < nx || stc > ns-nx) // would be out of bounds
00868         {
00869           ROS_DEBUG("[PathCalc] Out of bounds");
00870           return 0;
00871         }
00872 
00873         // add to path
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         // check for potentials at eight positions near cell
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           // check eight neighbors to find the lowest
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             //savemap("navfn_highpot");
00933             return 0;
00934           }
00935         }
00936 
00937         // have a good gradient here
00938         else                    
00939         {
00940 
00941           // get grad at four positions near cell
00942           gradCell(stc);
00943           gradCell(stc+1);
00944           gradCell(stcnx);
00945           gradCell(stcnx+1);
00946 
00947 
00948           // get interpolated gradient
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; // interpolated x
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; // interpolated y
00955 
00956           // show gradients
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           // check for zero gradient, failed
00963           if (x == 0.0 && y == 0.0)
00964           {
00965             ROS_DEBUG("[PathCalc] Zero gradient");        
00966             return 0;
00967           }
00968 
00969           // move in the right direction
00970           float ss = pathStep/sqrt(x*x+y*y);
00971           dx += x*ss;
00972           dy += y*ss;
00973 
00974           // check for overflow
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         //      ROS_INFO("[Path] Pot: %0.1f  grad: %0.1f,%0.1f  pos: %0.1f,%0.1f\n",
00983         //           potarr[stc], x, y, pathx[npath-1], pathy[npath-1]);
00984       }
00985 
00986       //  return npath;                 // out of cycles, return failure
00987       ROS_DEBUG("[PathCalc] No path found, path too long");
00988       //savemap("navfn_pathlong");
00989       return 0;                 // out of cycles, return failure
00990     }
00991 
00992 
00993   //
00994   // gradient calculations
00995   //
00996 
00997   // calculate gradient at a cell
00998   // positive value are to the right and down
00999   float                         
01000     NavFn::gradCell(int n)
01001     {
01002       if (gradx[n]+grady[n] > 0.0)      // check this cell
01003         return 1.0;                     
01004 
01005       if (n < nx || n > ns-nx)  // would be out of bounds
01006         return 0.0;
01007 
01008       float cv = potarr[n];
01009       float dx = 0.0;
01010       float dy = 0.0;
01011 
01012       // check for in an obstacle
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                              // not in an obstacle
01027       {
01028         // dx calc, average to sides
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         // dy calc, average to sides
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       // normalize
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   // display function setup
01055   // <n> is the number of cycles to wait before displaying,
01056   //     use 0 to turn it off
01057 
01058   void
01059     NavFn::display(void fn(NavFn *nav), int n)
01060     {
01061       displayFn = fn;
01062       displayInt = n;
01063     }
01064 
01065 
01066   //
01067   // debug writes
01068   // saves costmap and start/goal
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       // write start and goal points
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       // write cost array
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 };


navfn
Author(s): Kurt Konolige, Eitan Marder-Eppstein
autogenerated on Mon Oct 6 2014 02:46:56