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             *cm = COST_OBS;
00245             int v = *cmap;
00246             if (v < COST_OBS_ROS)
00247             {
00248               v = COST_NEUTRAL+COST_FACTOR*v;
00249               if (v >= COST_OBS)
00250                 v = COST_OBS-1;
00251               *cm = v;
00252             }
00253             else if(v == COST_UNKNOWN_ROS && allow_unknown)
00254             {
00255               v = COST_OBS-1;
00256               *cm = v;
00257             }
00258           }
00259         }
00260       }
00261 
00262       else                              // not a ROS map, just a PGM
00263       {
00264         for (int i=0; i<ny; i++)
00265         {
00266           int k=i*nx;
00267           for (int j=0; j<nx; j++, k++, cmap++, cm++)
00268           {
00269             *cm = COST_OBS;
00270             if (i<7 || i > ny-8 || j<7 || j > nx-8)
00271               continue; // don't do borders
00272             int v = *cmap;
00273             if (v < COST_OBS_ROS)
00274             {
00275               v = COST_NEUTRAL+COST_FACTOR*v;
00276               if (v >= COST_OBS)
00277                 v = COST_OBS-1;
00278               *cm = v;
00279             }
00280             else if(v == COST_UNKNOWN_ROS)
00281             {
00282               v = COST_OBS-1;
00283               *cm = v;
00284             }
00285           }
00286         }
00287 
00288       }
00289     }
00290 
00291   bool
00292     NavFn::calcNavFnDijkstra(bool atStart)
00293     {
00294       setupNavFn(true);
00295 
00296       // calculate the nav fn and path
00297       propNavFnDijkstra(std::max(nx*ny/20,nx+ny),atStart);
00298 
00299       // path
00300       int len = calcPath(nx*ny/2);
00301 
00302       if (len > 0)                      // found plan
00303       {
00304         ROS_DEBUG("[NavFn] Path found, %d steps\n", len);
00305         return true;
00306       }
00307       else
00308       {
00309         ROS_DEBUG("[NavFn] No path found\n");
00310         return false;
00311       }
00312 
00313     }
00314 
00315 
00316   //
00317   // calculate navigation function, given a costmap, goal, and start
00318   //
00319 
00320   bool
00321     NavFn::calcNavFnAstar()
00322     {
00323       setupNavFn(true);
00324 
00325       // calculate the nav fn and path
00326       propNavFnAstar(std::max(nx*ny/20,nx+ny));
00327 
00328       // path
00329       int len = calcPath(nx*4);
00330 
00331       if (len > 0)                      // found plan
00332       {
00333         ROS_DEBUG("[NavFn] Path found, %d steps\n", len);
00334         return true;
00335       }
00336       else
00337       {
00338         ROS_DEBUG("[NavFn] No path found\n");
00339         return false;
00340       }
00341     }
00342 
00343 
00344   //
00345   // returning values
00346   //
00347 
00348   float *NavFn::getPathX() { return pathx; }
00349   float *NavFn::getPathY() { return pathy; }
00350   int    NavFn::getPathLen() { return npath; }
00351 
00352 
00353   //
00354   // simple obstacle setup for tests
00355   //
00356 
00357   void
00358     NavFn::setObs()
00359     {
00360 #if 0
00361       // set up a simple obstacle
00362       ROS_INFO("[NavFn] Setting simple obstacle\n");
00363       int xx = nx/3;
00364       for (int i=ny/3; i<ny; i++)
00365         costarr[i*nx + xx] = COST_OBS;
00366       xx = 2*nx/3;
00367       for (int i=ny/3; i<ny; i++)
00368         costarr[i*nx + xx] = COST_OBS;
00369 
00370       xx = nx/4;
00371       for (int i=20; i<ny-ny/3; i++)
00372         costarr[i*nx + xx] = COST_OBS;
00373       xx = nx/2;
00374       for (int i=20; i<ny-ny/3; i++)
00375         costarr[i*nx + xx] = COST_OBS;
00376       xx = 3*nx/4;
00377       for (int i=20; i<ny-ny/3; i++)
00378         costarr[i*nx + xx] = COST_OBS;
00379 #endif
00380     }
00381 
00382 
00383   // inserting onto the priority blocks
00384 #define push_cur(n)  { if (n>=0 && n<ns && !pending[n] && \
00385     costarr[n]<COST_OBS && curPe<PRIORITYBUFSIZE) \
00386   { curP[curPe++]=n; pending[n]=true; }}
00387 #define push_next(n) { if (n>=0 && n<ns && !pending[n] && \
00388     costarr[n]<COST_OBS && nextPe<PRIORITYBUFSIZE) \
00389   { nextP[nextPe++]=n; pending[n]=true; }}
00390 #define push_over(n) { if (n>=0 && n<ns && !pending[n] && \
00391     costarr[n]<COST_OBS && overPe<PRIORITYBUFSIZE) \
00392   { overP[overPe++]=n; pending[n]=true; }}
00393 
00394 
00395   // Set up navigation potential arrays for new propagation
00396 
00397   void
00398     NavFn::setupNavFn(bool keepit)
00399     {
00400       // reset values in propagation arrays
00401       for (int i=0; i<ns; i++)
00402       {
00403         potarr[i] = POT_HIGH;
00404         if (!keepit) costarr[i] = COST_NEUTRAL;
00405         gradx[i] = grady[i] = 0.0;
00406       }
00407 
00408       // outer bounds of cost array
00409       COSTTYPE *pc;
00410       pc = costarr;
00411       for (int i=0; i<nx; i++)
00412         *pc++ = COST_OBS;
00413       pc = costarr + (ny-1)*nx;
00414       for (int i=0; i<nx; i++)
00415         *pc++ = COST_OBS;
00416       pc = costarr;
00417       for (int i=0; i<ny; i++, pc+=nx)
00418         *pc = COST_OBS;
00419       pc = costarr + nx - 1;
00420       for (int i=0; i<ny; i++, pc+=nx)
00421         *pc = COST_OBS;
00422 
00423       // priority buffers
00424       curT = COST_OBS;
00425       curP = pb1; 
00426       curPe = 0;
00427       nextP = pb2;
00428       nextPe = 0;
00429       overP = pb3;
00430       overPe = 0;
00431       memset(pending, 0, ns*sizeof(bool));
00432 
00433       // set goal
00434       int k = goal[0] + goal[1]*nx;
00435       initCost(k,0);
00436 
00437       // find # of obstacle cells
00438       pc = costarr;
00439       int ntot = 0;
00440       for (int i=0; i<ns; i++, pc++)
00441       {
00442         if (*pc >= COST_OBS)
00443           ntot++;                       // number of cells that are obstacles
00444       }
00445       nobs = ntot;
00446     }
00447 
00448 
00449   // initialize a goal-type cost for starting propagation
00450 
00451   void
00452     NavFn::initCost(int k, float v)
00453     {
00454       potarr[k] = v;
00455       push_cur(k+1);
00456       push_cur(k-1);
00457       push_cur(k-nx);
00458       push_cur(k+nx);
00459     }
00460 
00461 
00462   // 
00463   // Critical function: calculate updated potential value of a cell,
00464   //   given its neighbors' values
00465   // Planar-wave update calculation from two lowest neighbors in a 4-grid
00466   // Quadratic approximation to the interpolated value 
00467   // No checking of bounds here, this function should be fast
00468   //
00469 
00470 #define INVSQRT2 0.707106781
00471 
00472   inline void
00473     NavFn::updateCell(int n)
00474     {
00475       // get neighbors
00476       float u,d,l,r;
00477       l = potarr[n-1];
00478       r = potarr[n+1];          
00479       u = potarr[n-nx];
00480       d = potarr[n+nx];
00481       //  ROS_INFO("[Update] c: %0.1f  l: %0.1f  r: %0.1f  u: %0.1f  d: %0.1f\n", 
00482       //         potarr[n], l, r, u, d);
00483       //  ROS_INFO("[Update] cost: %d\n", costarr[n]);
00484 
00485       // find lowest, and its lowest neighbor
00486       float ta, tc;
00487       if (l<r) tc=l; else tc=r;
00488       if (u<d) ta=u; else ta=d;
00489 
00490       // do planar wave update
00491       if (costarr[n] < COST_OBS)        // don't propagate into obstacles
00492       {
00493         float hf = (float)costarr[n]; // traversability factor
00494         float dc = tc-ta;               // relative cost between ta,tc
00495         if (dc < 0)             // ta is lowest
00496         {
00497           dc = -dc;
00498           ta = tc;
00499         }
00500 
00501         // calculate new potential
00502         float pot;
00503         if (dc >= hf)           // if too large, use ta-only update
00504           pot = ta+hf;
00505         else                    // two-neighbor interpolation update
00506         {
00507           // use quadratic approximation
00508           // might speed this up through table lookup, but still have to 
00509           //   do the divide
00510           float d = dc/hf;
00511           float v = -0.2301*d*d + 0.5307*d + 0.7040;
00512           pot = ta + hf*v;
00513         }
00514 
00515         //      ROS_INFO("[Update] new pot: %d\n", costarr[n]);
00516 
00517         // now add affected neighbors to priority blocks
00518         if (pot < potarr[n])
00519         {
00520           float le = INVSQRT2*(float)costarr[n-1];
00521           float re = INVSQRT2*(float)costarr[n+1];
00522           float ue = INVSQRT2*(float)costarr[n-nx];
00523           float de = INVSQRT2*(float)costarr[n+nx];
00524           potarr[n] = pot;
00525           if (pot < curT)       // low-cost buffer block 
00526           {
00527             if (l > pot+le) push_next(n-1);
00528             if (r > pot+re) push_next(n+1);
00529             if (u > pot+ue) push_next(n-nx);
00530             if (d > pot+de) push_next(n+nx);
00531           }
00532           else                  // overflow block
00533           {
00534             if (l > pot+le) push_over(n-1);
00535             if (r > pot+re) push_over(n+1);
00536             if (u > pot+ue) push_over(n-nx);
00537             if (d > pot+de) push_over(n+nx);
00538           }
00539         }
00540 
00541       }
00542 
00543     }
00544 
00545 
00546   //
00547   // Use A* method for setting priorities
00548   // Critical function: calculate updated potential value of a cell,
00549   //   given its neighbors' values
00550   // Planar-wave update calculation from two lowest neighbors in a 4-grid
00551   // Quadratic approximation to the interpolated value 
00552   // No checking of bounds here, this function should be fast
00553   //
00554 
00555 #define INVSQRT2 0.707106781
00556 
00557   inline void
00558     NavFn::updateCellAstar(int n)
00559     {
00560       // get neighbors
00561       float u,d,l,r;
00562       l = potarr[n-1];
00563       r = potarr[n+1];          
00564       u = potarr[n-nx];
00565       d = potarr[n+nx];
00566       //ROS_INFO("[Update] c: %0.1f  l: %0.1f  r: %0.1f  u: %0.1f  d: %0.1f\n", 
00567       //         potarr[n], l, r, u, d);
00568       // ROS_INFO("[Update] cost of %d: %d\n", n, costarr[n]);
00569 
00570       // find lowest, and its lowest neighbor
00571       float ta, tc;
00572       if (l<r) tc=l; else tc=r;
00573       if (u<d) ta=u; else ta=d;
00574 
00575       // do planar wave update
00576       if (costarr[n] < COST_OBS)        // don't propagate into obstacles
00577       {
00578         float hf = (float)costarr[n]; // traversability factor
00579         float dc = tc-ta;               // relative cost between ta,tc
00580         if (dc < 0)             // ta is lowest
00581         {
00582           dc = -dc;
00583           ta = tc;
00584         }
00585 
00586         // calculate new potential
00587         float pot;
00588         if (dc >= hf)           // if too large, use ta-only update
00589           pot = ta+hf;
00590         else                    // two-neighbor interpolation update
00591         {
00592           // use quadratic approximation
00593           // might speed this up through table lookup, but still have to 
00594           //   do the divide
00595           float d = dc/hf;
00596           float v = -0.2301*d*d + 0.5307*d + 0.7040;
00597           pot = ta + hf*v;
00598         }
00599 
00600         //ROS_INFO("[Update] new pot: %d\n", costarr[n]);
00601 
00602         // now add affected neighbors to priority blocks
00603         if (pot < potarr[n])
00604         {
00605           float le = INVSQRT2*(float)costarr[n-1];
00606           float re = INVSQRT2*(float)costarr[n+1];
00607           float ue = INVSQRT2*(float)costarr[n-nx];
00608           float de = INVSQRT2*(float)costarr[n+nx];
00609 
00610           // calculate distance
00611           int x = n%nx;
00612           int y = n/nx;
00613           float dist = (x-start[0])*(x-start[0]) + (y-start[1])*(y-start[1]);
00614           dist = sqrtf(dist)*(float)COST_NEUTRAL;
00615 
00616           potarr[n] = pot;
00617           pot += dist;
00618           if (pot < curT)       // low-cost buffer block 
00619           {
00620             if (l > pot+le) push_next(n-1);
00621             if (r > pot+re) push_next(n+1);
00622             if (u > pot+ue) push_next(n-nx);
00623             if (d > pot+de) push_next(n+nx);
00624           }
00625           else
00626           {
00627             if (l > pot+le) push_over(n-1);
00628             if (r > pot+re) push_over(n+1);
00629             if (u > pot+ue) push_over(n-nx);
00630             if (d > pot+de) push_over(n+nx);
00631           }
00632         }
00633 
00634       }
00635 
00636     }
00637 
00638 
00639 
00640   //
00641   // main propagation function
00642   // Dijkstra method, breadth-first
00643   // runs for a specified number of cycles,
00644   //   or until it runs out of cells to update,
00645   //   or until the Start cell is found (atStart = true)
00646   //
00647 
00648   bool
00649     NavFn::propNavFnDijkstra(int cycles, bool atStart)  
00650     {
00651       int nwv = 0;                      // max priority block size
00652       int nc = 0;                       // number of cells put into priority blocks
00653       int cycle = 0;            // which cycle we're on
00654 
00655       // set up start cell
00656       int startCell = start[1]*nx + start[0];
00657 
00658       for (; cycle < cycles; cycle++) // go for this many cycles, unless interrupted
00659       {
00660         // 
00661         if (curPe == 0 && nextPe == 0) // priority blocks empty
00662           break;
00663 
00664         // stats
00665         nc += curPe;
00666         if (curPe > nwv)
00667           nwv = curPe;
00668 
00669         // reset pending flags on current priority buffer
00670         int *pb = curP;
00671         int i = curPe;                  
00672         while (i-- > 0)         
00673           pending[*(pb++)] = false;
00674 
00675         // process current priority buffer
00676         pb = curP; 
00677         i = curPe;
00678         while (i-- > 0)         
00679           updateCell(*pb++);
00680 
00681         if (displayInt > 0 &&  (cycle % displayInt) == 0)
00682           displayFn(this);
00683 
00684         // swap priority blocks curP <=> nextP
00685         curPe = nextPe;
00686         nextPe = 0;
00687         pb = curP;              // swap buffers
00688         curP = nextP;
00689         nextP = pb;
00690 
00691         // see if we're done with this priority level
00692         if (curPe == 0)
00693         {
00694           curT += priInc;       // increment priority threshold
00695           curPe = overPe;       // set current to overflow block
00696           overPe = 0;
00697           pb = curP;            // swap buffers
00698           curP = overP;
00699           overP = pb;
00700         }
00701 
00702         // check if we've hit the Start cell
00703         if (atStart)
00704           if (potarr[startCell] < POT_HIGH)
00705             break;
00706       }
00707 
00708       ROS_DEBUG("[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n", 
00709           cycle,nc,(int)((nc*100.0)/(ns-nobs)),nwv);
00710 
00711       if (cycle < cycles) return true; // finished up here
00712       else return false;
00713     }
00714 
00715 
00716   //
00717   // main propagation function
00718   // A* method, best-first
00719   // uses Euclidean distance heuristic
00720   // runs for a specified number of cycles,
00721   //   or until it runs out of cells to update,
00722   //   or until the Start cell is found (atStart = true)
00723   //
00724 
00725   bool
00726     NavFn::propNavFnAstar(int cycles)   
00727     {
00728       int nwv = 0;                      // max priority block size
00729       int nc = 0;                       // number of cells put into priority blocks
00730       int cycle = 0;            // which cycle we're on
00731 
00732       // set initial threshold, based on distance
00733       float dist = (goal[0]-start[0])*(goal[0]-start[0]) + (goal[1]-start[1])*(goal[1]-start[1]);
00734       dist = sqrtf(dist)*(float)COST_NEUTRAL;
00735       curT = dist + curT;
00736 
00737       // set up start cell
00738       int startCell = start[1]*nx + start[0];
00739 
00740       // do main cycle
00741       for (; cycle < cycles; cycle++) // go for this many cycles, unless interrupted
00742       {
00743         // 
00744         if (curPe == 0 && nextPe == 0) // priority blocks empty
00745           break;
00746 
00747         // stats
00748         nc += curPe;
00749         if (curPe > nwv)
00750           nwv = curPe;
00751 
00752         // reset pending flags on current priority buffer
00753         int *pb = curP;
00754         int i = curPe;                  
00755         while (i-- > 0)         
00756           pending[*(pb++)] = false;
00757 
00758         // process current priority buffer
00759         pb = curP; 
00760         i = curPe;
00761         while (i-- > 0)         
00762           updateCellAstar(*pb++);
00763 
00764         if (displayInt > 0 &&  (cycle % displayInt) == 0)
00765           displayFn(this);
00766 
00767         // swap priority blocks curP <=> nextP
00768         curPe = nextPe;
00769         nextPe = 0;
00770         pb = curP;              // swap buffers
00771         curP = nextP;
00772         nextP = pb;
00773 
00774         // see if we're done with this priority level
00775         if (curPe == 0)
00776         {
00777           curT += priInc;       // increment priority threshold
00778           curPe = overPe;       // set current to overflow block
00779           overPe = 0;
00780           pb = curP;            // swap buffers
00781           curP = overP;
00782           overP = pb;
00783         }
00784 
00785         // check if we've hit the Start cell
00786         if (potarr[startCell] < POT_HIGH)
00787           break;
00788 
00789       }
00790 
00791       last_path_cost_ = potarr[startCell];
00792 
00793       ROS_DEBUG("[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n", 
00794           cycle,nc,(int)((nc*100.0)/(ns-nobs)),nwv);
00795 
00796 
00797       if (potarr[startCell] < POT_HIGH) return true; // finished up here
00798       else return false;
00799     }
00800 
00801 
00802   float NavFn::getLastPathCost()
00803   {
00804     return last_path_cost_;
00805   }
00806 
00807 
00808   //
00809   // Path construction
00810   // Find gradient at array points, interpolate path
00811   // Use step size of pathStep, usually 0.5 pixel
00812   //
00813   // Some sanity checks:
00814   //  1. Stuck at same index position
00815   //  2. Doesn't get near goal
00816   //  3. Surrounded by high potentials
00817   //
00818 
00819   int
00820     NavFn::calcPath(int n, int *st)
00821     {
00822       // test write
00823       //savemap("test");
00824 
00825       // check path arrays
00826       if (npathbuf < n)
00827       {
00828         if (pathx) delete [] pathx;
00829         if (pathy) delete [] pathy;
00830         pathx = new float[n];
00831         pathy = new float[n];
00832         npathbuf = n;
00833       }
00834 
00835       // set up start position at cell
00836       // st is always upper left corner for 4-point bilinear interpolation 
00837       if (st == NULL) st = start;
00838       int stc = st[1]*nx + st[0];
00839 
00840       // set up offset
00841       float dx=0;
00842       float dy=0;
00843       npath = 0;
00844 
00845       // go for <n> cycles at most
00846       for (int i=0; i<n; i++)
00847       {
00848         // check if near goal
00849         int nearest_point=std::max(0,std::min(nx*ny-1,stc+(int)round(dx)+(int)(nx*round(dy))));
00850         if (potarr[nearest_point] < COST_NEUTRAL)
00851         {
00852           pathx[npath] = (float)goal[0];
00853           pathy[npath] = (float)goal[1];
00854           return ++npath;       // done!
00855         }
00856 
00857         if (stc < nx || stc > ns-nx) // would be out of bounds
00858         {
00859           ROS_DEBUG("[PathCalc] Out of bounds");
00860           return 0;
00861         }
00862 
00863         // add to path
00864         pathx[npath] = stc%nx + dx;
00865         pathy[npath] = stc/nx + dy;
00866         npath++;
00867 
00868         bool oscillation_detected = false;
00869         if( npath > 2 &&
00870             pathx[npath-1] == pathx[npath-3] &&
00871             pathy[npath-1] == pathy[npath-3] )
00872         {
00873           ROS_DEBUG("[PathCalc] oscillation detected, attempting fix.");
00874           oscillation_detected = true;
00875         }
00876 
00877         int stcnx = stc+nx;
00878         int stcpx = stc-nx;
00879 
00880         // check for potentials at eight positions near cell
00881         if (potarr[stc] >= POT_HIGH ||
00882             potarr[stc+1] >= POT_HIGH ||
00883             potarr[stc-1] >= POT_HIGH ||
00884             potarr[stcnx] >= POT_HIGH ||
00885             potarr[stcnx+1] >= POT_HIGH ||
00886             potarr[stcnx-1] >= POT_HIGH ||
00887             potarr[stcpx] >= POT_HIGH ||
00888             potarr[stcpx+1] >= POT_HIGH ||
00889             potarr[stcpx-1] >= POT_HIGH ||
00890             oscillation_detected)
00891         {
00892           ROS_DEBUG("[Path] Pot fn boundary, following grid (%0.1f/%d)", potarr[stc], npath);
00893           // check eight neighbors to find the lowest
00894           int minc = stc;
00895           int minp = potarr[stc];
00896           int st = stcpx - 1;
00897           if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00898           st++;
00899           if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00900           st++;
00901           if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00902           st = stc-1;
00903           if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00904           st = stc+1;
00905           if (potarr[st] < minp) {minp = potarr[st]; minc = st; }
00906           st = stcnx-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           stc = minc;
00913           dx = 0;
00914           dy = 0;
00915 
00916           ROS_DEBUG("[Path] Pot: %0.1f  pos: %0.1f,%0.1f",
00917               potarr[stc], pathx[npath-1], pathy[npath-1]);
00918 
00919           if (potarr[stc] >= POT_HIGH)
00920           {
00921             ROS_DEBUG("[PathCalc] No path found, high potential");
00922             //savemap("navfn_highpot");
00923             return 0;
00924           }
00925         }
00926 
00927         // have a good gradient here
00928         else                    
00929         {
00930 
00931           // get grad at four positions near cell
00932           gradCell(stc);
00933           gradCell(stc+1);
00934           gradCell(stcnx);
00935           gradCell(stcnx+1);
00936 
00937 
00938           // get interpolated gradient
00939           float x1 = (1.0-dx)*gradx[stc] + dx*gradx[stc+1];
00940           float x2 = (1.0-dx)*gradx[stcnx] + dx*gradx[stcnx+1];
00941           float x = (1.0-dy)*x1 + dy*x2; // interpolated x
00942           float y1 = (1.0-dx)*grady[stc] + dx*grady[stc+1];
00943           float y2 = (1.0-dx)*grady[stcnx] + dx*grady[stcnx+1];
00944           float y = (1.0-dy)*y1 + dy*y2; // interpolated y
00945 
00946           // show gradients
00947           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",
00948                     gradx[stc], grady[stc], gradx[stc+1], grady[stc+1], 
00949                     gradx[stcnx], grady[stcnx], gradx[stcnx+1], grady[stcnx+1],
00950                     x, y);
00951 
00952           // check for zero gradient, failed
00953           if (x == 0.0 && y == 0.0)
00954           {
00955             ROS_DEBUG("[PathCalc] Zero gradient");        
00956             return 0;
00957           }
00958 
00959           // move in the right direction
00960           float ss = pathStep/sqrt(x*x+y*y);
00961           dx += x*ss;
00962           dy += y*ss;
00963 
00964           // check for overflow
00965           if (dx > 1.0) { stc++; dx -= 1.0; }
00966           if (dx < -1.0) { stc--; dx += 1.0; }
00967           if (dy > 1.0) { stc+=nx; dy -= 1.0; }
00968           if (dy < -1.0) { stc-=nx; dy += 1.0; }
00969 
00970         }
00971 
00972         //      ROS_INFO("[Path] Pot: %0.1f  grad: %0.1f,%0.1f  pos: %0.1f,%0.1f\n",
00973         //           potarr[stc], x, y, pathx[npath-1], pathy[npath-1]);
00974       }
00975 
00976       //  return npath;                 // out of cycles, return failure
00977       ROS_DEBUG("[PathCalc] No path found, path too long");
00978       //savemap("navfn_pathlong");
00979       return 0;                 // out of cycles, return failure
00980     }
00981 
00982 
00983   //
00984   // gradient calculations
00985   //
00986 
00987   // calculate gradient at a cell
00988   // positive value are to the right and down
00989   float                         
00990     NavFn::gradCell(int n)
00991     {
00992       if (gradx[n]+grady[n] > 0.0)      // check this cell
00993         return 1.0;                     
00994 
00995       if (n < nx || n > ns-nx)  // would be out of bounds
00996         return 0.0;
00997 
00998       float cv = potarr[n];
00999       float dx = 0.0;
01000       float dy = 0.0;
01001 
01002       // check for in an obstacle
01003       if (cv >= POT_HIGH) 
01004       {
01005         if (potarr[n-1] < POT_HIGH)
01006           dx = -COST_OBS;
01007         else if (potarr[n+1] < POT_HIGH)
01008           dx = COST_OBS;
01009 
01010         if (potarr[n-nx] < POT_HIGH)
01011           dy = -COST_OBS;
01012         else if (potarr[nx+1] < POT_HIGH)
01013           dy = COST_OBS;
01014       }
01015 
01016       else                              // not in an obstacle
01017       {
01018         // dx calc, average to sides
01019         if (potarr[n-1] < POT_HIGH)
01020           dx += potarr[n-1]- cv;        
01021         if (potarr[n+1] < POT_HIGH)
01022           dx += cv - potarr[n+1]; 
01023 
01024         // dy calc, average to sides
01025         if (potarr[n-nx] < POT_HIGH)
01026           dy += potarr[n-nx]- cv;       
01027         if (potarr[n+nx] < POT_HIGH)
01028           dy += cv - potarr[n+nx]; 
01029       }
01030 
01031       // normalize
01032       float norm = sqrtf(dx*dx+dy*dy);
01033       if (norm > 0)
01034       {
01035         norm = 1.0/norm;
01036         gradx[n] = norm*dx;
01037         grady[n] = norm*dy;
01038       }
01039       return norm;
01040     }
01041 
01042 
01043   //
01044   // display function setup
01045   // <n> is the number of cycles to wait before displaying,
01046   //     use 0 to turn it off
01047 
01048   void
01049     NavFn::display(void fn(NavFn *nav), int n)
01050     {
01051       displayFn = fn;
01052       displayInt = n;
01053     }
01054 
01055 
01056   //
01057   // debug writes
01058   // saves costmap and start/goal
01059   //
01060 
01061   void 
01062     NavFn::savemap(const char *fname)
01063     {
01064       char fn[4096];
01065 
01066       ROS_DEBUG("[NavFn] Saving costmap and start/goal points");
01067       // write start and goal points
01068       sprintf(fn,"%s.txt",fname);
01069       FILE *fp = fopen(fn,"w");
01070       if (!fp)
01071       {
01072         ROS_WARN("Can't open file %s", fn);
01073         return;
01074       }
01075       fprintf(fp,"Goal: %d %d\nStart: %d %d\n",goal[0],goal[1],start[0],start[1]);
01076       fclose(fp);
01077 
01078       // write cost array
01079       if (!costarr) return;
01080       sprintf(fn,"%s.pgm",fname);
01081       fp = fopen(fn,"wb");
01082       if (!fp)
01083       {
01084         ROS_WARN("Can't open file %s", fn);
01085         return;
01086       }
01087       fprintf(fp,"P5\n%d\n%d\n%d\n", nx, ny, 0xff);
01088       fwrite(costarr,1,nx*ny,fp);
01089       fclose(fp);
01090     }
01091 };


navfn
Author(s): Kurt Konolige, Eitan Marder-Eppstein
autogenerated on Sat Dec 28 2013 17:14:13