Class OccGrid
Defined in File OccGrid.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public mrpt::serialization::CSerializable
Class Documentation
-
class OccGrid : public mrpt::serialization::CSerializable
Extends MRPT’s occupancy grid with super-resolution likelihood field.
Read and update API
-
InsertionParameters insertionParameters_
-
void insertObservation(const mrpt::obs::CObservation2DRangeScan &obs, const mrpt::math::TPose2D &robotPose)
-
inline const mrpt::maps::COccupancyGridMap2D &grid() const
Likelihood API
-
LikelihoodParameters likelihoodParameters_
-
static constexpr float CACHE_MISS_VALUE = std::numeric_limits<float>::min()
For use in likelihoodCacheGrid_
-
void resetLikelihoodCache()
Invalidates all cached likelihood values (normally users do not need to call this)
Grid size API
-
void setSize(const mrpt::math::TPoint2Df &minCorner, const mrpt::math::TPoint2Df &maxCorner, float resolution, float occupancyValue = 0.5f)
Change the size of gridmap, erasing all its previous contents.
- Parameters:
minCorner – The (x,y) coordinates of left-bottom grid corner.
maxCorner – The (x,y) coordinates of right-top grid corner.
resolution – The new size of square cells [meters]
occupancyValue – The occupancy value of cells, tipically 0.5.
-
void resizeGrid(const mrpt::math::TPoint2Df &minCorner, const mrpt::math::TPoint2Df &maxCorner, float newCellsOccupancy = 0.5f) noexcept
Change the size of gridmap, maintaining previous contents.
See also
- Parameters:
minCorner – The (x,y) coordinates of left-bottom grid corner.
maxCorner – The (x,y) coordinates of right-top grid corner.
newCellsOccupancyValue – Occupancy of new cells, tipically 0.5.
-
struct InsertionParameters
Public Functions
-
InsertionParameters() = default
Public Members
-
float maxDistanceInsertion = 50.0
The largest distance at which cells will be updated [m]
-
float maxOccupancyUpdateCertainty = {0.65f}
A value in the range [0.5,1] used for updating cell with a bayesian approach (default 0.8)
-
float maxFreenessUpdateCertainty = {.0f}
A value in the range [0.5,1] for updating a free cell. (default=0 means use the same than maxOccupancyUpdateCertainty)
-
float maxFreenessInvalidRanges = {.0f}
Like maxFreenessUpdateCertainty, but for invalid ranges (no echo). (default=0 means same than maxOccupancyUpdateCertainty)
-
bool considerInvalidRangesAsFreeSpace = {true}
If set to true (default), invalid range values (no echo rays) as consider as free space until “maxOccupancyUpdateCertainty”, but ONLY when the previous and next rays are also an invalid ray.
-
uint16_t decimation = {1}
Specify the decimation of the range scan (default=1 : take all the range values!)
-
bool wideningBeamsWithDistance = {false}
Enabled: Rays widen with distance to approximate the real behavior of lasers, disabled: insert rays as simple lines (Default=false)
-
InsertionParameters() = default
-
InsertionParameters insertionParameters_