51 : insertionOptions(), likelihoodOptions(), m_x(), m_y(), m_z()
60 CPointsMap::~CPointsMap() =
default;
66 bool CPointsMap::save2D_to_text_file(
const string& file)
const 71 for (
unsigned int i = 0; i < m_x.size(); i++)
83 bool CPointsMap::save3D_to_text_file(
const string& file)
const 88 for (
unsigned int i = 0; i < m_x.size(); i++)
89 os::fprintf(f,
"%f %f %f\n", m_x[i], m_y[i], m_z[i]);
100 bool CPointsMap::load2Dor3D_from_text_file(
101 const std::string& file,
const bool is_3D)
108 if (!f)
return false;
111 char *ptr, *ptr1, *ptr2, *ptr3;
120 if (!fgets(str,
sizeof(str), f))
break;
124 while (ptr[0] && (ptr[0] ==
' ' || ptr[0] ==
'\t' || ptr[0] ==
'\r' ||
129 float xx = strtod(ptr, &ptr1);
132 float yy = strtod(ptr1, &ptr2);
137 this->insertPoint(xx, yy, 0);
141 float zz = strtod(ptr2, &ptr3);
144 this->insertPoint(xx, yy, zz);
165 mxArray* CPointsMap::writeToMatlab()
const 168 MRPT_TODO(
"Create 3xN array xyz of points coordinates")
169 const
char* fields[] = {
"x",
"y",
"z"};
170 mexplus::MxArray map_struct(
171 mexplus::MxArray::Struct(
sizeof(fields) /
sizeof(fields[0]), fields));
173 map_struct.set(
"x", m_x);
174 map_struct.set(
"y", m_y);
175 map_struct.set(
"z", m_z);
176 return map_struct.release();
186 void CPointsMap::getPoint(
size_t index,
float& x,
float& y)
const 192 void CPointsMap::getPoint(
size_t index,
float& x,
float& y,
float& z)
const 199 void CPointsMap::getPoint(
size_t index,
double& x,
double& y)
const 205 void CPointsMap::getPoint(
size_t index,
double& x,
double& y,
double& z)
const 216 void CPointsMap::getPointsBuffer(
217 size_t& outPointsCount,
const float*& xs,
const float*& ys,
218 const float*& zs)
const 220 outPointsCount =
size();
222 if (outPointsCount > 0)
230 xs = ys = zs =
nullptr;
237 void CPointsMap::clipOutOfRangeInZ(
float zMin,
float zMax)
239 const size_t n =
size();
240 vector<bool> deletionMask(n);
243 for (
size_t i = 0; i < n; i++)
244 deletionMask[i] = (m_z[i] < zMin || m_z[i] > zMax);
247 applyDeletionMask(deletionMask);
255 void CPointsMap::clipOutOfRange(
const TPoint2D& p,
float maxRange)
257 size_t i, n =
size();
258 vector<bool> deletionMask;
261 deletionMask.resize(n);
263 const auto max_sq = maxRange * maxRange;
266 for (i = 0; i < n; i++)
267 deletionMask[i] =
square(p.
x - m_x[i]) +
square(p.
y - m_y[i]) > max_sq;
270 applyDeletionMask(deletionMask);
275 void CPointsMap::determineMatching2D(
286 params.offset_other_map_points,
params.decimation_other_map_points);
288 const auto* otherMap =
static_cast<const CPointsMap*
>(otherMap2);
291 otherMapPose_.
x(), otherMapPose_.
y(), otherMapPose_.
phi());
293 const size_t nLocalPoints = otherMap->
size();
294 const size_t nGlobalPoints = this->
size();
295 float _sumSqrDist = 0;
296 size_t _sumSqrCount = 0;
297 size_t nOtherMapPointsWithCorrespondence =
300 float local_x_min = std::numeric_limits<float>::max(),
301 local_x_max = -std::numeric_limits<float>::max();
302 float global_x_min = std::numeric_limits<float>::max(),
303 global_x_max = -std::numeric_limits<float>::max();
304 float local_y_min = std::numeric_limits<float>::max(),
305 local_y_max = -std::numeric_limits<float>::max();
306 float global_y_min = std::numeric_limits<float>::max(),
307 global_y_max = -std::numeric_limits<float>::max();
309 double maxDistForCorrespondenceSquared;
310 float x_local, y_local;
311 unsigned int localIdx;
313 const float *x_other_it, *y_other_it, *z_other_it;
316 correspondences.clear();
317 correspondences.reserve(nLocalPoints);
318 extraResults.correspondencesRatio = 0;
321 _correspondences.reserve(nLocalPoints);
324 if (!nGlobalPoints || !nLocalPoints)
return;
326 const double sin_phi = sin(otherMapPose.phi);
327 const double cos_phi = cos(otherMapPose.phi);
335 size_t nPackets = nLocalPoints / 4;
337 Eigen::ArrayXf x_locals(nLocalPoints), y_locals(nLocalPoints);
340 const __m128 cos_4val = _mm_set1_ps(cos_phi);
341 const __m128 sin_4val = _mm_set1_ps(sin_phi);
342 const __m128 x0_4val = _mm_set1_ps(otherMapPose.x);
343 const __m128 y0_4val = _mm_set1_ps(otherMapPose.y);
346 __m128 x_mins = _mm_set1_ps(std::numeric_limits<float>::max());
347 __m128 x_maxs = _mm_set1_ps(std::numeric_limits<float>::min());
348 __m128 y_mins = x_mins;
349 __m128 y_maxs = x_maxs;
351 const float* ptr_in_x = &otherMap->m_x[0];
352 const float* ptr_in_y = &otherMap->m_y[0];
353 float* ptr_out_x = &x_locals[0];
354 float* ptr_out_y = &y_locals[0];
356 for (; nPackets; nPackets--, ptr_in_x += 4, ptr_in_y += 4, ptr_out_x += 4,
359 const __m128 xs = _mm_loadu_ps(ptr_in_x);
360 const __m128 ys = _mm_loadu_ps(ptr_in_y);
362 const __m128 lxs = _mm_add_ps(
364 _mm_sub_ps(_mm_mul_ps(xs, cos_4val), _mm_mul_ps(ys, sin_4val)));
365 const __m128 lys = _mm_add_ps(
367 _mm_add_ps(_mm_mul_ps(xs, sin_4val), _mm_mul_ps(ys, cos_4val)));
368 _mm_store_ps(ptr_out_x, lxs);
369 _mm_store_ps(ptr_out_y, lys);
371 x_mins = _mm_min_ps(x_mins, lxs);
372 x_maxs = _mm_max_ps(x_maxs, lxs);
373 y_mins = _mm_min_ps(y_mins, lys);
374 y_maxs = _mm_max_ps(y_maxs, lys);
378 alignas(MRPT_MAX_STATIC_ALIGN_BYTES)
float temp_nums[4];
380 _mm_store_ps(temp_nums, x_mins);
382 min(min(temp_nums[0], temp_nums[1]), min(temp_nums[2], temp_nums[3]));
383 _mm_store_ps(temp_nums, y_mins);
385 min(min(temp_nums[0], temp_nums[1]), min(temp_nums[2], temp_nums[3]));
386 _mm_store_ps(temp_nums, x_maxs);
388 max(max(temp_nums[0], temp_nums[1]), max(temp_nums[2], temp_nums[3]));
389 _mm_store_ps(temp_nums, y_maxs);
391 max(max(temp_nums[0], temp_nums[1]), max(temp_nums[2], temp_nums[3]));
394 for (
size_t k = 0; k < nLocalPoints % 4; k++)
396 float x = ptr_in_x[k];
397 float y = ptr_in_y[k];
398 float out_x = otherMapPose.x + cos_phi * x - sin_phi * y;
399 float out_y = otherMapPose.y + sin_phi * x + cos_phi * y;
401 local_x_min = std::min(local_x_min, out_x);
402 local_x_max = std::max(local_x_max, out_x);
404 local_y_min = std::min(local_y_min, out_y);
405 local_y_max = std::max(local_y_max, out_y);
407 ptr_out_x[k] = out_x;
408 ptr_out_y[k] = out_y;
414 const_cast<float*>(&otherMap->m_x[0]), otherMap->m_x.size(), 1);
416 const_cast<float*>(&otherMap->m_y[0]), otherMap->m_y.size(), 1);
418 Eigen::Array<float, Eigen::Dynamic, 1> x_locals =
419 otherMapPose.x + cos_phi * x_org.array() - sin_phi * y_org.array();
420 Eigen::Array<float, Eigen::Dynamic, 1> y_locals =
421 otherMapPose.y + sin_phi * x_org.array() + cos_phi * y_org.array();
423 local_x_min = x_locals.minCoeff();
424 local_y_min = y_locals.minCoeff();
425 local_x_max = x_locals.maxCoeff();
426 local_y_max = y_locals.maxCoeff();
430 float global_z_min, global_z_max;
432 global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
437 if (local_x_min > global_x_max || local_x_max < global_x_min ||
438 local_y_min > global_y_max || local_y_max < global_y_min)
443 for (localIdx =
params.offset_other_map_points,
444 x_other_it = &otherMap->m_x[
params.offset_other_map_points],
445 y_other_it = &otherMap->m_y[
params.offset_other_map_points],
446 z_other_it = &otherMap->m_z[
params.offset_other_map_points];
447 localIdx < nLocalPoints;
448 x_other_it +=
params.decimation_other_map_points,
449 y_other_it +=
params.decimation_other_map_points,
450 z_other_it +=
params.decimation_other_map_points,
451 localIdx +=
params.decimation_other_map_points)
454 x_local = x_locals[localIdx];
455 y_local = y_locals[localIdx];
464 float tentativ_err_sq;
465 unsigned int tentativ_this_idx = kdTreeClosestPoint2D(
471 maxDistForCorrespondenceSquared =
square(
472 params.maxAngularDistForCorrespondence *
476 params.maxDistForCorrespondence);
479 if (tentativ_err_sq < maxDistForCorrespondenceSquared)
482 _correspondences.resize(_correspondences.size() + 1);
487 p.
this_x = m_x[tentativ_this_idx];
488 p.
this_y = m_y[tentativ_this_idx];
489 p.
this_z = m_z[tentativ_this_idx];
499 nOtherMapPointsWithCorrespondence++;
512 if (
params.onlyUniqueRobust)
515 params.onlyKeepTheClosest,
516 "ERROR: onlyKeepTheClosest must be also set to true when " 517 "onlyUniqueRobust=true.");
519 nGlobalPoints, correspondences);
523 correspondences.swap(_correspondences);
529 extraResults.sumSqrDist =
530 _sumSqrDist /
static_cast<double>(_sumSqrCount);
532 extraResults.sumSqrDist = 0;
535 extraResults.correspondencesRatio =
params.decimation_other_map_points *
536 nOtherMapPointsWithCorrespondence /
545 void CPointsMap::changeCoordinatesReference(
const CPose2D& newBase)
547 const size_t N = m_x.size();
549 const CPose3D newBase3D(newBase);
551 for (
size_t i = 0; i < N; i++)
553 m_x[i], m_y[i], m_z[i],
554 m_x[i], m_y[i], m_z[i]
563 void CPointsMap::changeCoordinatesReference(
const CPose3D& newBase)
565 const size_t N = m_x.size();
567 for (
size_t i = 0; i < N; i++)
569 m_x[i], m_y[i], m_z[i],
570 m_x[i], m_y[i], m_z[i]
579 void CPointsMap::changeCoordinatesReference(
583 changeCoordinatesReference(newBase);
589 bool CPointsMap::isEmpty()
const {
return m_x.empty(); }
593 CPointsMap::TInsertionOptions::TInsertionOptions()
594 : horizontalTolerance(0.05_deg)
603 const int8_t version = 0;
606 out << minDistBetweenLaserPoints << addToExistingPointsMap
607 << also_interpolate << disableDeletion << fuseWithExisting
608 << isPlanarMap << horizontalTolerance << maxDistForInterpolatePoints
609 << insertInvalidPoints;
621 in >> minDistBetweenLaserPoints >> addToExistingPointsMap >>
622 also_interpolate >> disableDeletion >> fuseWithExisting >>
623 isPlanarMap >> horizontalTolerance >>
624 maxDistForInterpolatePoints >> insertInvalidPoints;
639 const int8_t version = 0;
641 out << sigma_dist << max_corr_distance << decimation;
653 in >> sigma_dist >> max_corr_distance >> decimation;
664 const int8_t version = 0;
678 in >> point_size >> this->color;
689 out <<
"\n----------- [CPointsMap::TInsertionOptions] ------------ \n\n";
708 out <<
"\n----------- [CPointsMap::TLikelihoodOptions] ------------ \n\n";
717 out <<
"\n----------- [CPointsMap::TRenderOptions] ------------ \n\n";
775 obj->loadFromPointsMap(
this);
778 obj->enableColorFromZ(
false);
784 obj->loadFromPointsMap(
this);
788 obj->recolorizeByCoordinate(
822 float maxDistSq = 0, d;
823 for (
auto X =
m_x.begin(), Y =
m_y.begin(), Z =
m_z.begin();
824 X !=
m_x.end(); ++X, ++Y, ++Z)
827 maxDistSq = max(d, maxDistSq);
840 vector<float>& xs, vector<float>& ys,
size_t decimation)
const 846 xs = vector<float>(
m_x.begin(),
m_x.end());
847 ys = vector<float>(
m_y.begin(),
m_y.end());
851 size_t N =
m_x.size() / decimation;
856 auto X =
m_x.begin();
857 auto Y =
m_y.begin();
858 for (
auto oX = xs.begin(), oY = ys.begin(); oX != xs.end();
859 X += decimation, Y += decimation, ++oX, ++oY)
872 float x0,
float y0)
const 880 float x1, y1, x2, y2, d1, d2;
891 if (d12 > 0.20f * 0.20f || d12 < 0.03f * 0.03f)
897 double interp_x, interp_y;
915 float& min_x,
float& max_x,
float& min_y,
float& max_y,
float& min_z,
920 const size_t nPoints =
m_x.size();
935 size_t nPackets = nPoints / 4;
938 __m128 x_mins = _mm_set1_ps(std::numeric_limits<float>::max());
939 __m128 x_maxs = _mm_set1_ps(std::numeric_limits<float>::min());
940 __m128 y_mins = x_mins, y_maxs = x_maxs;
941 __m128 z_mins = x_mins, z_maxs = x_maxs;
943 const float* ptr_in_x = &
m_x[0];
944 const float* ptr_in_y = &
m_y[0];
945 const float* ptr_in_z = &
m_z[0];
948 nPackets--, ptr_in_x += 4, ptr_in_y += 4, ptr_in_z += 4)
950 const __m128 xs = _mm_loadu_ps(ptr_in_x);
951 x_mins = _mm_min_ps(x_mins, xs);
952 x_maxs = _mm_max_ps(x_maxs, xs);
954 const __m128 ys = _mm_loadu_ps(ptr_in_y);
955 y_mins = _mm_min_ps(y_mins, ys);
956 y_maxs = _mm_max_ps(y_maxs, ys);
958 const __m128 zs = _mm_loadu_ps(ptr_in_z);
959 z_mins = _mm_min_ps(z_mins, zs);
960 z_maxs = _mm_max_ps(z_maxs, zs);
964 alignas(MRPT_MAX_STATIC_ALIGN_BYTES)
float temp_nums[4];
966 _mm_store_ps(temp_nums, x_mins);
968 min(min(temp_nums[0], temp_nums[1]),
969 min(temp_nums[2], temp_nums[3]));
970 _mm_store_ps(temp_nums, y_mins);
972 min(min(temp_nums[0], temp_nums[1]),
973 min(temp_nums[2], temp_nums[3]));
974 _mm_store_ps(temp_nums, z_mins);
976 min(min(temp_nums[0], temp_nums[1]),
977 min(temp_nums[2], temp_nums[3]));
978 _mm_store_ps(temp_nums, x_maxs);
980 max(max(temp_nums[0], temp_nums[1]),
981 max(temp_nums[2], temp_nums[3]));
982 _mm_store_ps(temp_nums, y_maxs);
984 max(max(temp_nums[0], temp_nums[1]),
985 max(temp_nums[2], temp_nums[3]));
986 _mm_store_ps(temp_nums, z_maxs);
988 max(max(temp_nums[0], temp_nums[1]),
989 max(temp_nums[2], temp_nums[3]));
992 for (
size_t k = 0; k < nPoints % 4; k++)
1006 (std::numeric_limits<float>::max)();
1009 -(std::numeric_limits<float>::max)();
1011 for (
auto xi =
m_x.begin(), yi =
m_y.begin(), zi =
m_z.begin();
1012 xi !=
m_x.end(); xi++, yi++, zi++)
1049 params.offset_other_map_points,
params.decimation_other_map_points);
1052 const auto* otherMap =
static_cast<const CPointsMap*
>(otherMap2);
1054 const size_t nLocalPoints = otherMap->
size();
1055 const size_t nGlobalPoints = this->
size();
1056 float _sumSqrDist = 0;
1057 size_t _sumSqrCount = 0;
1058 size_t nOtherMapPointsWithCorrespondence =
1061 float local_x_min = std::numeric_limits<float>::max(),
1062 local_x_max = -std::numeric_limits<float>::max();
1063 float local_y_min = std::numeric_limits<float>::max(),
1064 local_y_max = -std::numeric_limits<float>::max();
1065 float local_z_min = std::numeric_limits<float>::max(),
1066 local_z_max = -std::numeric_limits<float>::max();
1068 double maxDistForCorrespondenceSquared;
1071 correspondences.clear();
1072 correspondences.reserve(nLocalPoints);
1075 _correspondences.reserve(nLocalPoints);
1078 if (!nGlobalPoints || !nLocalPoints)
return;
1082 vector<float> x_locals(nLocalPoints), y_locals(nLocalPoints),
1083 z_locals(nLocalPoints);
1085 for (
unsigned int localIdx =
params.offset_other_map_points;
1086 localIdx < nLocalPoints;
1087 localIdx +=
params.decimation_other_map_points)
1089 float x_local, y_local, z_local;
1091 otherMap->m_x[localIdx], otherMap->m_y[localIdx],
1092 otherMap->m_z[localIdx], x_local, y_local, z_local);
1094 x_locals[localIdx] = x_local;
1095 y_locals[localIdx] = y_local;
1096 z_locals[localIdx] = z_local;
1099 local_x_min = min(local_x_min, x_local);
1100 local_x_max = max(local_x_max, x_local);
1101 local_y_min = min(local_y_min, y_local);
1102 local_y_max = max(local_y_max, y_local);
1103 local_z_min = min(local_z_min, z_local);
1104 local_z_max = max(local_z_max, z_local);
1108 float global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1111 global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1116 if (local_x_min > global_x_max || local_x_max < global_x_min ||
1117 local_y_min > global_y_max || local_y_max < global_y_min)
1122 for (
unsigned int localIdx =
params.offset_other_map_points;
1123 localIdx < nLocalPoints;
1124 localIdx +=
params.decimation_other_map_points)
1127 const float x_local = x_locals[localIdx];
1128 const float y_local = y_locals[localIdx];
1129 const float z_local = z_locals[localIdx];
1137 float tentativ_err_sq;
1139 x_local, y_local, z_local,
1144 maxDistForCorrespondenceSquared =
square(
1145 params.maxAngularDistForCorrespondence *
1146 params.angularDistPivotPoint.distanceTo(
1147 TPoint3D(x_local, y_local, z_local)) +
1148 params.maxDistForCorrespondence);
1151 if (tentativ_err_sq < maxDistForCorrespondenceSquared)
1154 _correspondences.resize(_correspondences.size() + 1);
1164 p.
other_x = otherMap->m_x[localIdx];
1165 p.
other_y = otherMap->m_y[localIdx];
1166 p.
other_z = otherMap->m_z[localIdx];
1171 nOtherMapPointsWithCorrespondence++;
1185 if (
params.onlyUniqueRobust)
1188 params.onlyKeepTheClosest,
1189 "ERROR: onlyKeepTheClosest must be also set to true when " 1190 "onlyUniqueRobust=true.");
1192 nGlobalPoints, correspondences);
1196 correspondences.swap(_correspondences);
1201 extraResults.sumSqrDist =
1202 (_sumSqrCount) ? _sumSqrDist / static_cast<double>(_sumSqrCount) : 0;
1203 extraResults.correspondencesRatio =
params.decimation_other_map_points *
1204 nOtherMapPointsWithCorrespondence /
1214 const TPoint2D& center,
const double radius,
const double zmin,
1218 for (
size_t k = 0; k <
m_x.size(); k++)
1220 if ((
m_z[k] <= zmax &&
m_z[k] >= zmin) &&
1232 double R,
double G,
double B)
1235 double minX, maxX, minY, maxY, minZ, maxZ;
1236 minX = min(corner1.
x, corner2.
x);
1237 maxX = max(corner1.
x, corner2.
x);
1238 minY = min(corner1.
y, corner2.
y);
1239 maxY = max(corner1.
y, corner2.
y);
1240 minZ = min(corner1.
z, corner2.
z);
1241 maxZ = max(corner1.
z, corner2.
z);
1242 for (
size_t k = 0; k <
m_x.size(); k++)
1244 if ((
m_x[k] >= minX &&
m_x[k] <= maxX) &&
1245 (
m_y[k] >= minY &&
m_y[k] <= maxY) &&
1246 (
m_z[k] >= minZ &&
m_z[k] <= maxZ))
1256 [[maybe_unused]]
const CPose3D& otherMapPose,
1258 float& correspondencesRatio)
1262 const auto* otherMap =
static_cast<const CPointsMap*
>(otherMap2);
1264 const size_t nLocalPoints = otherMap->
size();
1265 const size_t nGlobalPoints = this->
size();
1266 size_t nOtherMapPointsWithCorrespondence =
1270 correspondences.clear();
1271 correspondences.reserve(nLocalPoints);
1272 correspondencesRatio = 0;
1276 _correspondences.reserve(nLocalPoints);
1279 if (!nGlobalPoints)
return;
1282 if (!nLocalPoints)
return;
1285 float local_x_min, local_x_max, local_y_min, local_y_max, local_z_min,
1287 otherMap->boundingBox(
1288 local_x_min, local_x_max, local_y_min, local_y_max, local_z_min,
1292 float global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1295 global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1300 if (local_x_min > global_x_max || local_x_max < global_x_min ||
1301 local_y_min > global_y_max || local_y_max < global_y_min)
1305 std::vector<std::vector<size_t>> vIdx;
1309 std::vector<float> outX, outY, outZ, tentativeErrSq;
1310 std::vector<size_t> outIdx;
1311 for (
unsigned int localIdx = 0; localIdx < nLocalPoints; ++localIdx)
1314 const float x_local = otherMap->m_x[localIdx];
1315 const float y_local = otherMap->m_y[localIdx];
1316 const float z_local = otherMap->m_z[localIdx];
1324 x_local, y_local, z_local,
1332 const float mX = (outX[0] + outX[1] + outX[2]) / 3.0;
1333 const float mY = (outY[0] + outY[1] + outY[2]) / 3.0;
1334 const float mZ = (outZ[0] + outZ[1] + outZ[2]) / 3.0;
1340 if (distanceForThisPoint < maxDistForCorrespondence)
1343 _correspondences.resize(_correspondences.size() + 1);
1347 p.
this_idx = nOtherMapPointsWithCorrespondence++;
1355 p.
other_x = otherMap->m_x[localIdx];
1356 p.
other_y = otherMap->m_y[localIdx];
1357 p.
other_z = otherMap->m_z[localIdx];
1362 std::sort(outIdx.begin(), outIdx.end());
1363 vIdx.push_back(outIdx);
1372 std::map<size_t, std::map<size_t, std::map<size_t, pair<size_t, float>>>>
1374 TMatchingPairList::iterator it;
1375 for (it = _correspondences.begin(); it != _correspondences.end(); ++it)
1377 const size_t i0 = vIdx[it->this_idx][0];
1378 const size_t i1 = vIdx[it->this_idx][1];
1379 const size_t i2 = vIdx[it->this_idx][2];
1381 if (best.find(i0) != best.end() &&
1382 best[i0].find(i1) != best[i0].end() &&
1383 best[i0][i1].find(i2) !=
1387 if (best[i0][i1][i2].second > it->errorSquareAfterTransformation)
1389 best[i0][i1][i2].first = it->this_idx;
1390 best[i0][i1][i2].second = it->errorSquareAfterTransformation;
1395 best[i0][i1][i2].first = it->this_idx;
1396 best[i0][i1][i2].second = it->errorSquareAfterTransformation;
1400 for (it = _correspondences.begin(); it != _correspondences.end(); ++it)
1402 const size_t i0 = vIdx[it->this_idx][0];
1403 const size_t i1 = vIdx[it->this_idx][1];
1404 const size_t i2 = vIdx[it->this_idx][2];
1406 if (best[i0][i1][i2].first == it->this_idx)
1407 correspondences.push_back(*it);
1411 correspondencesRatio =
1412 nOtherMapPointsWithCorrespondence /
d2f(nLocalPoints);
1419 const float* zs,
const std::size_t num_pts)
1423 float closest_x, closest_y, closest_z;
1426 double sumSqrDist = 0;
1428 std::size_t nPtsForAverage = 0;
1429 for (std::size_t i = 0; i < num_pts;
1435 pc_in_map.
composePoint(xs[i], ys[i], zs[i], xg, yg, zg);
1439 closest_x, closest_y,
1447 sumSqrDist +=
static_cast<double>(closest_err);
1449 if (nPtsForAverage) sumSqrDist /= nPtsForAverage;
1472 const size_t N = scanPoints->
m_x.size();
1473 if (!N || !this->
size())
return -100;
1475 const float* xs = &scanPoints->m_x[0];
1476 const float* ys = &scanPoints->m_y[0];
1477 const float* zs = &scanPoints->m_z[0];
1481 double sumSqrDist = 0;
1482 float closest_x, closest_y;
1484 const float max_sqr_err =
1490 const double ccos = cos(takenFrom2D.
phi);
1491 const double csin = sin(takenFrom2D.
phi);
1492 int nPtsForAverage = 0;
1494 for (
size_t i = 0; i < N;
1499 const float xg = takenFrom2D.
x + ccos * xs[i] - csin * ys[i];
1500 const float yg = takenFrom2D.
y + csin * xs[i] + ccos * ys[i];
1504 closest_x, closest_y,
1511 sumSqrDist +=
static_cast<double>(closest_err);
1513 sumSqrDist /= nPtsForAverage;
1521 takenFrom, xs, ys, zs, N);
1529 if (!o.point_cloud.size())
1532 const size_t N = o.point_cloud.size();
1533 if (!N || !this->
size())
return -100;
1535 const CPose3D sensorAbsPose = takenFrom + o.sensorPose;
1537 const float* xs = &o.point_cloud.
x[0];
1538 const float* ys = &o.point_cloud.y[0];
1539 const float* zs = &o.point_cloud.z[0];
1542 sensorAbsPose, xs, ys, zs, N);
1549 if (!N || !this->
size())
return -100;
1551 const CPose3D sensorAbsPose = takenFrom + o.sensorPose;
1553 auto xs = o.pointcloud->getPointsBufferRef_x();
1554 auto ys = o.pointcloud->getPointsBufferRef_y();
1555 auto zs = o.pointcloud->getPointsBufferRef_z();
1558 sensorAbsPose, &xs[0], &ys[0], &zs[0], N);
1581 if (out_map)
return;
1583 out_map = std::make_shared<CSimplePointsMap>();
1587 *static_cast<const CPointsMap::TInsertionOptions*>(insertOps);
1589 out_map->insertObservation(obs,
nullptr);
1629 pt_has_color =
false;
1640 const size_t nThis = this->
size();
1641 const size_t nOther = anotherMap.
size();
1643 const size_t nTot = nThis + nOther;
1647 for (
size_t i = 0, j = nThis; i < nOther; i++, j++)
1649 m_x[j] = anotherMap.
m_x[i];
1650 m_y[j] = anotherMap.
m_y[i];
1651 m_z[j] = anotherMap.
m_z[i];
1667 const size_t n = mask.size();
1670 for (i = 0, j = 0; i < n; i++)
1692 const size_t N_this =
size();
1693 const size_t N_other = otherMap->
size();
1696 this->
resize(N_this + N_other);
1700 for (src = 0, dst = N_this; src < N_other; src++, dst++)
1724 if (
this == &obj)
return;
1757 robotPose2D =
CPose2D(*robotPose);
1758 robotPose3D = (*robotPose);
1774 bool reallyInsertIt;
1780 reallyInsertIt =
true;
1784 std::vector<bool> checkForDeletion;
1815 const float *xs, *ys, *zs;
1822 for (
size_t i = 0; i < n; i++)
1824 if (checkForDeletion[i])
1832 checkForDeletion[i] =
1868 bool reallyInsertIt;
1874 reallyInsertIt =
true;
1928 this->
size() + o.sensedData.size() * 30);
1930 for (
auto it = o.begin(); it != o.end(); ++it)
1932 const CPose3D sensorPose = robotPose3D +
CPose3D(it->sensorPose);
1933 const double rang = it->sensedDistance;
1935 if (rang <= 0 || rang < o.minSensorDistance ||
1936 rang > o.maxSensorDistance)
1941 const double arc_len = o.sensorConeApperture * rang;
1942 const unsigned int nSteps =
round(1 + arc_len / 0.05);
1943 const double Aa = o.sensorConeApperture / double(nSteps);
1946 for (
double a1 = -aper_2;
a1 < aper_2;
a1 += Aa)
1948 for (
double a2 = -aper_2;
a2 < aper_2;
a2 += Aa)
1950 loc.
x = cos(
a1) * cos(
a2) * rang;
1951 loc.
y = cos(
a1) * sin(
a2) * rang;
1952 loc.
z = sin(
a1) * rang;
1971 if (!o.point_cloud.size())
2031 std::vector<bool>* notFusedPoints)
2035 const CPose2D nullPose(0, 0, 0);
2040 const size_t nOther = otherMap->
size();
2047 params.maxAngularDistForCorrespondence = 0;
2048 params.maxDistForCorrespondence = minDistForFuse;
2053 correspondences,
params, extraResults);
2058 notFusedPoints->clear();
2059 notFusedPoints->reserve(
m_x.size() + nOther);
2060 notFusedPoints->resize(
m_x.size(),
true);
2069 for (
size_t i = 0; i < nOther; i++)
2075 int closestCorr = -1;
2076 float minDist = std::numeric_limits<float>::max();
2077 for (
auto corrsIt = correspondences.begin();
2078 corrsIt != correspondences.end(); ++corrsIt)
2080 if (corrsIt->other_idx == i)
2082 float dist =
square(corrsIt->other_x - corrsIt->this_x) +
2083 square(corrsIt->other_y - corrsIt->this_y) +
2084 square(corrsIt->other_z - corrsIt->this_z);
2088 closestCorr = corrsIt->this_idx;
2093 if (closestCorr != -1)
2100 const float F = 1.0f / (w_a + w_b);
2102 m_x[closestCorr] = F * (w_a * a.
x + w_b * b.
x);
2103 m_y[closestCorr] = F * (w_a * a.
y + w_b * b.
y);
2104 m_z[closestCorr] = F * (w_a * a.
z + w_b * b.
z);
2109 if (notFusedPoints) (*notFusedPoints)[closestCorr] =
false;
2114 if (notFusedPoints) (*notFusedPoints).push_back(
false);
2137 const size_t nOldPtsCount = this->
size();
2139 const size_t nNewPtsCount = nOldPtsCount + nScanPts;
2140 this->
resize(nNewPtsCount);
2142 const float K = 1.0f / 255;
2147 sensorGlobalPose = *robotPose + scan.
sensorPose;
2154 const double m00 = HM(0, 0), m01 = HM(0, 1), m02 = HM(0, 2), m03 = HM(0, 3);
2155 const double m10 = HM(1, 0), m11 = HM(1, 1), m12 = HM(1, 2), m13 = HM(1, 3);
2156 const double m20 = HM(2, 0), m21 = HM(2, 1), m22 = HM(2, 2), m23 = HM(2, 3);
2159 for (
size_t i = 0; i < nScanPts; i++)
2166 const double gx = m00 * lx + m01 * ly + m02 * lz + m03;
2167 const double gy = m10 * lx + m11 * ly + m12 * lz + m13;
2168 const double gz = m20 * lx + m21 * ly + m22 * lz + m23;
2171 nOldPtsCount + i, gx, gy, gz,
void clear()
Erase all the contents of the map.
#define IMPLEMENTS_VIRTUAL_SERIALIZABLE(class_name, base_class, NS)
This must be inserted as implementation of some required members for virtual CSerializable classes: ...
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.
float errorSquareAfterTransformation
void closestFromPointToLine(double Px, double Py, double x1, double y1, double x2, double y2, double &out_x, double &out_y)
Computes the closest point from a given point to a (infinite) line.
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream - used in derived classes' serialization.
TLikelihoodOptions()
Initilization of default parameters.
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream - for usage in derived classes' serialization.
void kdTreeNClosestPoint3DWithIdx(float x0, float y0, float z0, size_t knn, std::vector< float > &out_x, std::vector< float > &out_y, std::vector< float > &out_z, std::vector< size_t > &out_idx, std::vector< float > &out_dist_sqr) const
KD Tree-based search for the N closest points to some given 3D coordinates.
void insertAnotherMap(const CPointsMap *otherMap, const mrpt::poses::CPose3D &otherPose)
Insert the contents of another map into this one with some geometric transformation, without fusing close points.
Parameters for CMetricMap::compute3DMatchingRatio()
void keep_min(T &var, const K test_val)
If the second argument is below the first one, set the first argument to this lower value...
void getPoint(size_t index, float &x, float &y, float &z) const
Access to a given point from map, as a 2D point.
void colormap(const TColormap &color_map, const float color_index, float &r, float &g, float &b)
Transform a float number in the range [0,1] into RGB components.
A compile-time fixed-size numeric matrix container.
bool isPlanarMap
If set to true, only HORIZONTAL (in the XY plane) measurements will be inserted in the map (Default v...
mrpt::img::TColormap colormap
Colormap for points (index is "z" coordinates)
virtual void addFrom(const CPointsMap &anotherMap)
Adds all the points from anotherMap to this map, without fusing.
void getPointFast(size_t index, float &x, float &y, float &z) const
Just like getPoint() but without checking out-of-bound index and without returning the point weight...
Declares a class derived from "CObservation" that encapsules a single range measurement, and associated parameters.
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
virtual void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose=nullptr)=0
Transform the range scan into a set of cartessian coordinated points.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
static Ptr Create(Args &&... args)
#define MRPT_TRY_END
The end of a standard MRPT "try...catch()" block that allows tracing throw the call stack after an ex...
void internal_build_points_map_from_scan2D(const mrpt::obs::CObservation2DRangeScan &obs, mrpt::maps::CMetricMap::Ptr &out_map, const void *insertOps)
float sensorConeApperture
Cone aperture of each ultrasonic beam, in radians.
#define THROW_EXCEPTION(msg)
An observation from any sensor that can be summarized as a pointcloud.
bool enableSaveAs3DObject
(Default=true) If false, calling CMetricMap::getAs3DObject() will have no effects ...
size_t size(const MATRIXLIKE &m, const int dim)
int void fclose(FILE *f)
An OS-independent version of fclose.
#define ASSERT_BELOW_(__A, __B)
const POINTSMAP * buildAuxPointsMap(const void *options=nullptr) const
Returns a cached points map representing this laser scan, building it upon the first call...
bool isHorizontal(const double tolerance=0) const
Return true if the 6D pose represents a Z axis almost exactly vertical (upwards or downwards)...
mrpt::img::TColorf color
Color of points.
virtual void setPointAllFieldsFast(const size_t index, const std::vector< float > &point_data)=0
Set all the data fields for one point as a vector: depending on the implementation class this can be ...
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
void base_copyFrom(const CPointsMap &obj)
Helper method for ::copyFrom()
void setAllVertices(const std::vector< double > &x, const std::vector< double > &y)
Set all vertices at once.
A range or depth 3D scan measurement, as from a time-of-flight range camera or a structured-light dep...
void loadFromVelodyneScan(const mrpt::obs::CObservationVelodyneScan &scan, const mrpt::poses::CPose3D *robotPose=nullptr)
Like loadFromRangeScan() for Velodyne 3D scans.
mrpt::vision::TStereoCalibParams params
A wrapper of a TPolygon2D class, implementing CSerializable.
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
void internal_set_build_points_map_from_scan2D(scan2pts_functor fn)
void insertPoint(float x, float y, float z=0)
Provides a way to insert (append) individual points into the map: the missing fields of child classes...
virtual void getPointAllFieldsFast(const size_t index, std::vector< float > &point_data) const =0
Get all the data fields for one point as a vector: depending on the implementation class this can be ...
TMapGenericParams genericMapParams
Common params to all maps.
virtual void reserve(size_t newLength)=0
Reserves memory for a given number of points: the size of the map does not change, it only reserves the memory.
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
virtual void insertPointRGB(float x, float y, float z, [[maybe_unused]] float R, [[maybe_unused]] float G, [[maybe_unused]] float B)
overload (RGB data is ignored in classes without color information)
bool m_boundingBoxIsUpdated
void generatePointCloud(const TGeneratePointCloudParameters ¶ms=TGeneratePointCloudParameters())
Generates the point cloud into the point cloud data fields in CObservationVelodyneScan::point_cloud w...
void PLY_import_set_vertex(const size_t idx, const mrpt::math::TPoint3Df &pt, const mrpt::img::TColorf *pt_color=nullptr) override
In a base class, will be called after PLY_import_set_vertex_count() once for each loaded point...
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot/vehicle frame of reference.
size_t PLY_export_get_vertex_count() const override
In a base class, return the number of vertices.
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.
virtual unsigned int getPointWeight([[maybe_unused]] size_t index) const
Gets the point weight, which is ignored in all classes (defaults to 1) but in those which actually st...
mrpt::math::TPose2D asTPose() const
float maxDistForCorr
(Default: 0.10f) The minimum distance between 2 non-probabilistic map elements for counting them as a...
static Ptr Create(Args &&... args)
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
#define MRPT_TRY_START
The start of a standard MRPT "try...catch()" block that allows tracing throw the call stack after an ...
#define ASSERT_(f)
Defines an assertion mechanism.
TPointCloud point_cloud
Optionally, raw data can be converted into a 3D point cloud (local coordinates wrt the sensor...
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...
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.
double internal_computeObservationLikelihoodPointCloud3D(const mrpt::poses::CPose3D &pc_in_map, const float *xs, const float *ys, const float *zs, const std::size_t num_pts)
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
double phi() const
Get the phi angle of the 2D pose (in radians)
void ReadAsAndCastTo(CAST_TO_TYPE &read_here)
Read a value from a stream stored in a type different of the target variable, making the conversion v...
bool isPlanarScan(const double tolerance=0) const
Return true if the laser scanner is "horizontal", so it has an absolute value of "pitch" and "roll" l...
#define ASSERT_EQUAL_(__A, __B)
Assert comparing two values, reporting their actual values upon failure.
double sigma_dist
Sigma squared (variance, in meters) of the exponential used to model the likelihood (default= 0...
void getAllPoints(VECTOR &xs, VECTOR &ys, VECTOR &zs, size_t decimation=1) const
Returns a copy of the 2D/3D points as a std::vector of float coordinates.
void loadFromRangeScan(const mrpt::obs::CObservation2DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose=nullptr) override
See CPointsMap::loadFromRangeScan()
bool PointIntoPolygon(double x, double y) const
Check if a point is inside the polygon.
#define IS_DERIVED(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is an instance of the given ...
bool m_largestDistanceFromOriginIsUpdated
Auxiliary variables used in "getLargestDistanceFromOrigin".
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream - used in derived classes' serialization.
void extractCylinder(const mrpt::math::TPoint2D ¢er, const double radius, const double zmin, const double zmax, CPointsMap *outMap)
Extracts the points in the map within a cylinder in 3D defined the provided radius and zmin/zmax valu...
void fuseWith(CPointsMap *anotherMap, float minDistForFuse=0.02f, std::vector< bool > *notFusedPoints=nullptr)
Insert the contents of another map into this one, fusing the previous content with the new one...
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream - for usage in derived classes' serialization.
This namespace contains representation of robot actions and observations.
string iniFile(myDataDir+string("benchmark-options.ini"))
void extractPoints(const mrpt::math::TPoint3D &corner1, const mrpt::math::TPoint3D &corner2, CPointsMap *outMap, double R=1, double G=1, double B=1)
Extracts the points in the map within the area defined by two corners.
#define IMPLEMENTS_MEXPLUS_FROM(complete_type)
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
virtual void addFrom_classSpecific(const CPointsMap &anotherMap, const size_t nPreviousPoints)=0
Auxiliary method called from within addFrom() automatically, to finish the copying of class-specific ...
TPoint3D_< double > TPoint3D
Lightweight 3D point.
virtual void setPointWeight([[maybe_unused]] size_t index, [[maybe_unused]] unsigned long w)
Sets the point weight, which is ignored in all classes but those which actually store that field (Not...
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
double x() const
Common members of all points & poses classes.
float getLargestDistanceFromOrigin() const
This method returns the largest distance from the origin to any of the points, such as a sphere cente...
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
float m_largestDistanceFromOrigin
Auxiliary variables used in "getLargestDistanceFromOrigin".
void setPointFast(size_t index, float x, float y, float z)
Changes the coordinates of the given point (0-based index), without checking for out-of-bounds and wi...
mrpt::maps::CPointsMap::Ptr pointcloud
The pointcloud.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void compute3DDistanceToMesh(const mrpt::maps::CMetricMap *otherMap2, const mrpt::poses::CPose3D &otherMapPose, float maxDistForCorrespondence, mrpt::tfest::TMatchingPairList &correspondences, float &correspondencesRatio)
Computes the matchings between this and another 3D points map.
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
struct mxArray_tag mxArray
Forward declaration for mxArray (avoid #including as much as possible to speed up compiling) ...
Undefined colormap [New in MRPT 2.0].
void boundingBox(float &min_x, float &max_x, float &min_y, float &max_y, float &min_z, float &max_z) const
Computes the bounding box of all the points, or (0,0 ,0,0, 0,0) if there are no points.
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
int fprintf(FILE *fil, const char *format,...) noexcept MRPT_printf_format_check(2
An OS-independent version of fprintf.
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...
mrpt::aligned_std_vector< float > m_z
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.
double internal_computeObservationLikelihood(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
std::vector< uint8_t > intensity
Color [0,255].
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
constexpr std::size_t size() const
virtual void resize(size_t newLength)=0
Resizes all point buffers so they can hold the given number of points: newly created points are set t...
void mark_as_modified() const
Users normally don't need to call this.
virtual const mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override
Returns information about the class of an object in runtime.
bool addToExistingPointsMap
Applicable to "loadFromRangeScan" only! If set to false, the points from the scan are loaded...
Virtual base class for "archives": classes abstracting I/O streams.
bool fuseWithExisting
If set to true (default=false), inserted points are "fused" with previously existent ones...
mrpt::aligned_std_vector< float > m_y
TLikelihoodOptions likelihoodOptions
void filterUniqueRobustPairs(const size_t num_elements_this_map, TMatchingPairList &out_filtered_list) const
Creates a filtered list of pairings with those ones which have a single correspondence which coincide...
void getPointsBuffer(size_t &outPointsCount, const float *&xs, const float *&ys, const float *&zs) const
Provides a direct access to points buffer, or nullptr if there is no points in the map...
void setPoint(size_t index, float x, float y, float z)
Changes a given point from map, with Z defaulting to 0 if not provided.
TRenderOptions renderOptions
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
Declares a class that represents any robot's observation.
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams ¶ms) const override
Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose" In the case of a multi-metric map, this returns the average between the maps.
void kdtree_mark_as_outdated() const
To be called by child classes when KD tree data changes.
#define ASSERT_ABOVE_(__A, __B)
An RGBA color - floats in the range [0,1].
#define LOADABLEOPTS_DUMP_VAR_DEG(variableName)
Macro for dumping a variable to a stream, transforming the argument from radians to degrees...
float horizontalTolerance
The tolerance in rads in pitch & roll for a laser scan to be considered horizontal, considered only when isPlanarMap=true (default=0).
void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const override
Computes the matching between this and another 2D point map, which includes finding: ...
bool derivedFrom(const TRuntimeClassId *pBaseClass) const
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream - for usage in derived classes' serialization.
bool internal_insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose) override
This is a common version of CMetricMap::insertObservation() for point maps (actually, CMetricMap::internal_insertObservation), so derived classes don't need to worry implementing that method unless something special is really necesary.
void(*)(const mrpt::obs::CObservation2DRangeScan &obs, mrpt::maps::CMetricMap::Ptr &out_map, const void *insertOps) scan2pts_functor
TInsertionOptions insertionOptions
The options used when inserting observations in the map.
MRPT_TODO("toPointCloud / calibration")
double max_corr_distance
Maximum distance in meters to consider for the numerator divided by "sigma_dist", so that each point ...
FILE * fopen(const char *fileName, const char *mode) noexcept
An OS-independent version of fopen.
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::optional_ref< mrpt::math::CMatrixDouble33 > out_jacobian_df_dpoint=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dpose=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dse3=std::nullopt, bool use_small_rot_approx=false) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
virtual const mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() const
If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points ...
static TAuxLoadFunctor dummy_loader
#define MRPT_LOAD_CONFIG_VAR_DEGREES( variableName, configFileObject, sectionNameStr)
Loads a double variable, stored as radians but entered in the INI-file as degrees.
size_t kdTreeClosestPoint2D(float x0, float y0, float &out_x, float &out_y, float &out_dist_sqr) const
KD Tree-based search for the closest point (only ONE) to some given 2D coordinates.
virtual void insertPointFast(float x, float y, float z=0)=0
The virtual method for insertPoint() without calling mark_as_modified()
void determineMatching3D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const override
Computes the matchings between this and another 3D points map - method used in 3D-ICP.
virtual void setPointRGB(size_t index, float x, float y, float z, [[maybe_unused]] float R, [[maybe_unused]] float G, [[maybe_unused]] float B)
overload (RGB data is ignored in classes without color information)
float squareDistanceToClosestCorrespondence(float x0, float y0) const override
Returns the square distance from the 2D point (x0,y0) to the closest correspondence in the map...
uint32_t decimation
Speed up the likelihood computation by considering only one out of N rays (default=10) ...
Parameters for the determination of matchings between point clouds, etc.
mrpt::aligned_std_vector< float > m_x
The point coordinates.
size_t size() const
Save the point cloud as a PCL PCD file, in either ASCII or binary format.
bool disableDeletion
If set to false (default=true) points in the same plane as the inserted scan and inside the free spac...
Functions for estimating the optimal transformation between two frames of references given measuremen...
void clear()
Clear the contents of this container.
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
double phi
Orientation (rads)
void PLY_export_get_vertex(const size_t idx, mrpt::math::TPoint3Df &pt, bool &pt_has_color, mrpt::img::TColorf &pt_color) const override
In a base class, will be called after PLY_export_get_vertex_count() once for each exported point...
float kdTreeClosestPoint2DsqrError(float x0, float y0) const
Like kdTreeClosestPoint2D, but just return the square error from some point to its closest neighbor...
void kdTreeTwoClosestPoint2D(float x0, float y0, float &out_x1, float &out_y1, float &out_x2, float &out_y2, float &out_dist_sqr1, float &out_dist_sqr2) const
KD Tree-based search for the TWO closest point to some given 2D coordinates.
double distance(const TPoint2D &p1, const TPoint2D &p2)
Gets the distance between two points in a 2D space.
void applyDeletionMask(const std::vector< bool > &mask)
Remove from the map the points marked in a bool's array as "true".
size_t kdTreeClosestPoint3D(float x0, float y0, float z0, float &out_x, float &out_y, float &out_z, float &out_dist_sqr) const
KD Tree-based search for the closest point (only ONE) to some given 3D coordinates.
float minDistBetweenLaserPoints
The minimum distance between points (in 3D): If two points are too close, one of them is not inserted...
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream - for usage in derived classes' serialization.
int round(const T value)
Returns the closer integer (int) to x.