Occupancy grid mapping.
More...
#include <mapping.hpp>
|
void | lineDiag (GridMap &grid, int x0, int y0, int x1, int y1) const |
| Bresenham's algorithm for drawing lines at +/- 45 deg. More...
|
|
void | lineHigh (GridMap &grid, int x0, int y0, int x1, int y1) const |
| Bresenham's algorithm for drawing lines upward. More...
|
|
void | lineLow (GridMap &grid, int x0, int y0, int x1, int y1) const |
| Bresenham's algorithm for drawing lines downward. More...
|
|
void | rayTrace (GridMap &grid, int x0, int y0, int x1, int y1) const |
| Bresenham's line algorithm on occupancy map. More...
|
|
void | updateCell (GridMap &grid, int x, int y, double log) const |
| Update grid cell probability of occupancy. More...
|
|
Occupancy grid mapping.
Definition at line 52 of file mapping.hpp.
◆ OccupancyMapper()
ergodic_exploration::OccupancyMapper::OccupancyMapper |
( |
const mat & |
Tbs | ) |
|
Constructor.
- Parameters
-
Tbs | - transformation from base link to frame of laser scanner |
Definition at line 66 of file mapping.cpp.
◆ lineDiag()
void ergodic_exploration::OccupancyMapper::lineDiag |
( |
GridMap & |
grid, |
|
|
int |
x0, |
|
|
int |
y0, |
|
|
int |
x1, |
|
|
int |
y1 |
|
) |
| const |
|
private |
Bresenham's algorithm for drawing lines at +/- 45 deg.
- Parameters
-
grid[out] | - current map |
x0 | - line starting x position |
y0 | - line starting y position |
x1 | - line ending x position |
y1 | - line ending y position |
x is the jth column and u is the ith row in the grid
Definition at line 321 of file mapping.cpp.
◆ lineHigh()
void ergodic_exploration::OccupancyMapper::lineHigh |
( |
GridMap & |
grid, |
|
|
int |
x0, |
|
|
int |
y0, |
|
|
int |
x1, |
|
|
int |
y1 |
|
) |
| const |
|
private |
Bresenham's algorithm for drawing lines upward.
- Parameters
-
grid[out] | - current map |
x0 | - line starting x position |
y0 | - line starting y position |
x1 | - line ending x position |
y1 | - line ending y position |
x is the jth column and u is the ith row in the grid
Definition at line 283 of file mapping.cpp.
◆ lineLow()
void ergodic_exploration::OccupancyMapper::lineLow |
( |
GridMap & |
grid, |
|
|
int |
x0, |
|
|
int |
y0, |
|
|
int |
x1, |
|
|
int |
y1 |
|
) |
| const |
|
private |
Bresenham's algorithm for drawing lines downward.
- Parameters
-
grid[out] | - current map |
x0 | - line starting x position |
y0 | - line starting y position |
x1 | - line ending x position |
y1 | - line ending y position |
x is the jth column and u is the ith row in the grid
Definition at line 245 of file mapping.cpp.
◆ rayTrace()
void ergodic_exploration::OccupancyMapper::rayTrace |
( |
GridMap & |
grid, |
|
|
int |
x0, |
|
|
int |
y0, |
|
|
int |
x1, |
|
|
int |
y1 |
|
) |
| const |
|
private |
Bresenham's line algorithm on occupancy map.
- Parameters
-
grid[out] | - current map |
x0 | - line starting x position |
y0 | - line starting y position |
x1 | - line ending x position |
y1 | - line ending y position |
Ray tracing is used to find the grid cells in free space. Where x is the jth column and u is the ith row in the grid.
Definition at line 130 of file mapping.cpp.
◆ updateCell()
void ergodic_exploration::OccupancyMapper::updateCell |
( |
GridMap & |
grid, |
|
|
int |
x, |
|
|
int |
y, |
|
|
double |
log |
|
) |
| const |
|
private |
Update grid cell probability of occupancy.
- Parameters
-
grid[out] | - current map |
x | - grid cell x position |
y | - grid cell y position |
log | - either log_odds_occ_ or log_odds_free_ |
x is the jth column and u is the ith row in the grid
Definition at line 341 of file mapping.cpp.
◆ updateMap()
bool ergodic_exploration::OccupancyMapper::updateMap |
( |
GridMap & |
grid, |
|
|
const sensor_msgs::LaserScan::ConstPtr & |
scan, |
|
|
const vec & |
pose |
|
) |
| |
Update the occupancy grid map.
- Parameters
-
grid[out] | - current map |
scan | - laser scan |
pose | - robot pose in map frame |
- Returns
- true if map is updated
Definition at line 77 of file mapping.cpp.
◆ log_odds_free_
double ergodic_exploration::OccupancyMapper::log_odds_free_ |
|
private |
◆ log_odds_occ_
double ergodic_exploration::OccupancyMapper::log_odds_occ_ |
|
private |
◆ log_odds_prior_
double ergodic_exploration::OccupancyMapper::log_odds_prior_ |
|
private |
◆ prior_
double ergodic_exploration::OccupancyMapper::prior_ |
|
private |
◆ prob_free_
double ergodic_exploration::OccupancyMapper::prob_free_ |
|
private |
◆ prob_occ_
double ergodic_exploration::OccupancyMapper::prob_occ_ |
|
private |
◆ Tbs_
mat ergodic_exploration::OccupancyMapper::Tbs_ |
|
private |
The documentation for this class was generated from the following files: