BFS3D Class Reference

#include <bfs_3d.h>

List of all members.

Public Member Functions

 BFS3D (int dim_x, int dim_y, int dim_z, int radius, int cost_per_cell)
 constructor
void configDistanceField (bool enable, const distance_field::PropagationDistanceField *df)
 configure the distance field object that will be used as the occupancy grid.
int getDist (int x, int y, int z)
 get distance to the goal in cells from (x,y,z)
bool getShortestPath (std::vector< short unsigned int > start, std::vector< std::vector< int > > &path)
 compute the shortest path from the specified cell to the nearest goal.
void init ()
 initialize the occupancy grid (required if not using a distance field to describe the environment).
void printConfig (FILE *fOut)
 output configuration values for debugging
void printCostToGoal ()
 for debugging - print the cost to goal from each cell
void printGrid ()
 for debugging - print the occupancy grid to the terminal (beware poor formatting)
bool runBFS ()
 compute a breadth first search from every cell to the goal(s)
bool setGoal (std::vector< short unsigned int > goal)
 set a single goal
bool setGoals (std::vector< std::vector< short unsigned int > > goals)
 set a list of goals
 ~BFS3D ()
 destructor

Private Member Functions

void create3DStateSpace (State3D ****statespace3D)
void delete3DStateSpace (State3D ****statespace3D)
void initializeState3D (State3D *state, short unsigned int x, short unsigned int y, short unsigned int z)
bool isGoal (const std::vector< int > &state)
bool isValidCell (const int x, const int y, const int z)
void reInitializeState3D (State3D *state)
void search3DwithQueue (State3D ***statespace)
int xyzToIndex (int x, int y, int z)

Private Attributes

int cost_1_move_
int cost_sqrt2_move_
int cost_sqrt3_move_
const
distance_field::PropagationDistanceField * 
df_
short unsigned int dimX_
short unsigned int dimY_
short unsigned int dimZ_
std::vector< int > dist_
int dist_length_
bool enable_df_
std::vector< std::vector
< short unsigned int > > 
goal_
unsigned char *** grid3D_
short unsigned int radius_
double radius_m_

Detailed Description

Definition at line 65 of file bfs_3d.h.


Constructor & Destructor Documentation

BFS3D::BFS3D ( int  dim_x,
int  dim_y,
int  dim_z,
int  radius,
int  cost_per_cell 
)

constructor

Parameters:
dim_x dim_x in cells
dim_y dim_y of grid in cells
dim_z dim_z of grid in cells
radius radius in cells of the point robot
cost_per_cell cost of traversing one cell in the grid
Author:
Benjamin Cohen, Maxim Likhachev

Definition at line 35 of file bfs_3d.cpp.

BFS3D::~BFS3D (  ) 

destructor

Definition at line 58 of file bfs_3d.cpp.


Member Function Documentation

void BFS3D::configDistanceField ( bool  enable,
const distance_field::PropagationDistanceField *  df 
)

configure the distance field object that will be used as the occupancy grid.

Parameters:
enable enable or disable the distance field
df pointer to distance field to use

Definition at line 391 of file bfs_3d.cpp.

void BFS3D::create3DStateSpace ( State3D ****  statespace3D  )  [private]

Definition at line 154 of file bfs_3d.cpp.

void BFS3D::delete3DStateSpace ( State3D ****  statespace3D  )  [private]

Definition at line 173 of file bfs_3d.cpp.

int BFS3D::getDist ( int  x,
int  y,
int  z 
) [inline]

get distance to the goal in cells from (x,y,z)

Definition at line 169 of file bfs_3d.h.

bool BFS3D::getShortestPath ( std::vector< short unsigned int >  start,
std::vector< std::vector< int > > &  path 
)

compute the shortest path from the specified cell to the nearest goal.

Parameters:
start a 3x1 vector containing the {x,y,z} start position
path an nx3 vector containing the waypoints
Returns:
true if it was a success and false otherwise

Definition at line 318 of file bfs_3d.cpp.

void BFS3D::init (  ) 

initialize the occupancy grid (required if not using a distance field to describe the environment).

Definition at line 73 of file bfs_3d.cpp.

void BFS3D::initializeState3D ( State3D state,
short unsigned int  x,
short unsigned int  y,
short unsigned int  z 
) [private]

Definition at line 145 of file bfs_3d.cpp.

bool BFS3D::isGoal ( const std::vector< int > &  state  )  [private]

Definition at line 308 of file bfs_3d.cpp.

bool BFS3D::isValidCell ( const int  x,
const int  y,
const int  z 
) [private]

Definition at line 400 of file bfs_3d.cpp.

void BFS3D::printConfig ( FILE *  fOut  ) 

output configuration values for debugging

Definition at line 415 of file bfs_3d.cpp.

void BFS3D::printCostToGoal (  ) 

for debugging - print the cost to goal from each cell

Definition at line 436 of file bfs_3d.cpp.

void BFS3D::printGrid (  ) 

for debugging - print the occupancy grid to the terminal (beware poor formatting)

Definition at line 422 of file bfs_3d.cpp.

void BFS3D::reInitializeState3D ( State3D state  )  [private]

Definition at line 139 of file bfs_3d.cpp.

bool BFS3D::runBFS (  ) 

compute a breadth first search from every cell to the goal(s)

Returns:
true if it succeed and false otherwise

Definition at line 191 of file bfs_3d.cpp.

void BFS3D::search3DwithQueue ( State3D ***  statespace  )  [private]

Definition at line 219 of file bfs_3d.cpp.

bool BFS3D::setGoal ( std::vector< short unsigned int >  goal  ) 

set a single goal

Parameters:
goal a 3x1 vector {x,y,z}
Returns:
true if success, false if goal is invalid

Definition at line 91 of file bfs_3d.cpp.

bool BFS3D::setGoals ( std::vector< std::vector< short unsigned int > >  goals  ) 

set a list of goals

Parameters:
goal an nx3 vector {x,y,z}
Returns:
true if success, false if all goals are invalid

Definition at line 109 of file bfs_3d.cpp.

int BFS3D::xyzToIndex ( int  x,
int  y,
int  z 
) [inline, private]

Definition at line 157 of file bfs_3d.h.


Member Data Documentation

int BFS3D::cost_1_move_ [private]

Definition at line 135 of file bfs_3d.h.

int BFS3D::cost_sqrt2_move_ [private]

Definition at line 136 of file bfs_3d.h.

int BFS3D::cost_sqrt3_move_ [private]

Definition at line 137 of file bfs_3d.h.

const distance_field::PropagationDistanceField* BFS3D::df_ [private]

Definition at line 140 of file bfs_3d.h.

short unsigned int BFS3D::dimX_ [private]

Definition at line 126 of file bfs_3d.h.

short unsigned int BFS3D::dimY_ [private]

Definition at line 127 of file bfs_3d.h.

short unsigned int BFS3D::dimZ_ [private]

Definition at line 128 of file bfs_3d.h.

std::vector<int> BFS3D::dist_ [private]

Definition at line 145 of file bfs_3d.h.

int BFS3D::dist_length_ [private]

Definition at line 144 of file bfs_3d.h.

bool BFS3D::enable_df_ [private]

Definition at line 139 of file bfs_3d.h.

std::vector<std::vector<short unsigned int> > BFS3D::goal_ [private]

Definition at line 133 of file bfs_3d.h.

unsigned char*** BFS3D::grid3D_ [private]

Definition at line 142 of file bfs_3d.h.

short unsigned int BFS3D::radius_ [private]

Definition at line 130 of file bfs_3d.h.

double BFS3D::radius_m_ [private]

Definition at line 131 of file bfs_3d.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Defines


sbpl_arm_planner
Author(s): Benjamin Cohen/bcohen@seas.upenn.edu
autogenerated on Wed Feb 29 11:46:20 2012