55     m_likelihoodCacheOutDated = 
true;
    59         robotPose2D = 
CPose2D(*robotPose);
    60         robotPose3D = (*robotPose);
    68     const float maxCertainty = insertionOptions.maxOccupancyUpdateCertainty;
    69     float maxFreeCertainty = insertionOptions.maxFreenessUpdateCertainty;
    70     if (maxFreeCertainty == .0f) maxFreeCertainty = maxCertainty;
    71     float maxFreeCertaintyNoEcho = insertionOptions.maxFreenessInvalidRanges;
    72     if (maxFreeCertaintyNoEcho == .0f) maxFreeCertaintyNoEcho = maxCertainty;
    75         std::max<cellType>(1, p2l(maxFreeCertainty));
    76     cellType logodd_observation_occupied =
    77         3 * std::max<cellType>(1, p2l(maxCertainty));
    79         std::max<cellType>(1, p2l(maxFreeCertaintyNoEcho));
    83         OCCGRID_CELLTYPE_MIN + logodd_observation_occupied;
    85         OCCGRID_CELLTYPE_MAX -
    86         std::max(logodd_noecho_free, logodd_observation_free);
    96         CPose3D sensorPose3D = robotPose3D + o.sensorPose;
    97         CPose2D laserPose(sensorPose3D);
   102             o.isPlanarScan(insertionOptions.horizontalTolerance);
   103         unsigned int decimation = insertionOptions.decimation;
   106         if (insertionOptions.useMapAltitude &&
   107             fabs(insertionOptions.mapAltitude - sensorPose3D.z()) > 0.001)
   109             reallyInsert = 
false;
   115         bool sensorIsBottomwards =
   123             int cx, cy, N = o.getScanSize();
   127             const float maxDistanceInsertion =
   128                 insertionOptions.maxDistanceInsertion;
   129             const bool invalidAsFree =
   130                 insertionOptions.considerInvalidRangesAsFreeSpace;
   131             float new_x_max, new_x_min;
   132             float new_y_max, new_y_min;
   133             float last_valid_range = maxDistanceInsertion;
   135             int K = updateInfoChangeOnly.enabled
   136                         ? updateInfoChangeOnly.laserRaysSkip
   138             size_t idx, nRanges = o.getScanSize();
   142             const float px = 
d2f(laserPose.
x());
   143             const float py = 
d2f(laserPose.
y());
   145 #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG)   151             if (!insertionOptions.wideningBeamsWithDistance)
   164                 float *scanPoint_x, *scanPoint_y;
   166                 if (o.rightToLeft ^ sensorIsBottomwards)
   168                     A = 
d2f(laserPose.
phi() - 0.5f * o.aperture);
   169                     dAK = K * o.aperture / N;
   173                     A = 
d2f(laserPose.
phi() + 0.5f * o.aperture);
   174                     dAK = -K * o.aperture / N;
   177                 new_x_max = -(numeric_limits<float>::max)();
   178                 new_x_min = (numeric_limits<float>::max)();
   179                 new_y_max = -(numeric_limits<float>::max)();
   180                 new_y_min = (numeric_limits<float>::max)();
   182                 for (idx = 0, scanPoint_x = scanPoints_x,
   183                     scanPoint_y = scanPoints_y;
   185                      idx += K, scanPoint_x += K, scanPoint_y += K)
   187                     if (o.getScanRangeValidity(idx))
   189                         curRange = o.getScanRange(idx);
   190                         float R = std::min(maxDistanceInsertion, curRange);
   192                         *scanPoint_x = px + cos(
A) * 
R;
   193                         *scanPoint_y = py + sin(
A) * 
R;
   194                         last_valid_range = curRange;
   202                                 maxDistanceInsertion, 0.5f * last_valid_range);
   203                             *scanPoint_x = px + cos(
A) * 
R;
   204                             *scanPoint_y = py + sin(
A) * 
R;
   215                     new_x_max = max(new_x_max, *scanPoint_x);
   216                     new_x_min = min(new_x_min, *scanPoint_x);
   217                     new_y_max = max(new_y_max, *scanPoint_y);
   218                     new_y_min = min(new_y_min, *scanPoint_y);
   222                 float securMargen = 15 * resolution;
   224                 if (new_x_max > x_max - securMargen)
   225                     new_x_max += 2 * securMargen;
   228                 if (new_x_min < x_min + securMargen)
   233                 if (new_y_max > y_max - securMargen)
   234                     new_y_max += 2 * securMargen;
   237                 if (new_y_min < y_min + securMargen)
   245                 resizeGrid(new_x_min, new_x_max, new_y_min, new_y_max, 0.5);
   249                 unsigned theMapSize_x = size_x;
   256                 for (idx = 0; idx < nRanges; idx += K)
   258                     if (!o.getScanRangeValidity(idx) && !invalidAsFree)
   266                     int trg_cx = x2idx(scanPoints_x[idx]);
   267                     int trg_cy = y2idx(scanPoints_y[idx]);
   271                         static_cast<unsigned int>(trg_cx) < size_x &&
   272                         static_cast<unsigned int>(trg_cy) < size_y);
   276                     int Acx = trg_cx - cx;
   277                     int Acy = trg_cy - cy;
   279                     int Acx_ = std::abs(Acx);
   280                     int Acy_ = std::abs(Acy);
   282                     int nStepsRay = max(Acx_, Acy_);
   283                     if (!nStepsRay) 
continue;  
   286                     float N_1 = 1.0f / nStepsRay;  
   290                         (Acx < 0 ? -1 : +1) * 
round((Acx_ << 
FRBITS) * N_1);
   292                         (Acy < 0 ? -1 : +1) * 
round((Acy_ << 
FRBITS) * N_1);
   296                     const auto logodd_free = o.getScanRangeValidity(idx)
   297                                                  ? logodd_observation_free
   298                                                  : logodd_noecho_free;
   300                     for (
int nStep = 0; nStep < nStepsRay; nStep++)
   302                         updateCell_fast_free(
   303                             cx, cy, logodd_free, logodd_thres_free, theMapArray,
   317                     if (o.getScanRangeValidity(idx) &&
   318                         o.getScanRange(idx) < maxDistanceInsertion)
   319                         updateCell_fast_occupied(
   320                             trg_cx, trg_cy, logodd_observation_occupied,
   321                             logodd_thres_occupied, theMapArray, theMapSize_x);
   335                 if (o.rightToLeft ^ sensorIsBottomwards)
   337                     A = 
d2f(laserPose.
phi()) - 0.5f * o.aperture;
   338                     dAK = K * o.aperture / N;
   342                     A = 
d2f(laserPose.
phi()) + 0.5f * o.aperture;
   343                     dAK = -K * o.aperture / N;
   346                 new_x_max = -(numeric_limits<float>::max)();
   347                 new_x_min = (numeric_limits<float>::max)();
   348                 new_y_max = -(numeric_limits<float>::max)();
   349                 new_y_min = (numeric_limits<float>::max)();
   351                 last_valid_range = maxDistanceInsertion;
   352                 for (idx = 0; idx < nRanges; idx += K)
   354                     float scanPoint_x, scanPoint_y;
   355                     if (o.getScanRangeValidity(idx))
   357                         curRange = o.getScanRange(idx);
   358                         float R = min(maxDistanceInsertion, curRange);
   360                         scanPoint_x = px + cos(
A) * 
R;
   361                         scanPoint_y = py + sin(
A) * 
R;
   362                         last_valid_range = curRange;
   370                                 maxDistanceInsertion, 0.5f * last_valid_range);
   371                             scanPoint_x = px + cos(
A) * 
R;
   372                             scanPoint_y = py + sin(
A) * 
R;
   383                     new_x_max = max(new_x_max, scanPoint_x);
   384                     new_x_min = min(new_x_min, scanPoint_x);
   385                     new_y_max = max(new_y_max, scanPoint_y);
   386                     new_y_min = min(new_y_min, scanPoint_y);
   390                 float securMargen = 15 * resolution;
   392                 if (new_x_max > x_max - securMargen)
   393                     new_x_max += 2 * securMargen;
   396                 if (new_x_min < x_min + securMargen)
   401                 if (new_y_max > y_max - securMargen)
   402                     new_y_max += 2 * securMargen;
   405                 if (new_y_min < y_min + securMargen)
   413                 resizeGrid(new_x_min, new_x_max, new_y_min, new_y_max, 0.5);
   417                 unsigned theMapSize_x = size_x;
   426                 if (o.rightToLeft ^ sensorIsBottomwards)
   428                     A = 
d2f(laserPose.
phi()) - 0.5f * o.aperture;
   429                     dAK = K * o.aperture / N;
   433                     A = 
d2f(laserPose.
phi()) + 0.5f * o.aperture;
   434                     dAK = -K * o.aperture / N;
   442                 last_valid_range = maxDistanceInsertion;
   444                 const float dA_2 = 0.5f * o.aperture / N;
   445                 for (idx = 0; idx < nRanges; idx += K, 
A += dAK)
   448                     if (o.getScanRangeValidity(idx))
   450                         curRange = o.getScanRange(idx);
   451                         last_valid_range = curRange;
   452                         theR = min(maxDistanceInsertion, curRange);
   460                                 maxDistanceInsertion, 0.5f * last_valid_range);
   465                     if (theR < resolution)
   478                     P1.
x = px + cos(
A - dA_2) * theR;
   479                     P1.
y = py + sin(
A - dA_2) * theR;
   481                     P2.
x = px + cos(
A + dA_2) * theR;
   482                     P2.
y = py + sin(
A + dA_2) * theR;
   485                     if (P2.
y < P1.
y) std::swap(P2, P1);
   486                     if (P2.
y < P0.
y) std::swap(P2, P0);
   487                     if (P1.
y < P0.
y) std::swap(P1, P0);
   497 #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG)   500                         static_cast<unsigned int>(P0.
cx) < size_x &&
   501                         static_cast<unsigned int>(P0.
cy) < size_y);
   503                         static_cast<unsigned int>(P1.
cx) < size_x &&
   504                         static_cast<unsigned int>(P1.
cy) < size_y);
   506                         static_cast<unsigned int>(P2.
cx) < size_x &&
   507                         static_cast<unsigned int>(P2.
cy) < size_y);
   517                     if (P0.
cy == P2.
cy && P0.
cy == P1.
cy)
   523                         for (
int ccx = min_cx; ccx <= max_cx; ccx++)
   524                             updateCell_fast_free(
   525                                 ccx, P0.
cy, logodd_observation_free,
   526                                 logodd_thres_free, theMapArray, theMapSize_x);
   534                                 (P1.
y - P0.
y) * (P2.
x - P0.
x) / (P2.
y - P0.
y);
   536                         P1b.
cx = x2idx(P1b.
x);
   537                         P1b.
cy = y2idx(P1b.
y);
   542                         const int Acx01 = P1.
cx - P0.
cx;
   543                         const int Acy01 = P1.
cy - P0.
cy;
   544                         const int Acx01b = P1b.
cx - P0.
cx;
   548                         const float inv_N_01 =
   550                                         std::abs(Acx01), std::abs(Acy01),
   553                         const int frAcx01 = 
round(
   554                             (Acx01 << 
FRBITS) * inv_N_01);  
   555                         const int frAcy01 = 
round(
   556                             (Acy01 << 
FRBITS) * inv_N_01);  
   557                         const int frAcx01b = 
round(
   558                             (Acx01b << 
FRBITS) * inv_N_01);  
   568                         int frAx_R1 = 0, frAx_R2 = 0;  
   569                         int frAy_R1 = frAcy01;
   599                         int last_insert_cy = -1;
   603                             if (last_insert_cy !=
   606                                 last_insert_cy = R1.cy;
   609                                 for (
int ccx = R1.cx; ccx <= R2.cx; ccx++)
   610                                     updateCell_fast_free(
   611                                         ccx, R1.cy, logodd_observation_free,
   612                                         logodd_thres_free, theMapArray,
   623                         } 
while (R1.cy < P1.
cy);
   632                         const int Acx12 = P2.
cx - P1.
cx;
   633                         const int Acy12 = P2.
cy - P1.
cy;
   634                         const int Acx1b2 = P2.
cx - P1b.
cx;
   638                         const float inv_N_12 =
   640                                         std::abs(Acx12), std::abs(Acy12),
   643                         const int frAcx12 = 
round(
   644                             (Acx12 << 
FRBITS) * inv_N_12);  
   645                         const int frAcy12 = 
round(
   646                             (Acy12 << 
FRBITS) * inv_N_12);  
   647                         const int frAcx1b2 = 
round(
   648                             (Acx1b2 << 
FRBITS) * inv_N_12);  
   687                         last_insert_cy = -100;
   692                             if (last_insert_cy !=
   696                                 last_insert_cy = R1.cy;
   697                                 for (
int ccx = R1.cx; ccx <= R2.cx; ccx++)
   698                                     updateCell_fast_free(
   699                                         ccx, R1.cy, logodd_observation_free,
   700                                         logodd_thres_free, theMapArray,
   711                         } 
while (R1.cy <= P2.
cy);
   721                     if (o.getScanRangeValidity(idx) &&
   722                         o.getScanRange(idx) < maxDistanceInsertion)
   726                         P1.
x = px + cos(
A - dA_2) * theR;
   727                         P1.
y = py + sin(
A - dA_2) * theR;
   729                         P2.
x = px + cos(
A + dA_2) * theR;
   730                         P2.
y = py + sin(
A + dA_2) * theR;
   737 #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG)   740                             static_cast<unsigned int>(P1.
cx) < size_x &&
   741                             static_cast<unsigned int>(P1.
cy) < size_y);
   743                             static_cast<unsigned int>(P2.
cx) < size_x &&
   744                             static_cast<unsigned int>(P2.
cy) < size_y);
   748                         if (P2.
cx == P1.
cx && P2.
cy == P1.
cy)
   750                             updateCell_fast_occupied(
   751                                 P1.
cx, P1.
cy, logodd_observation_occupied,
   752                                 logodd_thres_occupied, theMapArray,
   760                             const int AcxE = P2.
cx - P1.
cx;
   761                             const int AcyE = P2.
cy - P1.
cy;
   765                                 (max(std::abs(AcxE), std::abs(AcyE)) + 1);
   766                             const float inv_N_12 =
   768                             const int frAcxE = 
round(
   769                                 (AcxE << 
FRBITS) * inv_N_12);  
   770                             const int frAcyE = 
round(
   771                                 (AcyE << 
FRBITS) * inv_N_12);  
   778                             for (
int nStep = 0; nStep <= nSteps; nStep++)
   780                                 updateCell_fast_occupied(
   781                                     R1.cx, R1.cy, logodd_observation_occupied,
   782                                     logodd_thres_occupied, theMapArray,
   812         o.getSensorPose(spose);
   813         CPose3D sensorPose3D = robotPose3D + spose;
   814         CPose2D laserPose(sensorPose3D);
   818         bool reallyInsert = 
true;
   819         unsigned int decimation = insertionOptions.decimation;
   822         if (insertionOptions.useMapAltitude &&
   823             fabs(insertionOptions.mapAltitude - sensorPose3D.z()) > 0.001)
   825             reallyInsert = 
false;
   838             const float maxDistanceInsertion =
   839                 insertionOptions.maxDistanceInsertion;
   840             const bool invalidAsFree =
   841                 insertionOptions.considerInvalidRangesAsFreeSpace;
   842             float new_x_max, new_x_min;
   843             float new_y_max, new_y_min;
   844             float last_valid_range = maxDistanceInsertion;
   846             int K = updateInfoChangeOnly.enabled
   847                         ? updateInfoChangeOnly.laserRaysSkip
   849             size_t idx, nRanges = o.sensedData.size();
   853             px = 
d2f(laserPose.
x());
   854             py = 
d2f(laserPose.
y());
   856 #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG)   868             new_x_max = -(numeric_limits<float>::max)();
   869             new_x_min = (numeric_limits<float>::max)();
   870             new_y_max = -(numeric_limits<float>::max)();
   871             new_y_min = (numeric_limits<float>::max)();
   873             last_valid_range = maxDistanceInsertion;
   875             for (idx = 0; idx < nRanges; idx += K)
   877                 float scanPoint_x, scanPoint_y;
   878                 if (o.sensedData[idx].sensedDistance < maxDistanceInsertion)
   880                     curRange = o.sensedData[idx].sensedDistance;
   881                     float R = min(maxDistanceInsertion, curRange);
   883                     scanPoint_x = px + cos(
A) * 
R;
   884                     scanPoint_y = py + sin(
A) * 
R;
   885                     last_valid_range = curRange;
   893                             min(maxDistanceInsertion, 0.5f * last_valid_range);
   894                         scanPoint_x = px + cos(
A) * 
R;
   895                         scanPoint_y = py + sin(
A) * 
R;
   906                 new_x_max = max(new_x_max, scanPoint_x);
   907                 new_x_min = min(new_x_min, scanPoint_x);
   908                 new_y_max = max(new_y_max, scanPoint_y);
   909                 new_y_min = min(new_y_min, scanPoint_y);
   913             float securMargen = 15 * resolution;
   915             if (new_x_max > x_max - securMargen)
   916                 new_x_max += 2 * securMargen;
   919             if (new_x_min < x_min + securMargen)
   924             if (new_y_max > y_max - securMargen)
   925                 new_y_max += 2 * securMargen;
   928             if (new_y_min < y_min + securMargen)
   936             resizeGrid(new_x_min, new_x_max, new_y_min, new_y_max, 0.5);
   940             unsigned theMapSize_x = size_x;
   948             A = 
d2f(laserPose.
phi()) - 0.5f * o.sensorConeApperture;
   956             last_valid_range = maxDistanceInsertion;
   958             const float dA_2 = 0.5f * o.sensorConeApperture;
   959             for (idx = 0; idx < nRanges; idx += K, 
A += dAK)
   962                 if (o.sensedData[idx].sensedDistance < maxDistanceInsertion)
   964                     curRange = o.sensedData[idx].sensedDistance;
   965                     last_valid_range = curRange;
   966                     theR = min(maxDistanceInsertion, curRange);
   974                             min(maxDistanceInsertion, 0.5f * last_valid_range);
   979                 if (theR < resolution)
   990                 P1.x = px + cos(
A - dA_2) * theR;
   991                 P1.y = py + sin(
A - dA_2) * theR;
   993                 P2.x = px + cos(
A + dA_2) * theR;
   994                 P2.y = py + sin(
A + dA_2) * theR;
   997                 if (P2.y < P1.y) std::swap(P2, P1);
   998                 if (P2.y < P0.
y) std::swap(P2, P0);
   999                 if (P1.y < P0.
y) std::swap(P1, P0);
  1002                 P0.
cx = x2idx(P0.
x);
  1003                 P0.
cy = y2idx(P0.
y);
  1004                 P1.cx = x2idx(P1.x);
  1005                 P1.cy = y2idx(P1.y);
  1006                 P2.cx = x2idx(P2.x);
  1007                 P2.cy = y2idx(P2.y);
  1009 #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG)  1012                     static_cast<unsigned int>(P0.
cx) < size_x &&
  1013                     static_cast<unsigned int>(P0.
cy) < size_y);
  1015                     static_cast<unsigned int>(P1.cx) < size_x &&
  1016                     static_cast<unsigned int>(P1.cy) < size_y);
  1018                     static_cast<unsigned int>(P2.cx) < size_x &&
  1019                     static_cast<unsigned int>(P2.cy) < size_y);
  1029                 if (P0.
cy == P2.cy && P0.
cy == P1.cy)
  1032                     int min_cx = 
min3(P0.
cx, P1.cx, P2.cx);
  1033                     int max_cx = 
max3(P0.
cx, P1.cx, P2.cx);
  1035                     for (
int ccx = min_cx; ccx <= max_cx; ccx++)
  1036                         updateCell_fast_free(
  1037                             ccx, P0.
cy, logodd_observation_free,
  1038                             logodd_thres_free, theMapArray, theMapSize_x);
  1046                         P0.
x + (P1.y - P0.
y) * (P2.x - P0.
x) / (P2.y - P0.
y);
  1048                     P1b.cx = x2idx(P1b.x);
  1049                     P1b.cy = y2idx(P1b.y);
  1054                     const int Acx01 = P1.cx - P0.
cx;
  1055                     const int Acy01 = P1.cy - P0.
cy;
  1056                     const int Acx01b = P1b.cx - P0.
cx;
  1060                     const float inv_N_01 =
  1062                                     std::abs(Acx01), std::abs(Acy01),
  1069                     const int frAcx01b =
  1080                     int frAx_R1 = 0, frAx_R2 = 0;  
  1081                     int frAy_R1 = frAcy01;
  1107                         R2.frX = P1.cx << 
FRBITS;
  1110                     int last_insert_cy = -1;
  1114                         if (last_insert_cy !=
  1117                             last_insert_cy = R1.cy;
  1120                             for (
int ccx = R1.cx; ccx <= R2.cx; ccx++)
  1121                                 updateCell_fast_free(
  1122                                     ccx, R1.cy, logodd_observation_free,
  1123                                     logodd_thres_free, theMapArray,
  1131                         R1.cx = R1.frX >> 
FRBITS;
  1132                         R1.cy = R1.frY >> 
FRBITS;
  1133                         R2.cx = R2.frX >> 
FRBITS;
  1134                     } 
while (R1.cy < P1.cy);
  1142                     const int Acx12 = P2.cx - P1.cx;
  1143                     const int Acy12 = P2.cy - P1.cy;
  1144                     const int Acx1b2 = P2.cx - P1b.cx;
  1148                     const float inv_N_12 =
  1150                                     std::abs(Acx12), std::abs(Acy12),
  1157                     const int frAcx1b2 =
  1192                     R1.frX = R1.cx << 
FRBITS;
  1193                     R1.frY = R1.cy << 
FRBITS;
  1194                     R2.frX = R2.cx << 
FRBITS;
  1195                     R2.frY = R2.cy << 
FRBITS;
  1197                     last_insert_cy = -100;
  1202                         if (last_insert_cy !=
  1206                             last_insert_cy = R1.cy;
  1207                             for (
int ccx = R1.cx; ccx <= R2.cx; ccx++)
  1208                                 updateCell_fast_free(
  1209                                     ccx, R1.cy, logodd_observation_free,
  1210                                     logodd_thres_free, theMapArray,
  1218                         R1.cx = R1.frX >> 
FRBITS;
  1219                         R1.cy = R1.frY >> 
FRBITS;
  1220                         R2.cx = R2.frX >> 
FRBITS;
  1221                     } 
while (R1.cy <= P2.cy);
  1231                 if (o.sensedData[idx].sensedDistance < maxDistanceInsertion)
  1235                     P1.x = px + cos(
A - dA_2) * theR;
  1236                     P1.y = py + sin(
A - dA_2) * theR;
  1238                     P2.x = px + cos(
A + dA_2) * theR;
  1239                     P2.y = py + sin(
A + dA_2) * theR;
  1241                     P1.cx = x2idx(P1.x);
  1242                     P1.cy = y2idx(P1.y);
  1243                     P2.cx = x2idx(P2.x);
  1244                     P2.cy = y2idx(P2.y);
  1246 #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG)  1249                         static_cast<unsigned int>(P1.cx) < size_x &&
  1250                         static_cast<unsigned int>(P1.cy) < size_y);
  1252                         static_cast<unsigned int>(P2.cx) < size_x &&
  1253                         static_cast<unsigned int>(P2.cy) < size_y);
  1257                     if (P2.cx == P1.cx && P2.cy == P1.cy)
  1259                         updateCell_fast_occupied(
  1260                             P1.cx, P1.cy, logodd_observation_occupied,
  1261                             logodd_thres_occupied, theMapArray, theMapSize_x);
  1268                         const int AcxE = P2.cx - P1.cx;
  1269                         const int AcyE = P2.cy - P1.cy;
  1273                             (max(std::abs(AcxE), std::abs(AcyE)) + 1);
  1274                         const float inv_N_12 =
  1283                         R1.frX = R1.cx << 
FRBITS;
  1284                         R1.frY = R1.cy << 
FRBITS;
  1286                         for (
int nStep = 0; nStep <= nSteps; nStep++)
  1288                             updateCell_fast_occupied(
  1289                                 R1.cx, R1.cy, logodd_observation_occupied,
  1290                                 logodd_thres_occupied, theMapArray,
  1295                             R1.cx = R1.frX >> 
FRBITS;
  1296                             R1.cy = R1.frY >> 
FRBITS;
  1334         considerInvalidRangesAsFreeSpace, 
bool, 
iniFile, section);
  1347     std::ostream& 
out)
 const  1349     out << 
"\n----------- [COccupancyGridMap2D::TInsertionOptions] " A compile-time fixed-size numeric matrix container. 
 
Declares a class derived from "CObservation" that encapsules a single range measurement, and associated parameters. 
 
bool internal_insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose=nullptr) override
Insert the observation information into this map. 
 
Local stucture used in the next method (must be here for usage within STL stuff) 
 
const T min3(const T &A, const T &B, const T &C)
 
void OnPostSuccesfulInsertObs(const mrpt::obs::CObservation &) override
See base class. 
 
#define ASSERT_(f)
Defines an assertion mechanism. 
 
float d2f(const double d)
shortcut for static_cast<float>(double) 
 
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 MRPT_CHECK_NORMAL_NUMBER(v)
Throws an exception if the number is NaN, IND, or +/-INF, or return the same number otherwise...
 
double phi() const
Get the phi angle of the 2D pose (in radians) 
 
This namespace contains representation of robot actions and observations. 
 
string iniFile(myDataDir+string("benchmark-options.ini"))
 
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
 
double x() const
Common members of all points & poses classes. 
 
#define mrpt_alloca(nBytes)
In platforms and compilers with support to "alloca", allocate a memory block on the stack; if alloca ...
 
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
 
#define MRPT_LOAD_CONFIG_VAR_DEGREESf( variableName, configFileObject, sectionNameStr)
 
#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...
 
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream. 
 
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries. 
 
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
 
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
 
Declares a class that represents any robot's observation. 
 
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini" file. 
 
OccGridCellTraits::cellType cellType
The type of the map cells: 
 
MATRIX44 getHomogeneousMatrixVal() const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
 
#define mrpt_alloca_free(mem_block)
This method must be called to "free" each memory block allocated with "system::alloca": If the block ...
 
const T max3(const T &A, const T &B, const T &C)
 
for(unsigned int i=0;i< NUM_IMGS;i++)
 
int round(const T value)
Returns the closer integer (int) to x.