Go to the documentation of this file.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 #ifndef _NAVFN_H
00042 #define _NAVFN_H
00043
00044 #include <math.h>
00045 #include <stdint.h>
00046 #include <string.h>
00047 #include <stdio.h>
00048
00049
00050 #define COST_UNKNOWN_ROS 255 // 255 is unknown cost
00051 #define COST_OBS 254 // 254 for forbidden regions
00052 #define COST_OBS_ROS 253 // ROS values of 253 are obstacles
00053 #define COST_NEUTRAL 50 // Set this to "open space" value
00054 #define COST_FACTOR 3 // Used for translating costs in NavFn::setCostmap()
00055
00056
00057
00058
00059 #ifndef COSTTYPE
00060 #define COSTTYPE unsigned char // Whatever is used...
00061 #endif
00062
00063
00064 #define POT_HIGH 1.0e10 // unassigned cell potential
00065
00066
00067 #define PRIORITYBUFSIZE 10000
00068
00069
00070 namespace navfn {
00085 int create_nav_plan_astar(const COSTTYPE *costmap, int nx, int ny,
00086 int* goal, int* start,
00087 float *plan, int nplan);
00088
00089
00090
00095 class NavFn
00096 {
00097 public:
00103 NavFn(int nx, int ny);
00104
00105 ~NavFn();
00106
00112 void setNavArr(int nx, int ny);
00113 int nx, ny, ns;
00121 void setCostmap(const COSTTYPE *cmap, bool isROS=true, bool allow_unknown = true);
00127 bool calcNavFnAstar();
00132 bool calcNavFnDijkstra(bool atStart = false);
00138 float *getPathX();
00144 float *getPathY();
00150 int getPathLen();
00156 float getLastPathCost();
00159 COSTTYPE *obsarr;
00160 COSTTYPE *costarr;
00161 float *potarr;
00162 bool *pending;
00163 int nobs;
00166 int *pb1, *pb2, *pb3;
00167 int *curP, *nextP, *overP;
00168 int curPe, nextPe, overPe;
00171 float curT;
00172 float priInc;
00179 void setGoal(int *goal);
00180
00185 void setStart(int *start);
00186
00187 int goal[2];
00188 int start[2];
00194 void initCost(int k, float v);
00197 void setObs();
00198
00205 void updateCell(int n);
00211 void updateCellAstar(int n);
00213 void setupNavFn(bool keepit = false);
00221 bool propNavFnDijkstra(int cycles, bool atStart = false);
00227 bool propNavFnAstar(int cycles);
00230 float *gradx, *grady;
00231 float *pathx, *pathy;
00232 int npath;
00233 int npathbuf;
00235 float last_path_cost_;
00243 int calcPath(int n, int *st = NULL);
00245 float gradCell(int n);
00246 float pathStep;
00249 void display(void fn(NavFn *nav), int n = 100);
00250 int displayInt;
00251 void (*displayFn)(NavFn *nav);
00254 void savemap(const char *fname);
00256 };
00257 };
00258
00259
00260 #endif // NAVFN