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
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064 #define COST_NEUTRAL 50 // Set this to "open space" value
00065 #define COST_FACTOR 0.8 // Used for translating costs in NavFn::setCostmap()
00066
00067
00068
00069
00070 #ifndef COSTTYPE
00071 #define COSTTYPE unsigned char // Whatever is used...
00072 #endif
00073
00074
00075 #define POT_HIGH 1.0e10 // unassigned cell potential
00076
00077
00078 #define PRIORITYBUFSIZE 10000
00079
00080
00081 namespace navfn {
00096 int create_nav_plan_astar(const COSTTYPE *costmap, int nx, int ny,
00097 int* goal, int* start,
00098 float *plan, int nplan);
00099
00100
00101
00106 class NavFn
00107 {
00108 public:
00114 NavFn(int nx, int ny);
00115
00116 ~NavFn();
00117
00123 void setNavArr(int nx, int ny);
00124 int nx, ny, ns;
00132 void setCostmap(const COSTTYPE *cmap, bool isROS=true, bool allow_unknown = true);
00138 bool calcNavFnAstar();
00143 bool calcNavFnDijkstra(bool atStart = false);
00149 float *getPathX();
00155 float *getPathY();
00161 int getPathLen();
00167 float getLastPathCost();
00170 COSTTYPE *costarr;
00171 float *potarr;
00172 bool *pending;
00173 int nobs;
00176 int *pb1, *pb2, *pb3;
00177 int *curP, *nextP, *overP;
00178 int curPe, nextPe, overPe;
00181 float curT;
00182 float priInc;
00189 void setGoal(int *goal);
00190
00195 void setStart(int *start);
00196
00197 int goal[2];
00198 int start[2];
00204 void initCost(int k, float v);
00207 void setObs();
00208
00215 void updateCell(int n);
00221 void updateCellAstar(int n);
00223 void setupNavFn(bool keepit = false);
00231 bool propNavFnDijkstra(int cycles, bool atStart = false);
00237 bool propNavFnAstar(int cycles);
00240 float *gradx, *grady;
00241 float *pathx, *pathy;
00242 int npath;
00243 int npathbuf;
00245 float last_path_cost_;
00253 int calcPath(int n, int *st = NULL);
00255 float gradCell(int n);
00256 float pathStep;
00259 void display(void fn(NavFn *nav), int n = 100);
00260 int displayInt;
00261 void (*displayFn)(NavFn *nav);
00264 void savemap(const char *fname);
00266 };
00267 };
00268
00269
00270 #endif // NAVFN