Public Member Functions | Public Attributes
navfn::NavFn Class Reference

Navigation function class. Holds buffers for costmap, navfn map. Maps are pixel-based. Origin is upper left, x is right, y is down. More...

#include <navfn.h>

List of all members.

Public Member Functions

bool calcNavFnAstar ()
 Calculates a plan using the A* heuristic, returns true if one is found.
bool calcNavFnDijkstra (bool atStart=false)
 Caclulates the full navigation function using Dijkstra.
int calcPath (int n, int *st=NULL)
 Calculates the path for at mose <n> cycles.
void display (void fn(NavFn *nav), int n=100)
float getLastPathCost ()
 Gets the cost of the path found the last time a navigation function was computed.
int getPathLen ()
 Accessor for the length of a path.
float * getPathX ()
 Accessor for the x-coordinates of a path.
float * getPathY ()
 Accessor for the y-coordinates of a path.
float gradCell (int n)
void initCost (int k, float v)
 Initialize cell k with cost v for propagation.
 NavFn (int nx, int ny)
 Constructs the planner.
bool propNavFnAstar (int cycles)
 Run propagation for <cycles> iterations, or until start is reached using the best-first A* method with Euclidean distance heuristic.
bool propNavFnDijkstra (int cycles, bool atStart=false)
 Run propagation for <cycles> iterations, or until start is reached using breadth-first Dijkstra method.
void savemap (const char *fname)
void setCostmap (const COSTTYPE *cmap, bool isROS=true, bool allow_unknown=true)
 Set up the cost array for the planner, usually from ROS.
void setGoal (int *goal)
 Sets the goal position for the planner. Note: the navigation cost field computed gives the cost to get to a given point from the goal, not from the start.
void setNavArr (int nx, int ny)
 Sets or resets the size of the map.
void setObs ()
void setStart (int *start)
 Sets the start position for the planner. Note: the navigation cost field computed gives the cost to get to a given point from the goal, not from the start.
void setupNavFn (bool keepit=false)
void updateCell (int n)
 Updates the cell at index n.
void updateCellAstar (int n)
 Updates the cell at index n using the A* heuristic.
 ~NavFn ()

Public Attributes

COSTTYPEcostarr
int * curP
int curPe
float curT
void(* displayFn )(NavFn *nav)
int displayInt
int goal [2]
float * gradx
float * grady
float last_path_cost_
int * nextP
int nextPe
int nobs
int npath
int npathbuf
int ns
int nx
int ny
COSTTYPEobsarr
int * overP
int overPe
float pathStep
float * pathx
float * pathy
int * pb1
int * pb2
int * pb3
bool * pending
float * potarr
float priInc
int start [2]

Detailed Description

Navigation function class. Holds buffers for costmap, navfn map. Maps are pixel-based. Origin is upper left, x is right, y is down.

Definition at line 106 of file navfn.h.


Constructor & Destructor Documentation

navfn::NavFn::NavFn ( int  nx,
int  ny 
)

Constructs the planner.

Parameters:
nxThe x size of the map
nyThe y size of the map

Definition at line 110 of file navfn.cpp.

Definition at line 143 of file navfn.cpp.


Member Function Documentation

Calculates a plan using the A* heuristic, returns true if one is found.

Returns:
True if a plan is found, false otherwise calculates a plan, returns true if found

Definition at line 331 of file navfn.cpp.

bool navfn::NavFn::calcNavFnDijkstra ( bool  atStart = false)

Caclulates the full navigation function using Dijkstra.

calculates the full navigation function

Definition at line 296 of file navfn.cpp.

int navfn::NavFn::calcPath ( int  n,
int *  st = NULL 
)

Calculates the path for at mose <n> cycles.

Parameters:
nThe maximum number of cycles to run for
Returns:
The lenght of the path found calculates path for at most <n> cycles, returns path length, 0 if none

Definition at line 830 of file navfn.cpp.

void navfn::NavFn::display ( void   fnNavFn *nav,
int  n = 100 
)

display callback <n> is the number of cycles between updates

Definition at line 1059 of file navfn.cpp.

Gets the cost of the path found the last time a navigation function was computed.

Returns:
The cost of the last path found Return cost of path found the last time A* was called

Definition at line 812 of file navfn.cpp.

Accessor for the length of a path.

Returns:
The length of a path length of path, 0 if not found

Definition at line 360 of file navfn.cpp.

Accessor for the x-coordinates of a path.

Returns:
The x-coordinates of a path x-coordinates of path

Definition at line 358 of file navfn.cpp.

Accessor for the y-coordinates of a path.

Returns:
The y-coordinates of a path y-coordinates of path

Definition at line 359 of file navfn.cpp.

float navfn::NavFn::gradCell ( int  n)

calculates gradient at cell <n>, returns norm

Definition at line 1000 of file navfn.cpp.

void navfn::NavFn::initCost ( int  k,
float  v 
)

Initialize cell k with cost v for propagation.

Parameters:
kthe cell to initialize
vthe cost to give to the cell initialize cell <k> with cost <v>, for propagation

Definition at line 462 of file navfn.cpp.

bool navfn::NavFn::propNavFnAstar ( int  cycles)

Run propagation for <cycles> iterations, or until start is reached using the best-first A* method with Euclidean distance heuristic.

Parameters:
cyclesThe maximum number of iterations to run for
Returns:
true if the start point is reached returns true if start point found

Definition at line 736 of file navfn.cpp.

bool navfn::NavFn::propNavFnDijkstra ( int  cycles,
bool  atStart = false 
)

Run propagation for <cycles> iterations, or until start is reached using breadth-first Dijkstra method.

Parameters:
cyclesThe maximum number of iterations to run for
atStartWhether or not to stop when the start point is reached
Returns:
true if the start point is reached returns true if start point found or full prop

Definition at line 659 of file navfn.cpp.

void navfn::NavFn::savemap ( const char *  fname)

save costmap write out costmap and start/goal states as fname.pgm and fname.txt

Definition at line 1072 of file navfn.cpp.

void navfn::NavFn::setCostmap ( const COSTTYPE cmap,
bool  isROS = true,
bool  allow_unknown = true 
)

Set up the cost array for the planner, usually from ROS.

Parameters:
cmapThe costmap
isROSWhether or not the costmap is coming in in ROS format
allow_unknownWhether or not the planner should be allowed to plan through unknown space sets up the cost map

Definition at line 234 of file navfn.cpp.

void navfn::NavFn::setGoal ( int *  goal)

Sets the goal position for the planner. Note: the navigation cost field computed gives the cost to get to a given point from the goal, not from the start.

goal and start positions

Parameters:
goalthe goal position

Definition at line 175 of file navfn.cpp.

void navfn::NavFn::setNavArr ( int  nx,
int  ny 
)

Sets or resets the size of the map.

Parameters:
nxThe x size of the map
nyThe y size of the map sets or resets the size of the map

Definition at line 195 of file navfn.cpp.

simple obstacle for testing

Definition at line 368 of file navfn.cpp.

void navfn::NavFn::setStart ( int *  start)

Sets the start position for the planner. Note: the navigation cost field computed gives the cost to get to a given point from the goal, not from the start.

Parameters:
startthe start position

Definition at line 183 of file navfn.cpp.

void navfn::NavFn::setupNavFn ( bool  keepit = false)

resets all nav fn arrays for propagation

Definition at line 408 of file navfn.cpp.

void navfn::NavFn::updateCell ( int  n) [inline]

Updates the cell at index n.

propagation

Parameters:
nThe index to update updates the cell at index <n>

Definition at line 483 of file navfn.cpp.

void navfn::NavFn::updateCellAstar ( int  n) [inline]

Updates the cell at index n using the A* heuristic.

Parameters:
nThe index to update updates the cell at index <n>, uses A* heuristic

Definition at line 568 of file navfn.cpp.


Member Data Documentation

cost array in 2D configuration space

Definition at line 171 of file navfn.h.

Definition at line 178 of file navfn.h.

Definition at line 179 of file navfn.h.

block priority thresholds current threshold

Definition at line 182 of file navfn.h.

display function itself

Definition at line 262 of file navfn.h.

save second argument of display() above

Definition at line 261 of file navfn.h.

Definition at line 198 of file navfn.h.

gradient and paths

Definition at line 241 of file navfn.h.

gradient arrays, size of potential array

Definition at line 241 of file navfn.h.

Holds the cost of the path found the last time A* was called

Definition at line 246 of file navfn.h.

Definition at line 178 of file navfn.h.

Definition at line 179 of file navfn.h.

number of obstacle cells

Definition at line 174 of file navfn.h.

number of path points

Definition at line 243 of file navfn.h.

size of pathx, pathy buffers

Definition at line 244 of file navfn.h.

size of grid, in pixels

Definition at line 124 of file navfn.h.

Definition at line 124 of file navfn.h.

Definition at line 124 of file navfn.h.

cell arrays obstacle array, to be expanded to cost array

Definition at line 170 of file navfn.h.

priority buffer block ptrs

Definition at line 178 of file navfn.h.

end points of arrays

Definition at line 179 of file navfn.h.

step size for following gradient

Definition at line 257 of file navfn.h.

Definition at line 242 of file navfn.h.

path points, as subpixel cell coordinates

Definition at line 242 of file navfn.h.

block priority buffers

Definition at line 177 of file navfn.h.

Definition at line 177 of file navfn.h.

storage buffers for priority blocks

Definition at line 177 of file navfn.h.

pending cells during propagation

Definition at line 173 of file navfn.h.

potential array, navigation function potential

Definition at line 172 of file navfn.h.

priority threshold increment

Definition at line 183 of file navfn.h.

Definition at line 199 of file navfn.h.


The documentation for this class was generated from the following files:


navfn
Author(s): Kurt Konolige, Eitan Marder-Eppstein
autogenerated on Mon Oct 6 2014 02:46:56