#include <OccupancyGrid.h>
Occupancy grid definition. See GridStates for possible grid values.
Definition at line 56 of file OccupancyGrid.h.
karto::OccupancyGrid::OccupancyGrid | ( | kt_int32s | width, |
kt_int32s | height, | ||
const Vector2d & | rOffset, | ||
kt_double | resolution | ||
) |
Occupancy grid of given size
width | width |
height | height |
rOffset | offset |
resolution | resolution |
Definition at line 28 of file OccupancyGrid.cpp.
karto::OccupancyGrid::OccupancyGrid | ( | const OccupancyGrid & | ) | [private] |
kt_bool karto::OccupancyGrid::AddScan | ( | LocalizedLaserScan * | pScan, |
kt_bool | doUpdate = false |
||
) | [protected] |
Adds the scan's information to this grid's counters (optionally update the grid's cells' occupancy status)
pScan | laser scan |
doUpdate | whether to update the grid's cell's occupancy status |
Definition at line 142 of file OccupancyGrid.cpp.
OccupancyGrid * karto::OccupancyGrid::Clone | ( | ) | const |
void karto::OccupancyGrid::ComputeDimensions | ( | const LocalizedLaserScanList & | rScans, |
kt_double | resolution, | ||
kt_int32s & | rWidth, | ||
kt_int32s & | rHeight, | ||
Vector2d & | rOffset | ||
) | [static, protected] |
Calculates grid dimensions from localized laser scans and resolution
rScans | scans |
resolution | resolution |
rWidth | (output parameter) width |
rHeight | (output parameter) height |
rOffset | (output parameter) offset |
Definition at line 105 of file OccupancyGrid.cpp.
OccupancyGrid * karto::OccupancyGrid::CreateFromMapper | ( | OpenMapper * | pMapper, |
kt_double | resolution | ||
) | [static] |
Occupancy grid from the scans in the given mapper using the given resolution
pMapper | mapper |
resolution | resolution |
Definition at line 100 of file OccupancyGrid.cpp.
OccupancyGrid * karto::OccupancyGrid::CreateFromScans | ( | const LocalizedLaserScanList & | rScans, |
kt_double | resolution | ||
) | [static] |
Occupancy grid from the given scans using the given resolution
rScans | list of scans |
resolution | resolution |
Definition at line 84 of file OccupancyGrid.cpp.
OccupancyGrid * karto::OccupancyGrid::CreateFromScans | ( | const std::vector< SmartPointer< LocalizedRangeScan > > & | rScans, |
kt_double | resolution | ||
) | [static] |
Occupancy grid from the given scans using the given resolution
rScans | scans |
resolution | resolution |
Definition at line 72 of file OccupancyGrid.cpp.
void karto::OccupancyGrid::CreateFromScans | ( | const LocalizedLaserScanList & | rScans | ) | [protected, virtual] |
Grid<kt_int32u>* karto::OccupancyGrid::GetCellHitsCounts | ( | ) | [inline, protected] |
Gets grid of cell hit counts
Definition at line 144 of file OccupancyGrid.h.
Grid<kt_int32u>* karto::OccupancyGrid::GetCellPassCounts | ( | ) | [inline, protected] |
Get grid of cell pass counts
Definition at line 153 of file OccupancyGrid.h.
kt_bool karto::OccupancyGrid::IsFree | ( | const Vector2i & | rGridIndex | ) | const [inline] |
Checks if the given grid index is free
rGridIndex | grid index |
Definition at line 124 of file OccupancyGrid.h.
karto::OccupancyGrid::KARTO_RTTI | ( | ) | [private] |
Reimplemented from karto::Grid< kt_int8u >.
const OccupancyGrid& karto::OccupancyGrid::operator= | ( | const OccupancyGrid & | ) | [private] |
kt_double karto::OccupancyGrid::RayCast | ( | const Pose2 & | rPose2, |
kt_double | maxRange | ||
) | const |
Casts a ray from the given point (up to the given max range) and returns the distance to the closest obstacle
rPose2 | starting point |
maxRange | maximum range |
Definition at line 186 of file OccupancyGrid.cpp.
kt_bool karto::OccupancyGrid::RayTrace | ( | const Vector2d & | rWorldFrom, |
const Vector2d & | rWorldTo, | ||
kt_bool | isEndPointValid, | ||
kt_bool | doUpdate = false |
||
) | [protected] |
Traces a beam from the start position to the end position marking the bookkeeping arrays accordingly.
rWorldFrom | start position of beam |
rWorldTo | end position of beam |
isEndPointValid | is the reading within the range threshold? |
doUpdate | whether to update the cells' occupancy status immediately |
Definition at line 226 of file OccupancyGrid.cpp.
void karto::OccupancyGrid::Resize | ( | kt_int32s | width, |
kt_int32s | height | ||
) | [protected, virtual] |
Resizes the grid (deletes all old data)
width | new width |
height | new height |
Reimplemented from karto::Grid< kt_int8u >.
Definition at line 296 of file OccupancyGrid.cpp.
void karto::OccupancyGrid::UpdateCell | ( | kt_int8u * | pCell, |
kt_int32u | cellPassCnt, | ||
kt_int32u | cellHitCnt | ||
) | [protected] |
Updates a single cell's value based on the given counters
pCell | cell |
cellPassCnt | cell pass count |
cellHitCnt | cell hit count |
Definition at line 260 of file OccupancyGrid.cpp.
void karto::OccupancyGrid::UpdateGrid | ( | ) | [protected] |
Updates the grid based on the values in m_pCellHitsCnt and m_pCellPassCnt
Definition at line 277 of file OccupancyGrid.cpp.
friend class CellUpdater [friend] |
Definition at line 61 of file OccupancyGrid.h.
friend class IncrementalOccupancyGrid [friend] |
Definition at line 62 of file OccupancyGrid.h.
SmartPointer< Grid<kt_int32u> > karto::OccupancyGrid::m_pCellHitsCnt [protected] |
Counters of number of times a beam ended at a cell
Definition at line 223 of file OccupancyGrid.h.
SmartPointer< Grid<kt_int32u> > karto::OccupancyGrid::m_pCellPassCnt [protected] |
Counters of number of times a beam passed through a cell
Definition at line 218 of file OccupancyGrid.h.
CellUpdater* karto::OccupancyGrid::m_pCellUpdater [private] |
Definition at line 226 of file OccupancyGrid.h.
Definition at line 234 of file OccupancyGrid.h.
Definition at line 237 of file OccupancyGrid.h.