31 #include <pcl/io/pcd_io.h> 32 #include <pcl/point_types.h> 74 CPointsMap::CPointsMap()
80 m_largestDistanceFromOrigin(0),
81 m_heightfilter_z_min(-10),
82 m_heightfilter_z_max(10),
83 m_heightfilter_enabled(false)
100 if (!f)
return false;
102 for (
unsigned int i = 0; i <
x.size(); i++)
117 if (!f)
return false;
119 for (
unsigned int i = 0; i <
x.size(); i++)
139 if (!f)
return false;
142 char *ptr, *ptr1, *ptr2, *ptr3;
151 if (!fgets(str,
sizeof(str), f))
break;
155 while (ptr[0] && (ptr[0] ==
' ' || ptr[0] ==
'\t' || ptr[0] ==
'\r' ||
160 float xx = strtod(ptr, &ptr1);
163 float yy = strtod(ptr1, &ptr2);
172 float zz = strtod(ptr2, &ptr3);
197 MRPT_TODO(
"Create 3xN array xyz of points coordinates")
198 const
char* fields[] = {
"x",
"y",
"z"};
199 mexplus::MxArray map_struct(
200 mexplus::MxArray::Struct(
sizeof(fields) /
sizeof(fields[0]), fields));
202 map_struct.set(
"x", this->
x);
203 map_struct.set(
"y", this->
y);
204 map_struct.set(
"z", this->
z);
205 return map_struct.release();
223 size_t index,
float&
x,
float&
y,
float&
z)
const 244 size_t index,
double&
x,
double&
y,
double&
z)
const 260 size_t& outPointsCount,
const float*& xs,
const float*& ys,
261 const float*& zs)
const 263 outPointsCount =
size();
265 if (outPointsCount > 0)
273 xs = ys = zs =
nullptr;
282 const size_t n =
size();
283 vector<bool> deletionMask(
n);
286 for (
size_t i = 0; i <
n; i++)
287 deletionMask[i] = (
z[i] < zMin ||
z[i] > zMax);
300 size_t i,
n =
size();
301 vector<bool> deletionMask;
304 deletionMask.resize(
n);
307 for (i = 0; i <
n; i++)
328 params.offset_other_map_points,
params.decimation_other_map_points)
333 otherMapPose_.
x(), otherMapPose_.
y(), otherMapPose_.
phi());
335 const size_t nLocalPoints = otherMap->
size();
336 const size_t nGlobalPoints = this->
size();
337 float _sumSqrDist = 0;
338 size_t _sumSqrCount = 0;
339 size_t nOtherMapPointsWithCorrespondence =
342 float local_x_min = std::numeric_limits<float>::max(),
343 local_x_max = -std::numeric_limits<float>::max();
344 float global_x_min = std::numeric_limits<float>::max(),
345 global_x_max = -std::numeric_limits<float>::max();
346 float local_y_min = std::numeric_limits<float>::max(),
347 local_y_max = -std::numeric_limits<float>::max();
348 float global_y_min = std::numeric_limits<float>::max(),
349 global_y_max = -std::numeric_limits<float>::max();
351 double maxDistForCorrespondenceSquared;
352 float x_local, y_local;
353 unsigned int localIdx;
355 const float *x_other_it, *y_other_it,
359 correspondences.clear();
360 correspondences.reserve(nLocalPoints);
361 extraResults.correspondencesRatio = 0;
364 _correspondences.reserve(nLocalPoints);
367 if (!nGlobalPoints)
return;
370 if (!nLocalPoints)
return;
372 const double sin_phi = sin(otherMapPose.phi);
373 const double cos_phi = cos(otherMapPose.phi);
382 size_t nPackets = nLocalPoints / 4;
383 if ((nLocalPoints & 0x03) != 0) nPackets++;
386 size_t nLocalPoints_4align = nLocalPoints;
387 size_t nExtraPad = 0;
388 if (0 != (nLocalPoints & 0x03))
390 nExtraPad = 4 - (nLocalPoints & 0x03);
391 nLocalPoints_4align += nExtraPad;
394 Eigen::Array<float, Eigen::Dynamic, 1> x_locals(nLocalPoints_4align),
395 y_locals(nLocalPoints_4align);
404 if (otherMap->x.capacity() < nLocalPoints_4align ||
405 otherMap->y.capacity() < nLocalPoints_4align)
408 const_cast<vector<float>*
>(&otherMap->x)
409 ->
reserve(nLocalPoints_4align + 16);
410 const_cast<vector<float>*
>(&otherMap->y)
411 ->
reserve(nLocalPoints_4align + 16);
416 float* ptr_in_x =
const_cast<float*
>(&otherMap->x[0]);
417 float* ptr_in_y =
const_cast<float*
>(&otherMap->y[0]);
418 for (
size_t k = nExtraPad; k; k--)
420 ptr_in_x[nLocalPoints + k] = 0;
421 ptr_in_y[nLocalPoints + k] = 0;
425 const __m128 cos_4val =
426 _mm_set1_ps(cos_phi);
427 const __m128 sin_4val = _mm_set1_ps(sin_phi);
428 const __m128 x0_4val = _mm_set1_ps(otherMapPose.x);
429 const __m128 y0_4val = _mm_set1_ps(otherMapPose.y);
432 __m128 x_mins = _mm_set1_ps(std::numeric_limits<float>::max());
434 __m128 y_mins = x_mins;
435 __m128 y_maxs = x_maxs;
437 const float* ptr_in_x = &otherMap->x[0];
438 const float* ptr_in_y = &otherMap->y[0];
439 float* ptr_out_x = &x_locals[0];
440 float* ptr_out_y = &y_locals[0];
442 for (; nPackets; nPackets--, ptr_in_x += 4, ptr_in_y += 4, ptr_out_x += 4,
445 const __m128 xs = _mm_loadu_ps(ptr_in_x);
446 const __m128 ys = _mm_loadu_ps(ptr_in_y);
448 const __m128 lxs = _mm_add_ps(
450 _mm_sub_ps(_mm_mul_ps(xs, cos_4val), _mm_mul_ps(ys, sin_4val)));
451 const __m128 lys = _mm_add_ps(
453 _mm_add_ps(_mm_mul_ps(xs, sin_4val), _mm_mul_ps(ys, cos_4val)));
454 _mm_store_ps(ptr_out_x, lxs);
455 _mm_store_ps(ptr_out_y, lys);
457 x_mins = _mm_min_ps(x_mins, lxs);
458 x_maxs = _mm_max_ps(x_maxs, lxs);
459 y_mins = _mm_min_ps(y_mins, lys);
460 y_maxs = _mm_max_ps(y_maxs, lys);
464 alignas(16)
float temp_nums[4];
466 _mm_store_ps(temp_nums, x_mins);
468 min(
min(temp_nums[0], temp_nums[1]),
min(temp_nums[2], temp_nums[3]));
469 _mm_store_ps(temp_nums, y_mins);
471 min(
min(temp_nums[0], temp_nums[1]),
min(temp_nums[2], temp_nums[3]));
472 _mm_store_ps(temp_nums, x_maxs);
474 max(max(temp_nums[0], temp_nums[1]), max(temp_nums[2], temp_nums[3]));
475 _mm_store_ps(temp_nums, y_maxs);
477 max(max(temp_nums[0], temp_nums[1]), max(temp_nums[2], temp_nums[3]));
481 const Eigen::Map<Eigen::Matrix<float, Eigen::Dynamic, 1>> x_org(
482 const_cast<float*>(&otherMap->x[0]), otherMap->x.size(), 1);
483 const Eigen::Map<Eigen::Matrix<float, Eigen::Dynamic, 1>> y_org(
484 const_cast<float*>(&otherMap->y[0]), otherMap->y.size(), 1);
486 Eigen::Array<float, Eigen::Dynamic, 1> x_locals =
487 otherMapPose.x + cos_phi * x_org.array() - sin_phi * y_org.array();
488 Eigen::Array<float, Eigen::Dynamic, 1> y_locals =
489 otherMapPose.y + sin_phi * x_org.array() + cos_phi * y_org.array();
491 local_x_min = x_locals.minCoeff();
492 local_y_min = y_locals.minCoeff();
493 local_x_max = x_locals.maxCoeff();
494 local_y_max = y_locals.maxCoeff();
498 float global_z_min, global_z_max;
500 global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
505 if (local_x_min > global_x_max || local_x_max < global_x_min ||
506 local_y_min > global_y_max || local_y_max < global_y_min)
511 for (localIdx =
params.offset_other_map_points,
512 x_other_it = &otherMap->x[
params.offset_other_map_points],
513 y_other_it = &otherMap->y[
params.offset_other_map_points],
514 z_other_it = &otherMap->z[
params.offset_other_map_points];
515 localIdx < nLocalPoints;
516 x_other_it +=
params.decimation_other_map_points,
517 y_other_it +=
params.decimation_other_map_points,
518 z_other_it +=
params.decimation_other_map_points,
519 localIdx +=
params.decimation_other_map_points)
522 x_local = x_locals[localIdx];
523 y_local = y_locals[localIdx];
532 float tentativ_err_sq;
539 maxDistForCorrespondenceSquared =
square(
540 params.maxAngularDistForCorrespondence *
544 params.maxDistForCorrespondence);
547 if (tentativ_err_sq < maxDistForCorrespondenceSquared)
550 _correspondences.resize(_correspondences.size() + 1);
554 p.this_idx = tentativ_this_idx;
555 p.this_x =
x[tentativ_this_idx];
556 p.this_y =
y[tentativ_this_idx];
557 p.this_z =
z[tentativ_this_idx];
559 p.other_idx = localIdx;
560 p.other_x = *x_other_it;
561 p.other_y = *y_other_it;
562 p.other_z = *z_other_it;
564 p.errorSquareAfterTransformation = tentativ_err_sq;
567 nOtherMapPointsWithCorrespondence++;
570 _sumSqrDist +=
p.errorSquareAfterTransformation;
580 if (
params.onlyUniqueRobust)
583 params.onlyKeepTheClosest,
584 "ERROR: onlyKeepTheClosest must be also set to true when " 585 "onlyUniqueRobust=true.");
587 nGlobalPoints, correspondences);
591 correspondences.swap(_correspondences);
597 extraResults.sumSqrDist =
598 _sumSqrDist /
static_cast<double>(_sumSqrCount);
600 extraResults.sumSqrDist = 0;
603 extraResults.correspondencesRatio =
params.decimation_other_map_points *
604 nOtherMapPointsWithCorrespondence /
605 static_cast<float>(nLocalPoints);
615 const size_t N =
x.size();
617 const CPose3D newBase3D(newBase);
619 for (
size_t i = 0; i < N; i++)
633 const size_t N =
x.size();
635 for (
size_t i = 0; i < N; i++)
662 : minDistBetweenLaserPoints(0.02f),
663 addToExistingPointsMap(true),
664 also_interpolate(false),
665 disableDeletion(true),
666 fuseWithExisting(false),
668 horizontalTolerance(
DEG2RAD(0.05)),
669 maxDistForInterpolatePoints(2.0f),
670 insertInvalidPoints(false)
681 out << minDistBetweenLaserPoints << addToExistingPointsMap
682 << also_interpolate << disableDeletion << fuseWithExisting
683 << isPlanarMap << horizontalTolerance << maxDistForInterpolatePoints
684 << insertInvalidPoints;
695 in >> minDistBetweenLaserPoints >> addToExistingPointsMap >>
696 also_interpolate >> disableDeletion >> fuseWithExisting >>
697 isPlanarMap >> horizontalTolerance >>
698 maxDistForInterpolatePoints >> insertInvalidPoints;
707 : sigma_dist(0.0025), max_corr_distance(1.0), decimation(10)
716 out << sigma_dist << max_corr_distance << decimation;
727 in >> sigma_dist >> max_corr_distance >> decimation;
742 "\n----------- [CPointsMap::TInsertionOptions] ------------ \n\n");
763 "\n----------- [CPointsMap::TLikelihoodOptions] ------------ \n\n");
806 mrpt::make_aligned_shared<opengl::CPointCloud>();
808 obj->loadFromPointsMap(
this);
811 obj->enableColorFromZ(
true);
846 float maxDistSq = 0, d;
847 for (X =
x.begin(), Y =
y.begin(), Z =
z.begin(); X !=
x.end();
851 maxDistSq = max(d, maxDistSq);
864 vector<float>& xs, vector<float>& ys,
size_t decimation)
const 876 size_t N =
x.size() / decimation;
883 for (X =
x.begin(), Y =
y.begin(), oX = xs.begin(), oY = ys.begin();
884 oX != xs.end(); X += decimation, Y += decimation, ++oX, ++oY)
897 float x0,
float y0)
const 905 float x1, y1, x2, y2, d1, d2;
916 if (d12 > 0.20f * 0.20f || d12 < 0.03f * 0.03f)
922 double interp_x, interp_y;
940 float& min_x,
float& max_x,
float& min_y,
float& max_y,
float& min_z,
943 const size_t nPoints =
x.size();
958 size_t nPackets = nPoints / 4;
959 if ((nPoints & 0x03) != 0) nPackets++;
963 size_t nPoints_4align = nPoints;
964 size_t nExtraPad = 0;
965 if (0 != (nPoints & 0x03))
967 nExtraPad = 4 - (nPoints & 0x03);
968 nPoints_4align += nExtraPad;
978 if (
x.capacity() < nPoints_4align ||
979 y.capacity() < nPoints_4align ||
z.capacity() < nPoints_4align)
982 const_cast<vector<float>*
>(&
x)->
reserve(nPoints_4align + 16);
983 const_cast<vector<float>*
>(&
y)->
reserve(nPoints_4align + 16);
984 const_cast<vector<float>*
>(&
z)->
reserve(nPoints_4align + 16);
989 float* ptr_in_x =
const_cast<float*
>(&
x[0]);
990 float* ptr_in_y =
const_cast<float*
>(&
y[0]);
991 float* ptr_in_z =
const_cast<float*
>(&
z[0]);
992 for (
size_t k = nExtraPad; k; k--)
994 ptr_in_x[nPoints + k - 1] = 0;
995 ptr_in_y[nPoints + k - 1] = 0;
996 ptr_in_z[nPoints + k - 1] = 0;
1001 __m128 x_mins = _mm_set1_ps(std::numeric_limits<float>::max());
1003 __m128 y_mins = x_mins, y_maxs = x_maxs;
1004 __m128 z_mins = x_mins, z_maxs = x_maxs;
1006 const float* ptr_in_x = &this->
x[0];
1007 const float* ptr_in_y = &this->
y[0];
1008 const float* ptr_in_z = &this->
z[0];
1011 nPackets--, ptr_in_x += 4, ptr_in_y += 4, ptr_in_z += 4)
1013 const __m128 xs = _mm_loadu_ps(ptr_in_x);
1014 x_mins = _mm_min_ps(x_mins, xs);
1015 x_maxs = _mm_max_ps(x_maxs, xs);
1017 const __m128 ys = _mm_loadu_ps(ptr_in_y);
1018 y_mins = _mm_min_ps(y_mins, ys);
1019 y_maxs = _mm_max_ps(y_maxs, ys);
1021 const __m128 zs = _mm_loadu_ps(ptr_in_z);
1022 z_mins = _mm_min_ps(z_mins, zs);
1023 z_maxs = _mm_max_ps(z_maxs, zs);
1027 alignas(16)
float temp_nums[4];
1029 _mm_store_ps(temp_nums, x_mins);
1031 min(
min(temp_nums[0], temp_nums[1]),
1032 min(temp_nums[2], temp_nums[3]));
1033 _mm_store_ps(temp_nums, y_mins);
1035 min(
min(temp_nums[0], temp_nums[1]),
1036 min(temp_nums[2], temp_nums[3]));
1037 _mm_store_ps(temp_nums, z_mins);
1039 min(
min(temp_nums[0], temp_nums[1]),
1040 min(temp_nums[2], temp_nums[3]));
1041 _mm_store_ps(temp_nums, x_maxs);
1043 max(max(temp_nums[0], temp_nums[1]),
1044 max(temp_nums[2], temp_nums[3]));
1045 _mm_store_ps(temp_nums, y_maxs);
1047 max(max(temp_nums[0], temp_nums[1]),
1048 max(temp_nums[2], temp_nums[3]));
1049 _mm_store_ps(temp_nums, z_maxs);
1051 max(max(temp_nums[0], temp_nums[1]),
1052 max(temp_nums[2], temp_nums[3]));
1057 (std::numeric_limits<float>::max)();
1060 -(std::numeric_limits<float>::max)();
1064 xi !=
x.end(); xi++, yi++, zi++)
1100 params.offset_other_map_points,
params.decimation_other_map_points)
1105 const size_t nLocalPoints = otherMap->
size();
1106 const size_t nGlobalPoints = this->
size();
1107 float _sumSqrDist = 0;
1108 size_t _sumSqrCount = 0;
1109 size_t nOtherMapPointsWithCorrespondence =
1112 float local_x_min = std::numeric_limits<float>::max(),
1113 local_x_max = -std::numeric_limits<float>::max();
1114 float local_y_min = std::numeric_limits<float>::max(),
1115 local_y_max = -std::numeric_limits<float>::max();
1116 float local_z_min = std::numeric_limits<float>::max(),
1117 local_z_max = -std::numeric_limits<float>::max();
1119 double maxDistForCorrespondenceSquared;
1122 correspondences.clear();
1123 correspondences.reserve(nLocalPoints);
1126 _correspondences.reserve(nLocalPoints);
1129 if (!nGlobalPoints || !nLocalPoints)
return;
1133 vector<float> x_locals(nLocalPoints), y_locals(nLocalPoints),
1134 z_locals(nLocalPoints);
1136 for (
unsigned int localIdx =
params.offset_other_map_points;
1137 localIdx < nLocalPoints;
1138 localIdx +=
params.decimation_other_map_points)
1140 float x_local, y_local, z_local;
1142 otherMap->x[localIdx], otherMap->y[localIdx], otherMap->z[localIdx],
1143 x_local, y_local, z_local);
1145 x_locals[localIdx] = x_local;
1146 y_locals[localIdx] = y_local;
1147 z_locals[localIdx] = z_local;
1150 local_x_min =
min(local_x_min, x_local);
1151 local_x_max = max(local_x_max, x_local);
1152 local_y_min =
min(local_y_min, y_local);
1153 local_y_max = max(local_y_max, y_local);
1154 local_z_min =
min(local_z_min, z_local);
1155 local_z_max = max(local_z_max, z_local);
1159 float global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1162 global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1167 if (local_x_min > global_x_max || local_x_max < global_x_min ||
1168 local_y_min > global_y_max || local_y_max < global_y_min)
1173 for (
unsigned int localIdx =
params.offset_other_map_points;
1174 localIdx < nLocalPoints;
1175 localIdx +=
params.decimation_other_map_points)
1178 const float x_local = x_locals[localIdx];
1179 const float y_local = y_locals[localIdx];
1180 const float z_local = z_locals[localIdx];
1188 float tentativ_err_sq;
1190 x_local, y_local, z_local,
1195 maxDistForCorrespondenceSquared =
square(
1196 params.maxAngularDistForCorrespondence *
1197 params.angularDistPivotPoint.distanceTo(
1198 TPoint3D(x_local, y_local, z_local)) +
1199 params.maxDistForCorrespondence);
1202 if (tentativ_err_sq < maxDistForCorrespondenceSquared)
1205 _correspondences.resize(_correspondences.size() + 1);
1209 p.this_idx = tentativ_this_idx;
1210 p.this_x =
x[tentativ_this_idx];
1211 p.this_y =
y[tentativ_this_idx];
1212 p.this_z =
z[tentativ_this_idx];
1214 p.other_idx = localIdx;
1215 p.other_x = otherMap->x[localIdx];
1216 p.other_y = otherMap->y[localIdx];
1217 p.other_z = otherMap->z[localIdx];
1219 p.errorSquareAfterTransformation = tentativ_err_sq;
1222 nOtherMapPointsWithCorrespondence++;
1225 _sumSqrDist +=
p.errorSquareAfterTransformation;
1236 if (
params.onlyUniqueRobust)
1239 params.onlyKeepTheClosest,
1240 "ERROR: onlyKeepTheClosest must be also set to true when " 1241 "onlyUniqueRobust=true.");
1243 nGlobalPoints, correspondences);
1247 correspondences.swap(_correspondences);
1252 extraResults.sumSqrDist =
1253 (_sumSqrCount) ? _sumSqrDist / static_cast<double>(_sumSqrCount) : 0;
1254 extraResults.correspondencesRatio =
params.decimation_other_map_points *
1255 nOtherMapPointsWithCorrespondence /
1256 static_cast<float>(nLocalPoints);
1265 const TPoint2D& center,
const double radius,
const double zmin,
1269 for (
size_t k = 0; k <
x.size(); k++)
1271 if ((
z[k] <=
zmax &&
z[k] >= zmin) &&
1282 const double&
R,
const double& G,
const double& B)
1285 double minX, maxX, minY, maxY, minZ, maxZ;
1286 minX =
min(corner1.
x, corner2.
x);
1287 maxX = max(corner1.
x, corner2.
x);
1288 minY =
min(corner1.
y, corner2.
y);
1289 maxY = max(corner1.
y, corner2.
y);
1290 minZ =
min(corner1.
z, corner2.
z);
1291 maxZ = max(corner1.
z, corner2.
z);
1292 for (
size_t k = 0; k <
x.size(); k++)
1294 if ((
x[k] >= minX &&
x[k] <= maxX) && (
y[k] >= minY &&
y[k] <= maxY) &&
1295 (
z[k] >= minZ &&
z[k] <= maxZ))
1306 float& correspondencesRatio)
1313 const size_t nLocalPoints = otherMap->
size();
1314 const size_t nGlobalPoints = this->
size();
1315 size_t nOtherMapPointsWithCorrespondence =
1319 correspondences.clear();
1320 correspondences.reserve(nLocalPoints);
1321 correspondencesRatio = 0;
1325 _correspondences.reserve(nLocalPoints);
1328 if (!nGlobalPoints)
return;
1331 if (!nLocalPoints)
return;
1334 float local_x_min, local_x_max, local_y_min, local_y_max, local_z_min,
1337 local_x_min, local_x_max, local_y_min, local_y_max, local_z_min,
1341 float global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1344 global_x_min, global_x_max, global_y_min, global_y_max, global_z_min,
1349 if (local_x_min > global_x_max || local_x_max < global_x_min ||
1350 local_y_min > global_y_max || local_y_max < global_y_min)
1354 std::vector<std::vector<size_t>> vIdx;
1359 std::vector<size_t> outIdx;
1360 for (
unsigned int localIdx = 0; localIdx < nLocalPoints; ++localIdx)
1363 const float x_local = otherMap->
x[localIdx];
1364 const float y_local = otherMap->
y[localIdx];
1365 const float z_local = otherMap->
z[localIdx];
1373 x_local, y_local, z_local,
1385 const float distanceForThisPoint = fabs(
1390 if (distanceForThisPoint < maxDistForCorrespondence)
1393 _correspondences.resize(_correspondences.size() + 1);
1397 p.this_idx = nOtherMapPointsWithCorrespondence++;
1404 p.other_idx = localIdx;
1405 p.other_x = otherMap->
x[localIdx];
1406 p.other_y = otherMap->
y[localIdx];
1407 p.other_z = otherMap->
z[localIdx];
1409 p.errorSquareAfterTransformation = distanceForThisPoint;
1412 std::sort(outIdx.begin(), outIdx.end());
1413 vIdx.push_back(outIdx);
1422 std::map<size_t, std::map<size_t, std::map<size_t, pair<size_t, float>>>>
1425 for (it = _correspondences.begin(); it != _correspondences.end(); ++it)
1427 const size_t i0 = vIdx[it->this_idx][0];
1428 const size_t i1 = vIdx[it->this_idx][1];
1429 const size_t i2 = vIdx[it->this_idx][2];
1431 if (best.find(i0) != best.end() &&
1432 best[i0].find(i1) != best[i0].end() &&
1433 best[i0][i1].find(i2) !=
1437 if (best[i0][i1][i2].second > it->errorSquareAfterTransformation)
1439 best[i0][i1][i2].first = it->this_idx;
1440 best[i0][i1][i2].second = it->errorSquareAfterTransformation;
1445 best[i0][i1][i2].first = it->this_idx;
1446 best[i0][i1][i2].second = it->errorSquareAfterTransformation;
1450 for (it = _correspondences.begin(); it != _correspondences.end(); ++it)
1452 const size_t i0 = vIdx[it->this_idx][0];
1453 const size_t i1 = vIdx[it->this_idx][1];
1454 const size_t i2 = vIdx[it->this_idx][2];
1456 if (best[i0][i1][i2].
first == it->this_idx)
1457 correspondences.push_back(*it);
1461 correspondencesRatio =
1462 nOtherMapPointsWithCorrespondence /
static_cast<float>(nLocalPoints);
1493 float sumSqrDist = 0;
1495 const size_t N = scanPoints->
x.size();
1496 if (!N || !this->
size())
return -100;
1498 const float* xs = &scanPoints->
x[0];
1499 const float* ys = &scanPoints->
y[0];
1500 const float* zs = &scanPoints->
z[0];
1502 float closest_x, closest_y, closest_z;
1505 int nPtsForAverage = 0;
1512 const float ccos = cos(takenFrom2D.
phi);
1513 const float csin = sin(takenFrom2D.
phi);
1515 for (
size_t i = 0; i < N;
1520 const float xg = takenFrom2D.
x + ccos * xs[i] - csin * ys[i];
1521 const float yg = takenFrom2D.
y + csin * xs[i] + ccos * ys[i];
1525 closest_x, closest_y,
1532 sumSqrDist += closest_err;
1539 for (
size_t i = 0; i < N;
1545 takenFrom.
composePoint(xs[i], ys[i], zs[i], xg, yg, zg);
1549 closest_x, closest_y,
1557 sumSqrDist += closest_err;
1561 sumSqrDist /= nPtsForAverage;
1591 if (out_map)
return;
1593 out_map = mrpt::make_aligned_shared<CSimplePointsMap>();
1597 *static_cast<const CPointsMap::TInsertionOptions*>(insertOps);
1599 out_map->insertObservation(&obs,
nullptr);
1642 pt_has_color =
false;
1653 const size_t nThis = this->
size();
1654 const size_t nOther = anotherMap.
size();
1656 const size_t nTot = nThis + nOther;
1660 for (
size_t i = 0, j = nThis; i < nOther; i++, j++)
1662 this->
x[j] = anotherMap.
x[i];
1663 this->
y[j] = anotherMap.
y[i];
1664 this->
z[j] = anotherMap.
z[i];
1676 const std::string& filename,
bool save_as_binary)
const 1679 pcl::PointCloud<pcl::PointXYZ> cloud;
1682 return 0 == pcl::io::savePCDFile(filename, cloud, save_as_binary);
1687 THROW_EXCEPTION(
"Operation not available: MRPT was built without PCL")
1696 pcl::PointCloud<pcl::PointXYZ> cloud;
1697 if (0 != pcl::io::loadPCDFile(filename, cloud))
return false;
1704 THROW_EXCEPTION(
"Operation not available: MRPT was built without PCL")
1716 const size_t n =
mask.size();
1719 for (i = 0, j = 0; i <
n; i++)
1741 const size_t N_this =
size();
1742 const size_t N_other = otherMap->
size();
1745 this->
resize(N_this + N_other);
1773 if (
this == &
obj)
return;
1780 obj.m_largestDistanceFromOriginIsUpdated;
1806 robotPose2D =
CPose2D(*robotPose);
1807 robotPose3D = (*robotPose);
1824 bool reallyInsertIt;
1830 reallyInsertIt =
true;
1834 std::vector<bool> checkForDeletion;
1864 const float *xs, *ys, *zs;
1871 for (
size_t i = 0; i <
n; i++)
1873 if (checkForDeletion[i])
1880 checkForDeletion[i] =
1916 bool reallyInsertIt;
1922 reallyInsertIt =
true;
1989 const CPose3D sensorPose = robotPose3D +
CPose3D(it->sensorPose);
1990 const double rang = it->sensedDistance;
1992 if (rang <= 0 || rang < o->minSensorDistance ||
1998 const unsigned int nSteps =
round(1 + arc_len / 0.05);
2002 for (
double a1 = -aper_2;
a1 < aper_2;
a1 += Aa)
2004 for (
double a2 = -aper_2;
a2 < aper_2;
a2 += Aa)
2006 loc.
x = cos(
a1) * cos(
a2) * rang;
2007 loc.
y = cos(
a1) * sin(
a2) * rang;
2008 loc.
z = sin(
a1) * rang;
2066 std::vector<bool>* notFusedPoints)
2070 const CPose2D nullPose(0, 0, 0);
2075 const size_t nOther = otherMap->
size();
2082 params.maxAngularDistForCorrespondence = 0;
2083 params.maxDistForCorrespondence = minDistForFuse;
2088 correspondences,
params, extraResults);
2093 notFusedPoints->clear();
2094 notFusedPoints->reserve(
x.size() + nOther);
2095 notFusedPoints->resize(
x.size(),
true);
2104 for (
size_t i = 0; i < nOther; i++)
2106 const unsigned long w_a =
2110 int closestCorr = -1;
2111 float minDist = std::numeric_limits<float>::max();
2113 correspondences.begin();
2114 corrsIt != correspondences.end(); ++corrsIt)
2116 if (corrsIt->other_idx == i)
2118 float dist =
square(corrsIt->other_x - corrsIt->this_x) +
2119 square(corrsIt->other_y - corrsIt->this_y) +
2120 square(corrsIt->other_z - corrsIt->this_z);
2124 closestCorr = corrsIt->this_idx;
2129 if (closestCorr != -1)
2131 unsigned long w_b =
getPoint(closestCorr,
b);
2135 const float F = 1.0f / (w_a + w_b);
2137 x[closestCorr] = F * (w_a *
a.x + w_b *
b.x);
2138 y[closestCorr] = F * (w_a *
a.y + w_b *
b.y);
2139 z[closestCorr] = F * (w_a *
a.z + w_b *
b.z);
2144 if (notFusedPoints) (*notFusedPoints)[closestCorr] =
false;
2149 if (notFusedPoints) (*notFusedPoints).push_back(
false);
2172 const size_t nOldPtsCount = this->
size();
2174 const size_t nNewPtsCount = nOldPtsCount + nScanPts;
2175 this->
resize(nNewPtsCount);
2177 const float K = 1.0f / 255;
2182 sensorGlobalPose = *robotPose + scan.
sensorPose;
2189 const double m00 = HM.get_unsafe(0, 0), m01 = HM.get_unsafe(0, 1),
2190 m02 = HM.get_unsafe(0, 2), m03 = HM.get_unsafe(0, 3);
2191 const double m10 = HM.get_unsafe(1, 0), m11 = HM.get_unsafe(1, 1),
2192 m12 = HM.get_unsafe(1, 2), m13 = HM.get_unsafe(1, 3);
2193 const double m20 = HM.get_unsafe(2, 0), m21 = HM.get_unsafe(2, 1),
2194 m22 = HM.get_unsafe(2, 2), m23 = HM.get_unsafe(2, 3);
2197 for (
size_t i = 0; i < nScanPts; i++)
2204 const double gx = m00 * lx + m01 * ly + m02 * lz + m03;
2205 const double gy = m10 * lx + m11 * ly + m12 * lz + m13;
2206 const double gz = m20 * lx + m21 * ly + m22 * lz + m23;
2209 nOldPtsCount + i, gx, gy, gz,
#define ASSERT_EQUAL_(__A, __B)
void clear()
Erase all the contents of the map.
virtual void copyFrom(const CPointsMap &obj)=0
Virtual assignment operator, copies as much common data (XYZ, color,...) as possible from the source ...
virtual void PLY_export_get_vertex(const size_t idx, mrpt::math::TPoint3Df &pt, bool &pt_has_color, mrpt::utils::TColorf &pt_color) const override
In a base class, will be called after PLY_export_get_vertex_count() once for each exported point...
double x() const
Common members of all points & poses classes.
TLikelihoodOptions()
Initilization of default parameters.
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()
bool save2D_to_text_file(const std::string &file) const
Save to a text file.
bool isPlanarMap
If set to true, only HORIZONTAL (in the XY plane) measurements will be inserted in the map (Default v...
virtual void addFrom(const CPointsMap &anotherMap)
Adds all the points from anotherMap to this map, without fusing.
void readFromStream(mrpt::utils::CStream &in)
Binary dump to stream - for usage in derived classes' serialization.
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.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
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.
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.
virtual void PLY_import_set_vertex(const size_t idx, const mrpt::math::TPoint3Df &pt, const mrpt::utils::TColorf *pt_color=nullptr) override
In a base class, will be called after PLY_import_set_vertex_count() once for each loaded point...
void changeCoordinatesReference(const mrpt::poses::CPose2D &b)
Replace each point by (pose compounding operator).
void internal_build_points_map_from_scan2D(const mrpt::obs::CObservation2DRangeScan &obs, mrpt::maps::CMetricMap::Ptr &out_map, const void *insertOps)
virtual void determineMatching3D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, mrpt::utils::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const override
Computes the matchings between this and another 3D points map - method used in 3D-ICP.
#define LOADABLEOPTS_DUMP_VAR_DEG(variableName)
Macro for dumping a variable to a stream, transforming the argument from radians to degrees...
#define ASSERT_ABOVE_(__A, __B)
float sensorConeApperture
Cone aperture of each ultrasonic beam, in radians.
This namespace provides a OS-independent interface to many useful functions: filenames manipulation...
void closestFromPointToLine(const double &Px, const double &Py, const double &x1, const double &y1, const double &x2, const double &y2, double &out_x, double &out_y)
Computes the closest point from a given point to a (infinite) line.
bool enableSaveAs3DObject
(Default=true) If false, calling CMetricMap::getAs3DObject() will have no effects ...
int void fclose(FILE *f)
An OS-independent version of fclose.
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)...
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 ...
virtual double internal_computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
virtual void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
#define THROW_EXCEPTION(msg)
void base_copyFrom(const CPointsMap &obj)
Helper method for ::copyFrom()
#define ASSERT_BELOW_(__A, __B)
virtual void setPointFast(size_t index, float x, float y, float z)=0
Changes the coordinates of the given point (0-based index), without checking for out-of-bounds and wi...
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...
virtual const mrpt::utils::TRuntimeClassId * GetRuntimeClass() const override
Returns information about the class of an object in runtime.
void setAllVertices(const std::vector< double > &x, const std::vector< double > &y)
Set all vertices at once.
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
void loadFromVelodyneScan(const mrpt::obs::CObservationVelodyneScan &scan, const mrpt::poses::CPose3D *robotPose=nullptr)
Like loadFromRangeScan() for Velodyne 3D scans.
virtual const mrpt::utils::TRuntimeClassId * GetRuntimeClass() const override
Returns information about the class of an object in runtime.
A wrapper of a TPolygon2D class, implementing CSerializable.
GLuint GLenum GLenum outY
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 unsigned int getPointWeight(size_t index) const
Gets the point weight, which is ignored in all classes (defaults to 1) but in those which actually st...
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.
TInsertionOptions()
Initilization of default parameters.
const Scalar * const_iterator
bool m_boundingBoxIsUpdated
void compute3DDistanceToMesh(const mrpt::maps::CMetricMap *otherMap2, const mrpt::poses::CPose3D &otherMapPose, float maxDistForCorrespondence, mrpt::utils::TMatchingPairList &correspondences, float &correspondencesRatio)
Computes the matchings between this and another 3D points map.
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
GLsizei GLsizei GLuint * obj
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 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...
bool save3D_to_text_file(const std::string &file) const
Save to a text file.
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
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.
float maxDistForCorr
(Default: 0.10f) The minimum distance between 2 non-probabilistic map elements for counting them as a...
std::deque< TMeasurement >::const_iterator const_iterator
GLuint GLenum GLenum GLenum outZ
TPointCloud point_cloud
Optionally, raw data can be converted into a 3D point cloud (local coordinates wrt the sensor...
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...
A numeric matrix of compile-time fixed size.
This base provides a set of functions for maths stuff.
#define CLASS_ID(T)
Access to runtime class ID for a defined class name.
void writeToStream(mrpt::utils::CStream &out) const
Binary dump to stream - for usage in derived classes' serialization.
Lightweight 3D point (float version).
std::shared_ptr< CMetricMap > Ptr
virtual void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::utils::TMatchingPairList &correspondences, const TMatchingParams ¶ms, TMatchingExtraResults &extraResults) const override
Computes the matching between this and another 2D point map, which includes finding: ...
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
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...
double sigma_dist
Sigma squared (variance, in meters) of the exponential used to model the likelihood (default= 0...
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
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.
virtual 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.
bool m_largestDistanceFromOriginIsUpdated
Auxiliary variables used in "getLargestDistanceFromOrigin".
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...
std::shared_ptr< CSetOfObjects > Ptr
This namespace contains representation of robot actions and observations.
#define IMPLEMENTS_MEXPLUS_FROM(complete_type)
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 ...
virtual void setPointWeight(size_t index, unsigned long w)
Sets the point weight, which is ignored in all classes but those which actually store that field (Not...
double x
X,Y,Z coordinates.
virtual bool savePCDFile(const std::string &filename, bool save_as_binary) const
Save the point cloud as a PCL PCD file, in either ASCII or binary format (requires MRPT built against...
void getPCLPointCloud(POINTCLOUD &cloud) const
Use to convert this MRPT point cloud object into a PCL point cloud object (PointCloud<PointXYZ>).
virtual bool isEmpty() const override
Returns true if the map is empty/no observation has been inserted.
float getLargestDistanceFromOrigin() const
This method returns the largest distance from the origin to any of the points, such as a sphere cente...
std::vector< float > x
The point coordinates.
float m_largestDistanceFromOrigin
Auxiliary variables used in "getLargestDistanceFromOrigin".
GLsizei const GLchar ** string
static mrpt::utils::TColorf COLOR_3DSCENE_value(0, 0, 1)
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void clipOutOfRange(const mrpt::math::TPoint2D &point, float maxRange)
Delete points which are more far than "maxRange" away from the given "point".
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.
int fprintf(FILE *fil, const char *format,...) noexcept MRPT_printf_format_check(2
An OS-independent version of fprintf.
void readFromStream(mrpt::utils::CStream &in)
Binary dump to stream - for usage in derived classes' serialization.
void clipOutOfRangeInZ(float zMin, float zMax)
Delete points out of the given "z" axis range have been removed.
float POINTSMAPS_3DOBJECT_POINTSIZE_value
unsigned long getPoint(size_t index, float &x, float &y, float &z) const
Access to a given point from map, as a 2D point.
std::vector< uint8_t > intensity
Color [0,255].
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...
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.
bool load2Dor3D_from_text_file(const std::string &file, const bool is_3D)
2D or 3D generic implementation of load2D_from_text_file and load3D_from_text_file ...
bool addToExistingPointsMap
Applicable to "loadFromRangeScan" only! If set to false, the points from the scan are loaded...
bool fuseWithExisting
If set to true (default=false), inserted points are "fused" with previously existent ones...
TLikelihoodOptions likelihoodOptions
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
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.
void POINTSMAPS_3DOBJECT_POINTSIZE(float value)
The size of points when exporting with getAs3DObject() (default=3.0) Affects to:
virtual mxArray * writeToMatlab() const
Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class.
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).
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 composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=nullptr, 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...
const double & phi() const
Get the phi angle of the 2D pose (in radians)
#define IS_CLASS(ptrObj, class_name)
Evaluates to true if the given pointer to an object (derived from mrpt::utils::CSerializable) is of t...
void kdtree_mark_as_outdated() const
To be called by child classes when KD tree data changes.
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 loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
float horizontalTolerance
The tolerance in rads in pitch & roll for a laser scan to be considered horizontal, considered only when isPlanarMap=true (default=0).
A RGB color - floats in the range [0,1].
virtual bool loadPCDFile(const std::string &filename)
Load the point cloud from a PCL PCD file (requires MRPT built against PCL)
int round(const T value)
Returns the closer integer (int) to x.
virtual ~CPointsMap()
Virtual destructor.
void(*)(const mrpt::obs::CObservation2DRangeScan &obs, mrpt::maps::CMetricMap::Ptr &out_map, const void *insertOps) scan2pts_functor
void writeToStream(mrpt::utils::CStream &out) const
Binary dump to stream - for usage in derived classes' serialization.
TInsertionOptions insertionOptions
The options used when inserting observations in the map.
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.
typedef void(APIENTRYP PFNGLBLENDCOLORPROC)(GLclampf red
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 ...
#define MRPT_LOAD_CONFIG_VAR_DEGREES( variableName, configFileObject, sectionNameStr)
Loads a double variable, stored as radians but entered in the INI-file as degrees.
TAuxLoadFunctor dummy_loader
GLsizei const GLfloat * value
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()
#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...
virtual 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) ...
std::shared_ptr< CPointCloud > Ptr
void extractPoints(const mrpt::math::TPoint3D &corner1, const mrpt::math::TPoint3D &corner2, CPointsMap *outMap, const double &R=1, const double &G=1, const double &B=1)
Extracts the points in the map within the area defined by two corners.
Parameters for the determination of matchings between point clouds, etc.
size_t size() const
Returns the number of stored points in the map.
#define ASSERTMSG_(f, __ERROR_MSG)
GLubyte GLubyte GLubyte a
bool disableDeletion
If set to false (default=true) points in the same plane as the inserted scan and inside the free spac...
GLenum const GLfloat * params
double phi
Orientation (rads)
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.
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
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".
struct mxArray_tag mxArray
Forward declaration for mxArray (avoid #including as much as possible to speed up compiling) ...
TMeasurementList sensedData
All the measurements.
virtual int printf(const char *fmt,...) MRPT_printf_format_check(2
Writes a string to the stream in a textual form.
#define IMPLEMENTS_VIRTUAL_SERIALIZABLE( class_name, base_class_name, NameSpace)
This must be inserted as implementation of some required members for virtual CSerializable classes: ...
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...