Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
navfn.hpp
1 // Copyright (c) 2008, Willow Garage, Inc.
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD License 2.0)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of the Willow Garage nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
33 //
34 // Navigation function computation
35 // Uses Dijkstra's method
36 // Modified for Euclidean-distance computation
37 //
38 
39 #ifndef NAV2_NAVFN_PLANNER__NAVFN_HPP_
40 #define NAV2_NAVFN_PLANNER__NAVFN_HPP_
41 
42 #include <math.h>
43 #include <stdint.h>
44 #include <string.h>
45 #include <stdio.h>
46 
47 namespace nav2_navfn_planner
48 {
49 
50 // cost defs
51 #define COST_UNKNOWN_ROS 255 // 255 is unknown cost
52 #define COST_OBS 254 // 254 for forbidden regions
53 #define COST_OBS_ROS 253 // ROS values of 253 are obstacles
54 
55 // navfn cost values are set to
56 // COST_NEUTRAL + COST_FACTOR * costmap_cost_value.
57 // Incoming costmap cost values are in the range 0 to 252.
58 // With COST_NEUTRAL of 50, the COST_FACTOR needs to be about 0.8 to
59 // ensure the input values are spread evenly over the output range, 50
60 // to 253. If COST_FACTOR is higher, cost values will have a plateau
61 // around obstacles and the planner will then treat (for example) the
62 // whole width of a narrow hallway as equally undesirable and thus
63 // will not plan paths down the center.
64 
65 #define COST_NEUTRAL 50 // Set this to "open space" value
66 #define COST_FACTOR 0.8 // Used for translating costs in NavFn::setCostmap()
67 
68 // Define the cost type in the case that it is not set. However, this allows
69 // clients to modify it without changing the file. Arguably, it is better to require it to
70 // be defined by a user explicitly
71 #ifndef COSTTYPE
72 #define COSTTYPE unsigned char // Whatever is used...
73 #endif
74 
75 // potential defs
76 #define POT_HIGH 1.0e10 // unassigned cell potential
77 
78 // priority buffers
79 #define PRIORITYBUFSIZE 10000
80 
93 int create_nav_plan_astar(
94  const COSTTYPE * costmap, int nx, int ny,
95  int * goal, int * start,
96  float * plan, int nplan);
97 
103 class NavFn
104 {
105 public:
111  NavFn(int nx, int ny);
112 
113  ~NavFn();
114 
120  void setNavArr(int nx, int ny);
121  int nx, ny, ns;
130  void setCostmap(const COSTTYPE * cmap, bool isROS = true, bool allow_unknown = true);
131 
136  bool calcNavFnAstar();
137 
141  bool calcNavFnDijkstra(bool atStart = false);
142 
147  float * getPathX();
148 
153  float * getPathY();
154 
159  int getPathLen();
160 
165  float getLastPathCost();
166 
168  COSTTYPE * costarr;
169  float * potarr;
170  bool * pending;
171  int nobs;
174  int * pb1, * pb2, * pb3;
175  int * curP, * nextP, * overP;
176  int curPe, nextPe, overPe;
179  float curT;
180  float priInc;
189  void setGoal(int * goal);
190 
197  void setStart(int * start);
198 
199  int goal[2];
200  int start[2];
206  void initCost(int k, float v);
207 
214  void updateCell(int n);
215 
220  void updateCellAstar(int n);
221 
226  void setupNavFn(bool keepit = false);
227 
235  bool propNavFnDijkstra(int cycles, bool atStart = false);
236 
243  bool propNavFnAstar(int cycles);
246  float * gradx, * grady;
247  float * pathx, * pathy;
248  int npath;
249  int npathbuf;
258  int calcPath(int n, int * st = NULL);
259 
265  float gradCell(int n);
267  float pathStep;
271  // void display(void fn(NavFn * nav), int n = 100);
272  // int displayInt; /**< save second argument of display() above */
273  // void (* displayFn)(NavFn * nav); /**< display function itself */
274 
277  // void savemap(const char * fname);
278 };
279 
280 } // namespace nav2_navfn_planner
281 
282 #endif // NAV2_NAVFN_PLANNER__NAVFN_HPP_
Navigation function class. Holds buffers for costmap, navfn map. Maps are pixel-based....
Definition: navfn.hpp:104
int getPathLen()
Accessor for the length of a path.
Definition: navfn.cpp:324
bool propNavFnDijkstra(int cycles, bool atStart=false)
Run propagation for <cycles> iterations, or until start is reached using breadth-first Dijkstra metho...
Definition: navfn.cpp:576
float * getPathX()
Accessor for the x-coordinates of a path.
Definition: navfn.cpp:322
float gradCell(int n)
Calculate gradient at a cell.
Definition: navfn.cpp:928
void updateCell(int n)
Updates the cell at index n.
Definition: navfn.cpp:421
int calcPath(int n, int *st=NULL)
Calculates the path for at mose <n> cycles.
Definition: navfn.cpp:756
float getLastPathCost()
Gets the cost of the path found the last time a navigation function was computed.
Definition: navfn.cpp:738
bool calcNavFnDijkstra(bool atStart=false)
Caclulates the full navigation function using Dijkstra.
Definition: navfn.cpp:296
void updateCellAstar(int n)
Updates the cell at index n using the A* heuristic.
Definition: navfn.cpp:496
void initCost(int k, float v)
Initialize cell k with cost v for propagation.
Definition: navfn.cpp:400
void setNavArr(int nx, int ny)
Sets or resets the size of the map.
Definition: navfn.cpp:206
NavFn(int nx, int ny)
Constructs the planner.
Definition: navfn.cpp:111
void setCostmap(const COSTTYPE *cmap, bool isROS=true, bool allow_unknown=true)
Set up the cost array for the planner, usually from ROS.
Definition: navfn.cpp:246
void setupNavFn(bool keepit=false)
Set up navigation potential arrays for new propagation.
Definition: navfn.cpp:341
bool propNavFnAstar(int cycles)
Run propagation for <cycles> iterations, or until start is reached using the best-first A* method wit...
Definition: navfn.cpp:657
bool calcNavFnAstar()
Calculates a plan using the A* heuristic, returns true if one is found.
Definition: navfn.cpp:310
void setGoal(int *goal)
Sets the goal position for the planner. Note: the navigation cost field computed gives the cost to ge...
Definition: navfn.cpp:184
float * getPathY()
Accessor for the y-coordinates of a path.
Definition: navfn.cpp:323
void setStart(int *start)
Sets the start position for the planner. Note: the navigation cost field computed gives the cost to g...
Definition: navfn.cpp:192