Public Member Functions | Private Member Functions | Private Attributes
VisualLanes Class Reference

#include <VisualLanes.h>

List of all members.

Public Member Functions

void addMapLane (double w1lat, double w1long, double w2lat, double w2long, double w3lat, double w3long, double laneWidth)
void addMapLane (std::vector< double > ranges)
void addPoly (double x1, double x2, double x3, double x4, double y1, double y2, double y3, double y4, bool is_stop)
void addSickScan (std::vector< double > ranges)
void addTrace (double w1lat, double w1long, double w2lat, double w2long)
void clear ()
double getPhysicalSize ()
std::vector< float > * getPose ()
void gpsEnabled (bool onOff)
void initialize (double x, double y, double theta)
std::pair< double, double > * isPathClear (double x, double y)
std::pair< double, double > * laserScan (double x, double y)
std::pair< double, double > nearestClearPath (std::pair< double, double > obstacle, std::pair< double, double > original)
void savePGM (const char *filename)
void setCellShift (int shift)
void setLaserRange (float range)
void setPosition (double x, double y, double theta)
void setThreshold (int threshold)
cell value (int x, int y)
 VisualLanes (double physical_size, int resolution)
 ~VisualLanes ()

Private Member Functions

cellat (int x, int y)
cellatgoal (int x, int y)
std::pair< int, int > * cellLighten (int x, int y)
std::pair< int, int > * cellLightenDebug (int x, int y)
std::pair< int, int > * cellOccupied (int x, int y)
std::pair< int, int > * cellOccupiedDebug (int x, int y)
std::pair< int, int > * cellOccupiedRelative (int x, int y)
void clearBottom ()
void clearLeft ()
void clearRight ()
void clearTop ()
std::pair< int, int > * drawPointB (int x, int y)
std::pair< int, int > * drawPointW (int x, int y)
void lighten (int x, int y)
std::pair< int, int > * line (int x0, int y0, int x1, int y1, std::pair< int, int > *(VisualLanes::*_fp)(int, int))
void padObstacles ()
bool valid (int x, int y)

Private Attributes

cell ** _m
double _physical_size
int _resolution
int _shift
double _theta
int _threshold
double _x
int _x_offset
double _y
int _y_offset
int count
bool gpsOnOff
float laser_range
double rX
double rY
bool scan_off_bottom_side
bool scan_off_left_side
bool scan_off_right_side
bool scan_off_top_side

Detailed Description

Definition at line 37 of file VisualLanes.h.


Constructor & Destructor Documentation

VisualLanes::VisualLanes ( double  physical_size,
int  resolution 
)

Definition at line 9 of file VisualLanes.cc.

Definition at line 33 of file VisualLanes.cc.


Member Function Documentation

void VisualLanes::addMapLane ( double  w1lat,
double  w1long,
double  w2lat,
double  w2long,
double  w3lat,
double  w3long,
double  laneWidth 
)

Definition at line 796 of file VisualLanes.cc.

void VisualLanes::addMapLane ( std::vector< double >  ranges)

Definition at line 872 of file VisualLanes.cc.

void VisualLanes::addPoly ( double  x1,
double  x2,
double  x3,
double  x4,
double  y1,
double  y2,
double  y3,
double  y4,
bool  is_stop 
)

Definition at line 941 of file VisualLanes.cc.

void VisualLanes::addSickScan ( std::vector< double >  ranges)

The function takes a 180 degree sick laser scan and updates the occupancy grid.

Definition at line 192 of file VisualLanes.cc.

void VisualLanes::addTrace ( double  w1lat,
double  w1long,
double  w2lat,
double  w2long 
)

Definition at line 971 of file VisualLanes.cc.

cell * VisualLanes::at ( int  x,
int  y 
) [private]

Definition at line 765 of file VisualLanes.cc.

cell * VisualLanes::atgoal ( int  x,
int  y 
) [private]

Definition at line 757 of file VisualLanes.cc.

std::pair< int, int > * VisualLanes::cellLighten ( int  x,
int  y 
) [private]

This is one of many private functions that are intended to be feed into the generic line trace function, if you need to use it, the arguements are.. number of args, followed by x and y. don't really need number of args... but its there so I can get to the parameters I want.

Definition at line 309 of file VisualLanes.cc.

std::pair< int, int > * VisualLanes::cellLightenDebug ( int  x,
int  y 
) [private]

Definition at line 364 of file VisualLanes.cc.

std::pair< int, int > * VisualLanes::cellOccupied ( int  x,
int  y 
) [private]

If the cell is occupied then return the std::pair<int,int> containing the x and y that refer to the occupancy grid point.

Note, don't forget that the pair will be casted to void* before return!!

Definition at line 327 of file VisualLanes.cc.

std::pair< int, int > * VisualLanes::cellOccupiedDebug ( int  x,
int  y 
) [private]

Definition at line 346 of file VisualLanes.cc.

std::pair< int, int > * VisualLanes::cellOccupiedRelative ( int  x,
int  y 
) [private]

Definition at line 476 of file VisualLanes.cc.

void VisualLanes::clear ( void  )

The function clears the occupancy grid and resets all values in the grid back to the default occupancy.

Definition at line 41 of file VisualLanes.cc.

void VisualLanes::clearBottom ( ) [private]

Definition at line 67 of file VisualLanes.cc.

void VisualLanes::clearLeft ( ) [private]

Definition at line 89 of file VisualLanes.cc.

void VisualLanes::clearRight ( ) [private]

Definition at line 82 of file VisualLanes.cc.

void VisualLanes::clearTop ( ) [private]

Definition at line 75 of file VisualLanes.cc.

std::pair< int, int > * VisualLanes::drawPointB ( int  x,
int  y 
) [private]

Definition at line 983 of file VisualLanes.cc.

std::pair< int, int > * VisualLanes::drawPointW ( int  x,
int  y 
) [private]

Definition at line 994 of file VisualLanes.cc.

double VisualLanes::getPhysicalSize ( ) [inline]

Definition at line 128 of file VisualLanes.h.

std::vector< float > * VisualLanes::getPose ( )

Definition at line 181 of file VisualLanes.cc.

void VisualLanes::gpsEnabled ( bool  onOff) [inline]

Definition at line 44 of file VisualLanes.h.

void VisualLanes::initialize ( double  x,
double  y,
double  theta 
)

Standard initialization function that sets up the robots initial position.

Recommended use, is at start up.

Definition at line 50 of file VisualLanes.cc.

std::pair< double, double > * VisualLanes::isPathClear ( double  x,
double  y 
)

If path is clear, then the function returns an empty cell else the function returns the first cell in which it hits an obstacle

Note, this function's input is a point relative to the odometry of the car, I need to write a function for converting GPS to local odometry.

Before using this function, you must use setThreshold(int threshold) to set the specified threshold for a cell to be occupied.

Definition at line 524 of file VisualLanes.cc.

std::pair< double, double > * VisualLanes::laserScan ( double  x,
double  y 
)

Definition at line 494 of file VisualLanes.cc.

void VisualLanes::lighten ( int  x,
int  y 
) [private]
std::pair< int, int > * VisualLanes::line ( int  x0,
int  y0,
int  x1,
int  y1,
std::pair< int, int > *(VisualLanes::*)(int, int)  _fp 
) [private]

Takes in a function pointer to a function that opperates on x and y cell. The x and y are cells that must be reached by by a line trace.

Definition at line 380 of file VisualLanes.cc.

std::pair< double, double > VisualLanes::nearestClearPath ( std::pair< double, double >  obstacle,
std::pair< double, double >  original 
)

Beware the function is still experimental and definitely needs some work!!

The function should return a intermediate point to a goal point, note before using this function, you must set the cell shift size, by using setCellShift(int shift) first.

Definition at line 639 of file VisualLanes.cc.

void VisualLanes::padObstacles ( ) [private]

Definition at line 471 of file VisualLanes.cc.

void VisualLanes::savePGM ( const char *  filename)

This function saves the current occupancy grid to a specified .pgm file.

Definition at line 444 of file VisualLanes.cc.

void VisualLanes::setCellShift ( int  shift)

Definition at line 630 of file VisualLanes.cc.

void VisualLanes::setLaserRange ( float  range) [inline]

Definition at line 126 of file VisualLanes.h.

void VisualLanes::setPosition ( double  x,
double  y,
double  theta 
)

This function updates the robot's position in the occupancy grid, I do not know how this will behave if given a GPS coordinate.

The function is generally used with respect to the imu, but it is very possible to use it with the GPS player position info as well.

Definition at line 96 of file VisualLanes.cc.

void VisualLanes::setThreshold ( int  threshold)

Definition at line 299 of file VisualLanes.cc.

bool VisualLanes::valid ( int  x,
int  y 
) [private]

Definition at line 437 of file VisualLanes.cc.

cell VisualLanes::value ( int  x,
int  y 
)

Since the robot behaves in local coordinates, if you pass in an x and y with respect to the robot, it should return the value of that cell. (Note only with respect to the robot)

If you need to check a cell for occupancy, its better to use is path clear, Since it will check all sells in between and return the point it believes to have a collision based on the set threshold.

Definition at line 430 of file VisualLanes.cc.


Member Data Documentation

cell** VisualLanes::_m [private]

Definition at line 151 of file VisualLanes.h.

double VisualLanes::_physical_size [private]

Definition at line 152 of file VisualLanes.h.

int VisualLanes::_resolution [private]

Definition at line 153 of file VisualLanes.h.

int VisualLanes::_shift [private]

Definition at line 161 of file VisualLanes.h.

double VisualLanes::_theta [private]

Definition at line 156 of file VisualLanes.h.

int VisualLanes::_threshold [private]

Definition at line 160 of file VisualLanes.h.

double VisualLanes::_x [private]

Definition at line 154 of file VisualLanes.h.

int VisualLanes::_x_offset [private]

Definition at line 157 of file VisualLanes.h.

double VisualLanes::_y [private]

Definition at line 155 of file VisualLanes.h.

int VisualLanes::_y_offset [private]

Definition at line 158 of file VisualLanes.h.

int VisualLanes::count [private]

Definition at line 168 of file VisualLanes.h.

Definition at line 176 of file VisualLanes.h.

float VisualLanes::laser_range [private]

Definition at line 173 of file VisualLanes.h.

double VisualLanes::rX [private]

Definition at line 170 of file VisualLanes.h.

double VisualLanes::rY [private]

Definition at line 171 of file VisualLanes.h.

Definition at line 165 of file VisualLanes.h.

Definition at line 164 of file VisualLanes.h.

Definition at line 163 of file VisualLanes.h.

Definition at line 166 of file VisualLanes.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


art_map
Author(s): David Li, Patrick Beeson, Bartley Gillen, Tarun Nimmagadda, Mickey Ristroph, Michael Quinlan, Jack O'Quin
autogenerated on Tue Sep 24 2013 10:41:51