$search
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 // 00036 // Navigation function computation 00037 // Uses Dijkstra's method 00038 // Modified for Euclidean-distance computation 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 // cost defs 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 // Define the cost type in the case that it is not set. However, this allows 00057 // clients to modify it without changing the file. Arguably, it is better to require it to 00058 // be defined by a user explicitly 00059 #ifndef COSTTYPE 00060 #define COSTTYPE unsigned char // Whatever is used... 00061 #endif 00062 00063 // potential defs 00064 #define POT_HIGH 1.0e10 // unassigned cell potential 00065 00066 // priority buffers 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); // size of map 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