#include <Karto.h>

| Public Member Functions | |
| OccupancyGrid * | Clone () const | 
| virtual kt_bool | IsFree (const Vector2< kt_int32s > &rPose) const | 
| OccupancyGrid (kt_int32s width, kt_int32s height, const Vector2< kt_double > &rOffset, kt_double resolution) | |
| virtual kt_double | RayCast (const Pose2 &rPose2, kt_double maxRange) const | 
| void | SetMinPassThrough (kt_int32u count) | 
| void | SetOccupancyThreshold (kt_double thresh) | 
| virtual | ~OccupancyGrid () | 
| Static Public Member Functions | |
| static OccupancyGrid * | CreateFromScans (const LocalizedRangeScanVector &rScans, kt_double resolution) | 
| Protected Member Functions | |
| virtual kt_bool | AddScan (LocalizedRangeScan *pScan, kt_bool doUpdate=false) | 
| virtual void | CreateFromScans (const LocalizedRangeScanVector &rScans) | 
| virtual Grid< kt_int32u > * | GetCellHitsCounts () | 
| virtual Grid< kt_int32u > * | GetCellPassCounts () | 
| virtual kt_bool | RayTrace (const Vector2< kt_double > &rWorldFrom, const Vector2< kt_double > &rWorldTo, kt_bool isEndPointValid, kt_bool doUpdate=false) | 
| virtual void | Resize (kt_int32s width, kt_int32s height) | 
| virtual void | Update () | 
| virtual void | UpdateCell (kt_int8u *pCell, kt_int32u cellPassCnt, kt_int32u cellHitCnt) | 
| Static Protected Member Functions | |
| static void | ComputeDimensions (const LocalizedRangeScanVector &rScans, kt_double resolution, kt_int32s &rWidth, kt_int32s &rHeight, Vector2< kt_double > &rOffset) | 
| Protected Attributes | |
| Grid< kt_int32u > * | m_pCellHitsCnt | 
| Grid< kt_int32u > * | m_pCellPassCnt | 
| Private Member Functions | |
| OccupancyGrid (const OccupancyGrid &) | |
| const OccupancyGrid & | operator= (const OccupancyGrid &) | 
| Private Attributes | |
| CellUpdater * | m_pCellUpdater | 
| Parameter< kt_int32u > * | m_pMinPassThrough | 
| Parameter< kt_double > * | m_pOccupancyThreshold | 
| Friends | |
| class | CellUpdater | 
| class | IncrementalOccupancyGrid | 
Occupancy grid definition. See GridStates for possible grid values.
| virtual karto::OccupancyGrid::~OccupancyGrid | ( | ) |  [inline, virtual] | 
| karto::OccupancyGrid::OccupancyGrid | ( | const OccupancyGrid & | ) |  [private] | 
Restrict the copy constructor
| virtual kt_bool karto::OccupancyGrid::AddScan | ( | LocalizedRangeScan * | pScan, | 
| kt_bool | doUpdate = false | ||
| ) |  [inline, protected, virtual] | 
| OccupancyGrid* karto::OccupancyGrid::Clone | ( | ) | const  [inline] | 
| static void karto::OccupancyGrid::ComputeDimensions | ( | const LocalizedRangeScanVector & | rScans, | 
| kt_double | resolution, | ||
| kt_int32s & | rWidth, | ||
| kt_int32s & | rHeight, | ||
| Vector2< kt_double > & | rOffset | ||
| ) |  [inline, static, protected] | 
| static OccupancyGrid* karto::OccupancyGrid::CreateFromScans | ( | const LocalizedRangeScanVector & | rScans, | 
| kt_double | resolution | ||
| ) |  [inline, static] | 
| virtual void karto::OccupancyGrid::CreateFromScans | ( | const LocalizedRangeScanVector & | rScans | ) |  [inline, protected, virtual] | 
| virtual Grid<kt_int32u>* karto::OccupancyGrid::GetCellHitsCounts | ( | ) |  [inline, protected, virtual] | 
| virtual Grid<kt_int32u>* karto::OccupancyGrid::GetCellPassCounts | ( | ) |  [inline, protected, virtual] | 
| virtual kt_bool karto::OccupancyGrid::IsFree | ( | const Vector2< kt_int32s > & | rPose | ) | const  [inline, virtual] | 
| const OccupancyGrid& karto::OccupancyGrid::operator= | ( | const OccupancyGrid & | ) |  [private] | 
Restrict the assignment operator
| virtual kt_double karto::OccupancyGrid::RayCast | ( | const Pose2 & | rPose2, | 
| kt_double | maxRange | ||
| ) | const  [inline, virtual] | 
| virtual kt_bool karto::OccupancyGrid::RayTrace | ( | const Vector2< kt_double > & | rWorldFrom, | 
| const Vector2< kt_double > & | rWorldTo, | ||
| kt_bool | isEndPointValid, | ||
| kt_bool | doUpdate = false | ||
| ) |  [inline, protected, virtual] | 
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 | 
| virtual void karto::OccupancyGrid::Resize | ( | kt_int32s | width, | 
| kt_int32s | height | ||
| ) |  [inline, protected, virtual] | 
Resizes the grid (deletes all old data)
| width | |
| height | 
Reimplemented from karto::Grid< kt_int8u >.
| void karto::OccupancyGrid::SetMinPassThrough | ( | kt_int32u | count | ) |  [inline] | 
| void karto::OccupancyGrid::SetOccupancyThreshold | ( | kt_double | thresh | ) |  [inline] | 
| virtual void karto::OccupancyGrid::Update | ( | ) |  [inline, protected, virtual] | 
| virtual void karto::OccupancyGrid::UpdateCell | ( | kt_int8u * | pCell, | 
| kt_int32u | cellPassCnt, | ||
| kt_int32u | cellHitCnt | ||
| ) |  [inline, protected, virtual] | 
| friend class CellUpdater  [friend] | 
| friend class IncrementalOccupancyGrid  [friend] | 
| Grid<kt_int32u>* karto::OccupancyGrid::m_pCellHitsCnt  [protected] | 
| Grid<kt_int32u>* karto::OccupancyGrid::m_pCellPassCnt  [protected] | 
| CellUpdater* karto::OccupancyGrid::m_pCellUpdater  [private] |