31 "mrpt::maps::COccupancyGridMap2D,occupancyGrid",
34 COccupancyGridMap2D::TMapDefinition::TMapDefinition() =
default;
36 void COccupancyGridMap2D::TMapDefinition::loadFromConfigFile_map_specific(
38 const std::string& sectionNamePrefix)
41 const std::string sSectCreation =
42 sectionNamePrefix + string(
"_creationOpts");
50 insertionOpts.loadFromConfigFile(
51 source, sectionNamePrefix +
string(
"_insertOpts"));
54 likelihoodOpts.loadFromConfigFile(
55 source, sectionNamePrefix +
string(
"_likelihoodOpts"));
58 void COccupancyGridMap2D::TMapDefinition::dumpToTextStream_map_specific(
59 std::ostream&
out)
const 67 this->insertionOpts.dumpToTextStream(
out);
68 this->likelihoodOpts.dumpToTextStream(
out);
86 std::vector<float> COccupancyGridMap2D::entropyTable;
88 static const float MAX_H = 0.69314718055994531f;
93 COccupancyGridMap2D::get_logodd_lut()
101 COccupancyGridMap2D::COccupancyGridMap2D(
102 float min_x,
float max_x,
float min_y,
float max_y,
float res)
105 precomputedLikelihood(),
110 updateInfoChangeOnly(),
117 setSize(min_x, max_x, min_y, max_y, res, 0.5f);
141 float xmin,
float xmax,
float ymin,
float ymax,
float res,
157 xmin = res *
round(xmin / res);
158 ymin = res *
round(ymin / res);
159 xmax = res *
round(xmax / res);
160 ymax = res *
round(ymax / res);
173 #ifdef ROWSIZE_MULTIPLE_16 197 float new_x_min,
float new_x_max,
float new_y_min,
float new_y_max,
198 float new_cells_default_value,
bool additionalMargin) noexcept
200 unsigned int extra_x_izq = 0, extra_y_arr = 0, new_size_x = 0,
202 std::vector<cellType> new_map;
204 if (new_x_min > new_x_max)
207 "[COccupancyGridMap2D::resizeGrid] Warning!! Ignoring call, since: " 208 "x_min=%f x_max=%f\n",
209 new_x_min, new_x_max);
212 if (new_y_min > new_y_max)
215 "[COccupancyGridMap2D::resizeGrid] Warning!! Ignoring call, since: " 216 "y_min=%f y_max=%f\n",
217 new_y_min, new_y_max);
222 if (new_x_min >= x_min && new_y_min >= y_min && new_x_max <= x_max &&
227 m_likelihoodCacheOutDated =
true;
230 if (additionalMargin)
232 if (new_x_min < x_min) new_x_min = floor(new_x_min - 4);
233 if (new_x_max > x_max) new_x_max = ceil(new_x_max + 4);
234 if (new_y_min < y_min) new_y_min = floor(new_y_min - 4);
235 if (new_y_max > y_max) new_y_max = ceil(new_y_max + 4);
239 new_x_min = min(new_x_min, x_min);
240 new_x_max = max(new_x_max, x_max);
241 new_y_min = min(new_y_min, y_min);
242 new_y_max = max(new_y_max, y_max);
246 if (fabs(new_x_min / resolution -
round(new_x_min / resolution)) > 0.05f)
247 new_x_min = resolution *
round(new_x_min / resolution);
248 if (fabs(new_y_min / resolution -
round(new_y_min / resolution)) > 0.05f)
249 new_y_min = resolution *
round(new_y_min / resolution);
250 if (fabs(new_x_max / resolution -
round(new_x_max / resolution)) > 0.05f)
251 new_x_max = resolution *
round(new_x_max / resolution);
252 if (fabs(new_y_max / resolution -
round(new_y_max / resolution)) > 0.05f)
253 new_y_max = resolution *
round(new_y_max / resolution);
256 extra_x_izq =
round((x_min - new_x_min) / resolution);
257 extra_y_arr =
round((y_min - new_y_min) / resolution);
259 new_size_x =
round((new_x_max - new_x_min) / resolution);
260 new_size_y =
round((new_y_max - new_y_min) / resolution);
262 assert(new_size_x >= size_x + extra_x_izq);
264 #ifdef ROWSIZE_MULTIPLE_16 266 size_t old_new_size_x = new_size_x;
267 if (0 != (new_size_x % 16))
269 int size_x_incr = 16 - (new_size_x % 16);
271 new_x_max += size_x_incr * resolution;
273 new_size_x =
round((new_x_max - new_x_min) / resolution);
274 assert(0 == (new_size_x % 16));
278 new_map.resize(new_size_x * new_size_y, p2l(new_cells_default_value));
282 cellType* dest_ptr = &new_map[extra_x_izq + extra_y_arr * new_size_x];
284 size_t row_size = size_x *
sizeof(
cellType);
286 for (
size_t y = 0; y < size_y; y++)
288 #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG) 289 assert(dest_ptr + row_size - 1 <= &new_map[new_map.size() - 1]);
290 assert(src_ptr + row_size - 1 <= &map[map.size() - 1]);
292 memcpy(dest_ptr, src_ptr, row_size);
293 dest_ptr += new_size_x;
312 m_voronoi_diagram.clear();
354 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS 365 for (
size_t i = 0; i < N; i++)
367 const auto p =
l2p(static_cast<cellType>(i));
368 auto h =
d2f(
H(p) +
H(1 - p));
371 if (i == 0 || i == (N - 1)) h = 0;
384 for (
signed char it :
map)
389 if (h < (
MAX_H - 0.001f))
432 for (
auto it =
map.begin(); it <
map.end(); ++it) *it = defValue;
443 if (static_cast<unsigned int>(x) >=
size_x ||
444 static_cast<unsigned int>(y) >=
size_y)
453 float old =
l2p(theCell);
454 float new_v = 1 / (1 + (1 - v) * (1 - old) / (old * v));
484 std::vector<cellType> newMap;
493 newMap.resize(newSizeX * newSizeY);
495 for (
int x = 0; x < newSizeX; x++)
497 for (
int y = 0; y < newSizeY; y++)
501 for (
int xx = 0; xx < downRatio; xx++)
502 for (
int yy = 0; yy < downRatio; yy++)
503 newCell +=
getCell(x * downRatio + xx, y * downRatio + yy);
505 newCell /= (downRatio * downRatio);
507 newMap[x + y * newSizeX] =
p2l(newCell);
529 params.offset_other_map_points,
params.decimation_other_map_points);
532 const auto* otherMap =
static_cast<const CPointsMap*
>(otherMap2);
536 const size_t nLocalPoints = otherMap->
size();
537 std::vector<float> x_locals(nLocalPoints), y_locals(nLocalPoints),
538 z_locals(nLocalPoints);
540 const float sin_phi = sin(otherMapPose.
phi);
541 const float cos_phi = cos(otherMapPose.
phi);
543 size_t nOtherMapPointsWithCorrespondence =
545 size_t nTotalCorrespondences = 0;
546 float _sumSqrDist = 0;
549 const int cellsSearchRange =
553 correspondences.clear();
556 if (!nLocalPoints)
return;
561 float local_x_min = std::numeric_limits<float>::max();
562 float local_x_max = -std::numeric_limits<float>::max();
563 float local_y_min = std::numeric_limits<float>::max();
564 float local_y_max = -std::numeric_limits<float>::max();
566 const auto& otherMap_pxs = otherMap->getPointsBufferRef_x();
567 const auto& otherMap_pys = otherMap->getPointsBufferRef_y();
568 const auto& otherMap_pzs = otherMap->getPointsBufferRef_z();
571 for (
unsigned int localIdx =
params.offset_other_map_points;
572 localIdx < nLocalPoints;
573 localIdx +=
params.decimation_other_map_points)
576 const float xx = x_locals[localIdx] = otherMapPose.
x +
577 cos_phi * otherMap_pxs[localIdx] -
578 sin_phi * otherMap_pys[localIdx];
579 const float yy = y_locals[localIdx] = otherMapPose.
y +
580 sin_phi * otherMap_pxs[localIdx] +
581 cos_phi * otherMap_pys[localIdx];
582 z_locals[localIdx] = otherMap_pzs[localIdx];
585 local_x_min = min(local_x_min, xx);
586 local_x_max = max(local_x_max, xx);
587 local_y_min = min(local_y_min, yy);
588 local_y_max = max(local_y_max, yy);
593 if (local_x_min >
x_max || local_x_max < x_min || local_y_min >
y_max ||
600 for (
unsigned int localIdx =
params.offset_other_map_points;
601 localIdx < nLocalPoints;
602 localIdx +=
params.decimation_other_map_points)
605 float maxDistForCorrespondenceSquared =
609 const float x_local = x_locals[localIdx];
610 const float y_local = y_locals[localIdx];
611 const float z_local = z_locals[localIdx];
614 float min_dist = 1e6;
618 const int cx0 =
x2idx(x_local);
619 const int cy0 =
y2idx(y_local);
622 const int cx_min = max(0, cx0 - cellsSearchRange);
624 min(static_cast<int>(
size_x) - 1, cx0 + cellsSearchRange);
625 const int cy_min = max(0, cy0 - cellsSearchRange);
627 min(static_cast<int>(
size_y) - 1, cy0 + cellsSearchRange);
630 bool thisLocalHasCorr =
false;
633 for (
int cx = cx_min; cx <= cx_max; cx++)
635 for (
int cy = cy_min; cy <= cy_max; cy++)
641 const float residual_x =
idx2x(cx) - x_local;
642 const float residual_y =
idx2y(cy) - y_local;
645 maxDistForCorrespondenceSquared =
square(
646 params.maxAngularDistForCorrespondence *
647 params.angularDistPivotPoint.distanceTo(
649 params.maxDistForCorrespondence);
652 const float this_dist =
655 if (this_dist < maxDistForCorrespondenceSquared)
657 if (!
params.onlyKeepTheClosest)
660 nTotalCorrespondences++;
667 mp.
other_x = otherMap_pxs[localIdx];
668 mp.
other_y = otherMap_pys[localIdx];
669 mp.
other_z = otherMap_pzs[localIdx];
670 correspondences.push_back(mp);
675 if (this_dist < min_dist)
677 min_dist = this_dist;
682 closestCorr.
this_z = z_local;
684 closestCorr.
other_x = otherMap_pxs[localIdx];
685 closestCorr.
other_y = otherMap_pys[localIdx];
686 closestCorr.
other_z = otherMap_pzs[localIdx];
691 thisLocalHasCorr =
true;
698 if (
params.onlyKeepTheClosest &&
699 (min_dist < maxDistForCorrespondenceSquared))
701 nTotalCorrespondences++;
702 correspondences.push_back(closestCorr);
706 if (thisLocalHasCorr)
708 nOtherMapPointsWithCorrespondence++;
711 _sumSqrDist += min_dist;
716 extraResults.correspondencesRatio =
717 nOtherMapPointsWithCorrespondence /
718 d2f(nLocalPoints /
params.decimation_other_map_points);
719 extraResults.sumSqrDist = _sumSqrDist;
735 return e1.first > e2.first;
742 float x1,
float y1,
float x2,
float y2)
const 749 for (
int i = 0; i < nSteps; i++)
751 float x = x1 + (x2 - x1) * i /
d2f(nSteps);
752 float y = y1 + (y2 - y1) * i /
d2f(nSteps);
757 return sumCost /
d2f(nSteps);
Virtual base for specifying the kind and parameters of one map (normally, to be inserted into mrpt::m...
Parameters for CMetricMap::compute3DMatchingRatio()
static constexpr cellType OCCGRID_CELLTYPE_MIN
Discrete to float conversion factors: The min/max values of the integer cell type, eg.
void clear()
Erase the contents of all the cells.
float getResolution() const
Returns the resolution of the grid map.
mrpt::maps::COccupancyGridMap2D::TInsertionOptions insertionOpts
Observations insertion options.
double effectiveMappedArea
The target variable for the area of cells with information, i.e.
#define ASSERT_BELOW_(__A, __B)
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
To be added to all CSerializable-classes implementation files.
float resolution
Cell size, i.e.
OccGridCellTraits::cellTypeUnsigned cellTypeUnsigned
mrpt::containers::CDynamicGrid< uint16_t > m_voronoi_diagram
Used to store the Voronoi diagram.
void updateCell(int x, int y, float v)
Performs the Bayesian fusion of a new observation of a cell.
mrpt::vision::TStereoCalibParams params
mrpt::containers::CDynamicGrid< uint8_t > m_basis_map
Used for Voronoi calculation.Same struct as "map", but contains a "0" if not a basis point...
struct mrpt::maps::COccupancyGridMap2D::TUpdateCellsInfoChangeOnly updateInfoChangeOnly
static T H(const T p)
Entropy computation internal function:
void freeMap()
Frees the dynamic memory buffers of map.
static constexpr cellType OCCGRID_CELLTYPE_MAX
std::vector< cellType > map
Store of cell occupancy values.
mrpt::math::TPose2D asTPose() const
bool m_likelihoodCacheOutDated
#define ASSERT_(f)
Defines an assertion mechanism.
float d2f(const double d)
shortcut for static_cast<float>(double)
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
double H
The target variable for absolute entropy, computed as: H(map)=Sumx,y{ -p(x,y)*ln(p(x,y)) -(1-p(x,y))*ln(1-p(x,y)) }
This class allows loading and storing values and vectors of different types from a configuration text...
This base provides a set of functions for maths stuff.
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
bool isEmpty() const override
Returns true upon map construction or after calling clear(), the return changes to false upon success...
std::pair< double, mrpt::math::TPoint2D > TPairLikelihoodIndex
Auxiliary private class.
float idx2x(const size_t cx) const
Transform a cell index into a coordinate value.
void copyMapContentFrom(const COccupancyGridMap2D &otherMap)
copy the gridmap contents, but not all the options, from another map instance
double I
The target variable for absolute "information", defining I(x) = 1 - H(x)
This namespace contains representation of robot actions and observations.
void subSample(int downRatio)
Performs a downsampling of the gridmap, by a given factor: resolution/=ratio.
double I_change
The cummulative change in Information: This is updated only from the "updateCell" method...
void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const override
See the base class for more details: In this class it is implemented as correspondences of the passed...
#define ASSERT_ABOVEEQ_(__A, __B)
static CLogOddsGridMapLUT< COccupancyGridMap2D::cellType > logodd_lut
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double mean_H
The target variable for mean entropy, defined as entropy per cell: mean_H(map) = H(map) / (cells) ...
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
return_t square(const num_t x)
Inline function for the square of a number.
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
A class for storing an occupancy grid map.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define MAP_DEFINITION_REGISTER(_CLASSNAME_STRINGS, _CLASSNAME_WITH_NS)
Registers one map class into TMetricMapInitializer factory.
constexpr std::size_t size() const
virtual const mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override
Returns information about the class of an object in runtime.
unsigned long effectiveMappedCells
The mapped area in cells.
static cellType p2l(const float p)
Scales a real valued probability in [0,1] to an integer representation of: log(p)-log(1-p) in the val...
Declares a virtual base class for all metric maps storage classes.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
mrpt::vision::TStereoCalibResults out
int cellsUpdated
The cummulative updated cells count: This is updated only from the "updateCell" method.
static std::vector< float > entropyTable
Internally used to speed-up entropy calculation.
#define ASSERT_ABOVE_(__A, __B)
bool m_is_empty
True upon construction; used by isEmpty()
void internal_clear() override
Clear the map: It set all cells to their default occupancy value (0.5), without changing the resoluti...
mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions likelihoodOpts
Probabilistic observation likelihood options.
float min_x
See COccupancyGridMap2D::COccupancyGridMap2D.
float idx2y(const size_t cy) const
bool derivedFrom(const TRuntimeClassId *pBaseClass) const
OccGridCellTraits::cellType cellType
The type of the map cells:
void computeEntropy(TEntropyInfo &info) const
Computes the entropy and related values of this grid map.
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams ¶ms) const override
See docs in base class: in this class this always returns 0.
uint32_t size_x
The size of the grid in cells.
void fill(float default_value=0.5f)
Fills all the cells with a default value.
void resizeGrid(float new_x_min, float new_x_max, float new_y_min, float new_y_max, float new_cells_default_value=0.5f, bool additionalMargin=true) noexcept
Change the size of gridmap, maintaining previous contents.
float x_min
The limits of the grid in "units" (meters)
float getPos(float x, float y) const
Read the real valued [0,1] contents of a cell, given its coordinates.
#define ASSERT_BELOWEQ_(__A, __B)
void setSize(float x_min, float x_max, float y_min, float y_max, float resolution, float default_value=0.5f)
Change the size of gridmap, erasing all its previous contents.
float computePathCost(float x1, float y1, float x2, float y2) const
Compute the 'cost' of traversing a segment of the map according to the occupancy of traversed cells...
double mean_I
The target variable for mean information, defined as information per cell: mean_I(map) = I(map) / (ce...
bool operator<(const COccupancyGridMap2D::TPairLikelihoodIndex &e1, const COccupancyGridMap2D::TPairLikelihoodIndex &e2)
Parameters for the determination of matchings between point clouds, etc.
Used for returning entropy related information.
Functions for estimating the optimal transformation between two frames of references given measuremen...
int x2idx(float x) const
Transform a coordinate value into a cell index.
double phi
Orientation (rads)
float getCell(int x, int y) const
Read the real valued [0,1] contents of a cell, given its index.
static float l2p(const cellType l)
Scales an integer representation of the log-odd into a real valued probability in [0...
One static instance of this struct should exist in any class implementing CLogOddsGridMap2D to hold t...
void memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) noexcept
An OS and compiler independent version of "memcpy".
bool enabled
If set to false (default), this struct is not used.
int round(const T value)
Returns the closer integer (int) to x.