51 insertionOpts.loadFromConfigFile(
source, sectionNamePrefix+
string(
"_insertOpts") );
54 likelihoodOpts.loadFromConfigFile(
source, sectionNamePrefix+
string(
"_likelihoodOpts") );
66 this->insertionOpts.dumpToTextStream(out);
67 this->likelihoodOpts.dumpToTextStream(out);
82 std::vector<float> COccupancyGridMap2D::entropyTable;
84 static const float MAX_H = 0.69314718055994531f;
92 COccupancyGridMap2D::COccupancyGridMap2D(
100 x_min(),x_max(),y_min(),y_max(), resolution(),
101 precomputedLikelihood(),
102 precomputedLikelihoodToBeRecomputed(true),
106 voroni_free_threshold(),
107 updateInfoChangeOnly(),
161 ASSERT_(default_value>=0 && default_value<=1)
186 #ifdef ROWSIZE_MULTIPLE_16 214 unsigned int extra_x_izq=0,extra_y_arr=0,new_size_x=0,new_size_y=0;
215 std::vector<cellType> new_map;
217 if( new_x_min > new_x_max )
219 printf(
"[COccupancyGridMap2D::resizeGrid] Warning!! Ignoring call, since: x_min=%f x_max=%f\n", new_x_min, new_x_max);
222 if( new_y_min > new_y_max )
224 printf(
"[COccupancyGridMap2D::resizeGrid] Warning!! Ignoring call, since: y_min=%f y_max=%f\n", new_y_min, new_y_max);
229 if (new_x_min>=x_min &&
232 new_y_max<=y_max)
return;
235 precomputedLikelihoodToBeRecomputed =
true;
238 if (additionalMargin)
240 if (new_x_min<x_min) new_x_min= floor(new_x_min-4);
241 if (new_x_max>x_max) new_x_max= ceil(new_x_max+4);
242 if (new_y_min<y_min) new_y_min= floor(new_y_min-4);
243 if (new_y_max>y_max) new_y_max= ceil(new_y_max+4);
247 new_x_min =
min( new_x_min, x_min);
248 new_x_max = max( new_x_max, x_max);
249 new_y_min =
min( new_y_min, y_min);
250 new_y_max = max( new_y_max, y_max);
254 if (fabs(new_x_min/resolution -
round(new_x_min/resolution))>0.05f )
255 new_x_min = resolution*
round(new_x_min/resolution);
256 if (fabs(new_y_min/resolution -
round(new_y_min/resolution))>0.05f )
257 new_y_min = resolution*
round(new_y_min/resolution);
258 if (fabs(new_x_max/resolution -
round(new_x_max/resolution))>0.05f )
259 new_x_max = resolution*
round(new_x_max/resolution);
260 if (fabs(new_y_max/resolution -
round(new_y_max/resolution))>0.05f )
261 new_y_max = resolution*
round(new_y_max/resolution);
264 extra_x_izq =
round((x_min-new_x_min) / resolution);
265 extra_y_arr =
round((y_min-new_y_min) / resolution);
267 new_size_x =
round((new_x_max-new_x_min) / resolution);
268 new_size_y =
round((new_y_max-new_y_min) / resolution);
270 assert( new_size_x>=size_x+extra_x_izq );
272 #ifdef ROWSIZE_MULTIPLE_16 274 size_t old_new_size_x = new_size_x;
275 if (0!=(new_size_x % 16))
277 int size_x_incr = 16 - (new_size_x % 16);
279 new_x_max += size_x_incr * resolution;
281 new_size_x =
round((new_x_max-new_x_min)/resolution);
282 assert(0==(new_size_x % 16));
286 new_map.resize(new_size_x*new_size_y, p2l(new_cells_default_value));
290 cellType *dest_ptr = &new_map[extra_x_izq + extra_y_arr*new_size_x];
292 size_t row_size = size_x*
sizeof(
cellType);
294 for (
size_t y = 0;
y<size_y;
y++)
296 #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG) 297 assert( dest_ptr+row_size-1 <= &new_map[new_map.size()-1] );
298 assert( src_ptr+row_size-1 <= &map[map.size()-1] );
300 memcpy( dest_ptr, src_ptr, row_size );
301 dest_ptr += new_size_x;
320 m_voronoi_diagram.clear();
360 #ifdef OCCUPANCY_GRIDMAP_CELL_SIZE_8BITS 361 unsigned int N = 256;
363 unsigned int N = 65536;
373 p =
l2p(static_cast<cellType>(i));
377 if (i==0 || i==(N-1)) h=0;
386 info.effectiveMappedCells = 0;
390 info.effectiveMappedCells = 0;
396 if (h<(
MAX_H-0.001f))
398 info.effectiveMappedCells++;
405 info.I +=
info.effectiveMappedCells;
410 if (
info.effectiveMappedCells)
427 if (
p==0 ||
p==1)
return 0;
428 else return -
p*log(
p);
462 if (static_cast<unsigned int>(
x)>=
size_x || static_cast<unsigned int>(
y)>=
size_y)
471 float old =
l2p(theCell);
472 float new_v = 1 / ( 1 + (1-
v)*(1-old)/(old*
v) );
500 std::vector<cellType> newMap;
509 newMap.resize(newSizeX*newSizeY);
511 for (
int x=0;
x<newSizeX;
x++)
513 for (
int y=0;
y<newSizeY;
y++)
517 for (
int xx=0;xx<downRatio;xx++)
518 for (
int yy=0;yy<downRatio;yy++)
519 newCell+=
getCell(
x*downRatio+xx,
y*downRatio+yy);
521 newCell /= (downRatio*downRatio);
523 newMap[
x +
y*newSizeX ] =
p2l(newCell);
558 const size_t nLocalPoints = otherMap->size();
559 std::vector<float> x_locals(nLocalPoints), y_locals(nLocalPoints),z_locals(nLocalPoints);
561 const float sin_phi = sin(otherMapPose.
phi);
562 const float cos_phi = cos(otherMapPose.
phi);
564 size_t nOtherMapPointsWithCorrespondence = 0;
565 size_t nTotalCorrespondences = 0;
572 correspondences.clear();
575 if (!nLocalPoints)
return;
580 float local_x_min = std::numeric_limits<float>::max();
581 float local_x_max = -std::numeric_limits<float>::max();
582 float local_y_min = std::numeric_limits<float>::max();
583 float local_y_max = -std::numeric_limits<float>::max();
585 const std::vector<float> & otherMap_pxs = otherMap->getPointsBufferRef_x();
586 const std::vector<float> & otherMap_pys = otherMap->getPointsBufferRef_y();
587 const std::vector<float> & otherMap_pzs = otherMap->getPointsBufferRef_z();
590 for (
unsigned int localIdx=
params.offset_other_map_points;localIdx<nLocalPoints;localIdx+=
params.decimation_other_map_points)
593 const float xx = x_locals[localIdx] = otherMapPose.
x + cos_phi* otherMap_pxs[localIdx] - sin_phi* otherMap_pys[localIdx] ;
594 const float yy = y_locals[localIdx] = otherMapPose.
y + sin_phi* otherMap_pxs[localIdx] + cos_phi* otherMap_pys[localIdx] ;
595 z_locals[localIdx] = otherMap_pzs[localIdx];
598 local_x_min =
min(local_x_min,xx);
599 local_x_max = max(local_x_max,xx);
600 local_y_min =
min(local_y_min,yy);
601 local_y_max = max(local_y_max,yy);
606 if (local_x_min>
x_max ||
607 local_x_max<
x_min ||
608 local_y_min>
y_max ||
609 local_y_max<
y_min)
return;
615 for (
unsigned int localIdx=
params.offset_other_map_points;localIdx<nLocalPoints;localIdx+=
params.decimation_other_map_points)
618 float maxDistForCorrespondenceSquared =
square(
params.maxDistForCorrespondence );
621 const float x_local = x_locals[localIdx];
622 const float y_local = y_locals[localIdx];
623 const float z_local = z_locals[localIdx];
626 float min_dist = 1e6;
630 const int cx0=
x2idx(x_local);
631 const int cy0=
y2idx(y_local);
634 const int cx_min = max(0, cx0 - cellsSearchRange );
635 const int cx_max =
min(static_cast<int>(
size_x)-1, cx0 + cellsSearchRange );
636 const int cy_min = max(0, cy0 - cellsSearchRange );
637 const int cy_max =
min(static_cast<int>(
size_y)-1, cy0 + cellsSearchRange );
640 bool thisLocalHasCorr =
false;
644 for (
int cx=cx_min;cx<=cx_max;cx++)
646 for (
int cy=cy_min;cy<=cy_max;cy++)
649 if (
map[cx+cy*
size_x] < thresholdCellValue )
651 const float residual_x =
idx2x(cx)- x_local;
652 const float residual_y =
idx2y(cy)- y_local;
655 maxDistForCorrespondenceSquared =
square(
656 params.maxAngularDistForCorrespondence *
params.angularDistPivotPoint.distanceTo(
TPoint3D(x_local,y_local,0) ) +
657 params.maxDistForCorrespondence );
660 const float this_dist =
square( residual_x ) +
square( residual_y );
662 if (this_dist<maxDistForCorrespondenceSquared)
664 if (!
params.onlyKeepTheClosest)
667 nTotalCorrespondences++;
674 mp.
other_x = otherMap_pxs[localIdx];
675 mp.
other_y = otherMap_pys[localIdx];
676 mp.
other_z = otherMap_pzs[localIdx];
677 correspondences.push_back( mp );
682 if (this_dist<min_dist)
684 min_dist = this_dist;
689 closestCorr.
this_z = z_local;
691 closestCorr.
other_x = otherMap_pxs[localIdx];
692 closestCorr.
other_y = otherMap_pys[localIdx];
693 closestCorr.
other_z = otherMap_pzs[localIdx];
698 thisLocalHasCorr =
true;
705 if (
params.onlyKeepTheClosest && (min_dist<maxDistForCorrespondenceSquared))
707 nTotalCorrespondences++;
708 correspondences.push_back( closestCorr );
712 if (thisLocalHasCorr)
714 nOtherMapPointsWithCorrespondence++;
717 _sumSqrDist+= min_dist;
722 extraResults.correspondencesRatio = nOtherMapPointsWithCorrespondence /
static_cast<float>(nLocalPoints/
params.decimation_other_map_points);
723 extraResults.sumSqrDist = _sumSqrDist;
745 return e1.first > e2.first;
759 for (
int i=0;i<nSteps;i++)
761 float x = x1 + (x2-x1)*i/static_cast<float>(nSteps);
762 float y = y1 + (y2-y1)*i/static_cast<float>(nSteps);
767 return sumCost/
static_cast<float>(nSteps);
void BASE_IMPEXP memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) MRPT_NO_THROWS
An OS and compiler independent version of "memcpy".
float y_max
The limits of the grid in "units" (meters)
Virtual base for specifying the kind and parameters of one map (normally, to be inserted into mrpt::m...
Parameters for CMetricMap::compute3DMatchingRatio()
void clear()
Erase the contents of all the cells.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
float getResolution() const
Returns the resolution of the grid map.
#define ASSERT_ABOVE_(__A, __B)
mrpt::maps::COccupancyGridMap2D::TInsertionOptions insertionOpts
Observations insertion options.
mrpt::utils::CDynamicGrid< uint8_t > m_basis_map
Used for Voronoi calculation.Same struct as "map", but contains a "0" if not a basis point...
float resolution
See COccupancyGridMap2D::COccupancyGridMap2D.
float resolution
Cell size, i.e. resolution of the grid map.
static double H(double p)
Entropy computation internal function:
#define ASSERT_BELOW_(__A, __B)
bool derivedFrom(const TRuntimeClassId *pBaseClass) const
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
#define MRPT_NO_THROWS
C++11 noexcept: Used after member declarations.
void updateCell(int x, int y, float v)
Performs the Bayesian fusion of a new observation of a cell.
const Scalar * const_iterator
static const cellType OCCGRID_CELLTYPE_MAX
IMPLEMENTS_SERIALIZABLE(CLogFileRecord_FullEval, CHolonomicLogFileRecord, mrpt::nav) IMPLEMENTS_SERIALIZABLE(CHolonomicFullEval
GLsizei GLsizei GLuint * obj
void freeMap()
Frees the dynamic memory buffers of map.
std::vector< cellType > map
Store of cell occupancy values. Order: row by row, from left to right.
This class allows loading and storing values and vectors of different types from a configuration text...
T square(const T x)
Inline function for the square of a number.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
This base provides a set of functions for maths stuff.
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
struct MAPS_IMPEXP mrpt::maps::COccupancyGridMap2D::TUpdateCellsInfoChangeOnly updateInfoChangeOnly
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
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...
GLsizei const GLchar ** string
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
bool precomputedLikelihoodToBeRecomputed
#define CLASS_ID(class_name)
Access to runtime class ID for a defined class name.
bool isEmpty() const MRPT_OVERRIDE
Returns true upon map construction or after calling clear(), the return changes to false upon success...
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) MRPT_NO_THROWS
Change the size of gridmap, maintaining previous contents.
A class for storing an occupancy grid map.
static const cellType OCCGRID_CELLTYPE_MIN
Discrete to float conversion factors: The min/max values of the integer cell type, eg.
#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...
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.
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.
virtual ~COccupancyGridMap2D()
Destructor.
static std::vector< float > entropyTable
Internally used to speed-up entropy calculation.
virtual void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::utils::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const MRPT_OVERRIDE
See the base class for more details: In this class it is implemented as correspondences of the passed...
bool m_is_empty
True upon construction; used by isEmpty()
mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions likelihoodOpts
Probabilistic observation likelihood options.
uint32_t size_y
The size of the grid in cells.
GLsizei GLsizei GLchar * source
float idx2y(const size_t cy) const
int round(const T value)
Returns the closer integer (int) to x.
void computeEntropy(TEntropyInfo &info) const
Computes the entropy and related values of this grid map.
void fill(float default_value=0.5f)
Fills all the cells with a default value.
float getPos(float x, float y) const
Read the real valued [0,1] contents of a cell, given its coordinates.
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.
uint16_t cellTypeUnsigned
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...
Parameters for the determination of matchings between point clouds, etc.
virtual const mrpt::utils::TRuntimeClassId * GetRuntimeClass() const
Returns information about the class of an object in runtime.
Used for returning entropy related information.
std::pair< double, mrpt::math::TPoint2D > TPairLikelihoodIndex
Auxiliary private class.
bool MAPS_IMPEXP operator<(const COccupancyGridMap2D::TPairLikelihoodIndex &e1, const COccupancyGridMap2D::TPairLikelihoodIndex &e2)
GLenum const GLfloat * params
int16_t cellType
The type of the map cells:
int x2idx(float x) const
Transform a coordinate value into a cell index.
double phi
Orientation (rads)
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
float getCell(int x, int y) const
Read the real valued [0,1] contents of a cell, given its index.
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams ¶ms) const MRPT_OVERRIDE
See docs in base class: in this class this always returns 0.
static float l2p(const cellType l)
Scales an integer representation of the log-odd into a real valued probability in [0...
virtual void internal_clear() MRPT_OVERRIDE
Clear the map: It set all cells to their default occupancy value (0.5), without changing the resoluti...
One static instance of this struct should exist in any class implementing CLogOddsGridMap2D to hold t...
bool enabled
If set to false (default), this struct is not used. Set to true only when measuring the info of an ob...
mrpt::utils::CDynamicGrid< uint16_t > m_voronoi_diagram
Used to store the Voronoi diagram.