33 COccupancyGridMap2D::TMapDefinition::TMapDefinition() =
default;
35 void COccupancyGridMap2D::TMapDefinition::loadFromConfigFile_map_specific(
41 sectionNamePrefix +
string(
"_creationOpts");
49 insertionOpts.loadFromConfigFile(
50 source, sectionNamePrefix +
string(
"_insertOpts"));
53 likelihoodOpts.loadFromConfigFile(
54 source, sectionNamePrefix +
string(
"_likelihoodOpts"));
57 void COccupancyGridMap2D::TMapDefinition::dumpToTextStream_map_specific(
58 std::ostream& out)
const 66 this->insertionOpts.dumpToTextStream(out);
67 this->likelihoodOpts.dumpToTextStream(out);
85 std::vector<float> COccupancyGridMap2D::entropyTable;
87 static const float MAX_H = 0.69314718055994531f;
92 COccupancyGridMap2D::get_logodd_lut()
100 COccupancyGridMap2D::COccupancyGridMap2D(
101 float min_x,
float max_x,
float min_y,
float max_y,
float res)
104 precomputedLikelihood(),
109 updateInfoChangeOnly(),
116 setSize(min_x, max_x, min_y, max_y,
res, 0.5f);
140 float xmin,
float xmax,
float ymin,
float ymax,
float res,
172 #ifdef ROWSIZE_MULTIPLE_16 196 float new_x_min,
float new_x_max,
float new_y_min,
float new_y_max,
197 float new_cells_default_value,
bool additionalMargin) noexcept
199 unsigned int extra_x_izq = 0, extra_y_arr = 0, new_size_x = 0,
201 std::vector<cellType> new_map;
203 if (new_x_min > new_x_max)
206 "[COccupancyGridMap2D::resizeGrid] Warning!! Ignoring call, since: " 207 "x_min=%f x_max=%f\n",
208 new_x_min, new_x_max);
211 if (new_y_min > new_y_max)
214 "[COccupancyGridMap2D::resizeGrid] Warning!! Ignoring call, since: " 215 "y_min=%f y_max=%f\n",
216 new_y_min, new_y_max);
221 if (new_x_min >= x_min && new_y_min >= y_min && new_x_max <= x_max &&
226 m_likelihoodCacheOutDated =
true;
229 if (additionalMargin)
231 if (new_x_min < x_min) new_x_min = floor(new_x_min - 4);
232 if (new_x_max > x_max) new_x_max = ceil(new_x_max + 4);
233 if (new_y_min < y_min) new_y_min = floor(new_y_min - 4);
234 if (new_y_max > y_max) new_y_max = ceil(new_y_max + 4);
238 new_x_min =
min(new_x_min, x_min);
239 new_x_max = max(new_x_max, x_max);
240 new_y_min =
min(new_y_min, y_min);
241 new_y_max = max(new_y_max, y_max);
245 if (fabs(new_x_min / resolution -
round(new_x_min / resolution)) > 0.05f)
246 new_x_min = resolution *
round(new_x_min / resolution);
247 if (fabs(new_y_min / resolution -
round(new_y_min / resolution)) > 0.05f)
248 new_y_min = resolution *
round(new_y_min / resolution);
249 if (fabs(new_x_max / resolution -
round(new_x_max / resolution)) > 0.05f)
250 new_x_max = resolution *
round(new_x_max / resolution);
251 if (fabs(new_y_max / resolution -
round(new_y_max / resolution)) > 0.05f)
252 new_y_max = resolution *
round(new_y_max / resolution);
255 extra_x_izq =
round((x_min - new_x_min) / resolution);
256 extra_y_arr =
round((y_min - new_y_min) / resolution);
258 new_size_x =
round((new_x_max - new_x_min) / resolution);
259 new_size_y =
round((new_y_max - new_y_min) / resolution);
261 assert(new_size_x >= size_x + extra_x_izq);
263 #ifdef ROWSIZE_MULTIPLE_16 265 size_t old_new_size_x = new_size_x;
266 if (0 != (new_size_x % 16))
268 int size_x_incr = 16 - (new_size_x % 16);
270 new_x_max += size_x_incr * resolution;
272 new_size_x =
round((new_x_max - new_x_min) / resolution);
273 assert(0 == (new_size_x % 16));
277 new_map.resize(new_size_x * new_size_y, p2l(new_cells_default_value));
281 cellType* dest_ptr = &new_map[extra_x_izq + extra_y_arr * new_size_x];
283 size_t row_size = size_x *
sizeof(
cellType);
285 for (
size_t y = 0;
y < size_y;
y++)
287 #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG) 288 assert(dest_ptr + row_size - 1 <= &new_map[new_map.size() - 1]);
289 assert(src_ptr + row_size - 1 <= &map[map.size() - 1]);
291 memcpy(dest_ptr, src_ptr, row_size);
292 dest_ptr += new_size_x;
311 m_voronoi_diagram.clear();
356 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS 357 unsigned int N = 256;
359 unsigned int N = 65536;
367 for (i = 0; i < N; i++)
369 p =
l2p(static_cast<cellType>(i));
373 if (i == 0 || i == (N - 1)) h = 0;
386 for (
signed char it :
map)
391 if (h < (
MAX_H - 0.001f))
423 if (
p == 0 ||
p == 1)
446 for (
auto it =
map.begin(); it <
map.end(); ++it) *it = defValue;
458 if (static_cast<unsigned int>(
x) >=
size_x ||
459 static_cast<unsigned int>(
y) >=
size_y)
468 float old =
l2p(theCell);
469 float new_v = 1 / (1 + (1 -
v) * (1 - old) / (old *
v));
499 std::vector<cellType> newMap;
508 newMap.resize(newSizeX * newSizeY);
510 for (
int x = 0;
x < newSizeX;
x++)
512 for (
int y = 0;
y < newSizeY;
y++)
516 for (
int xx = 0; xx < downRatio; xx++)
517 for (
int yy = 0; yy < downRatio; yy++)
518 newCell +=
getCell(
x * downRatio + xx,
y * downRatio + yy);
520 newCell /= (downRatio * downRatio);
522 newMap[
x +
y * newSizeX] =
p2l(newCell);
544 params.offset_other_map_points,
params.decimation_other_map_points);
547 const auto* otherMap =
static_cast<const CPointsMap*
>(otherMap2);
551 const size_t nLocalPoints = otherMap->
size();
552 std::vector<float> x_locals(nLocalPoints), y_locals(nLocalPoints),
553 z_locals(nLocalPoints);
555 const float sin_phi = sin(otherMapPose.
phi);
556 const float cos_phi = cos(otherMapPose.
phi);
558 size_t nOtherMapPointsWithCorrespondence =
560 size_t nTotalCorrespondences = 0;
561 float _sumSqrDist = 0;
564 const int cellsSearchRange =
568 correspondences.clear();
571 if (!nLocalPoints)
return;
576 float local_x_min = std::numeric_limits<float>::max();
577 float local_x_max = -std::numeric_limits<float>::max();
578 float local_y_min = std::numeric_limits<float>::max();
579 float local_y_max = -std::numeric_limits<float>::max();
581 const auto& otherMap_pxs = otherMap->getPointsBufferRef_x();
582 const auto& otherMap_pys = otherMap->getPointsBufferRef_y();
583 const auto& otherMap_pzs = otherMap->getPointsBufferRef_z();
586 for (
unsigned int localIdx =
params.offset_other_map_points;
587 localIdx < nLocalPoints;
588 localIdx +=
params.decimation_other_map_points)
591 const float xx = x_locals[localIdx] = otherMapPose.
x +
592 cos_phi * otherMap_pxs[localIdx] -
593 sin_phi * otherMap_pys[localIdx];
594 const float yy = y_locals[localIdx] = otherMapPose.
y +
595 sin_phi * otherMap_pxs[localIdx] +
596 cos_phi * otherMap_pys[localIdx];
597 z_locals[localIdx] = otherMap_pzs[localIdx];
600 local_x_min =
min(local_x_min, xx);
601 local_x_max = max(local_x_max, xx);
602 local_y_min =
min(local_y_min, yy);
603 local_y_max = max(local_y_max, yy);
608 if (local_x_min >
x_max || local_x_max < x_min || local_y_min >
y_max ||
615 for (
unsigned int localIdx =
params.offset_other_map_points;
616 localIdx < nLocalPoints;
617 localIdx +=
params.decimation_other_map_points)
620 float maxDistForCorrespondenceSquared =
624 const float x_local = x_locals[localIdx];
625 const float y_local = y_locals[localIdx];
626 const float z_local = z_locals[localIdx];
629 float min_dist = 1e6;
633 const int cx0 =
x2idx(x_local);
634 const int cy0 =
y2idx(y_local);
637 const int cx_min = max(0, cx0 - cellsSearchRange);
639 min(static_cast<int>(
size_x) - 1, cx0 + cellsSearchRange);
640 const int cy_min = max(0, cy0 - cellsSearchRange);
642 min(static_cast<int>(
size_y) - 1, cy0 + cellsSearchRange);
645 bool thisLocalHasCorr =
false;
648 for (
int cx = cx_min; cx <= cx_max; cx++)
650 for (
int cy = cy_min; cy <= cy_max; cy++)
656 const float residual_x =
idx2x(cx) - x_local;
657 const float residual_y =
idx2y(cy) - y_local;
660 maxDistForCorrespondenceSquared =
square(
661 params.maxAngularDistForCorrespondence *
662 params.angularDistPivotPoint.distanceTo(
664 params.maxDistForCorrespondence);
667 const float this_dist =
670 if (this_dist < maxDistForCorrespondenceSquared)
672 if (!
params.onlyKeepTheClosest)
675 nTotalCorrespondences++;
682 mp.
other_x = otherMap_pxs[localIdx];
683 mp.
other_y = otherMap_pys[localIdx];
684 mp.
other_z = otherMap_pzs[localIdx];
685 correspondences.push_back(mp);
690 if (this_dist < min_dist)
692 min_dist = this_dist;
697 closestCorr.
this_z = z_local;
699 closestCorr.
other_x = otherMap_pxs[localIdx];
700 closestCorr.
other_y = otherMap_pys[localIdx];
701 closestCorr.
other_z = otherMap_pzs[localIdx];
706 thisLocalHasCorr =
true;
713 if (
params.onlyKeepTheClosest &&
714 (min_dist < maxDistForCorrespondenceSquared))
716 nTotalCorrespondences++;
717 correspondences.push_back(closestCorr);
721 if (thisLocalHasCorr)
723 nOtherMapPointsWithCorrespondence++;
726 _sumSqrDist += min_dist;
731 extraResults.correspondencesRatio =
732 nOtherMapPointsWithCorrespondence /
733 static_cast<float>(nLocalPoints /
params.decimation_other_map_points);
734 extraResults.sumSqrDist = _sumSqrDist;
750 return e1.first > e2.first;
757 float x1,
float y1,
float x2,
float y2)
const 764 for (
int i = 0; i < nSteps; i++)
766 float x = x1 + (x2 - x1) * i / static_cast<float>(nSteps);
767 float y = y1 + (y2 - y1) * i / static_cast<float>(nSteps);
772 return sumCost /
static_cast<float>(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
static double H(double p)
Entropy computation internal function:
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::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
GLsizei GLsizei GLuint * obj
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
T square(const T x)
Inline function for the square of a number.
bool m_likelihoodCacheOutDated
#define ASSERT_(f)
Defines an assertion mechanism.
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
GLsizei const GLchar ** string
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...
#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).
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.
GLsizei GLsizei GLchar * source
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...
GLenum const GLfloat * params
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".
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
bool enabled
If set to false (default), this struct is not used.
int round(const T value)
Returns the closer integer (int) to x.