17 template <
class Derived>
    18 struct loadFromRangeImpl
    27         obj.mark_as_modified();
    44         if (!
obj.insertionOptions.addToExistingPointsMap)
    49         const int sizeRangeScan = rangeScan.
scan.
size();
    51         if (!sizeRangeScan) 
return;  
    54         if (
obj.m_x.size() + sizeRangeScan > 
obj.m_x.capacity())
    56             obj.reserve((
size_t)(
obj.m_x.size() * 1.2f) + 3 * sizeRangeScan);
    66         float m00 = lric.
HM(0, 0);
    67         float m01 = lric.
HM(0, 1);
    68         float m03 = lric.
HM(0, 3);
    69         float m10 = lric.
HM(1, 0);
    70         float m11 = lric.
HM(1, 1);
    71         float m13 = lric.
HM(1, 3);
    72         float m20 = lric.
HM(2, 0);
    73         float m21 = lric.
HM(2, 1);
    74         float m23 = lric.
HM(2, 3);
    76         float lx_1, ly_1, lz_1, lx = 0, ly = 0,
    88         const bool useMinDist =
    89             obj.insertionOptions.minDistBetweenLaserPoints > 0;
    90         const float minDistSqrBetweenLaserPoints =
    91             square(
obj.insertionOptions.minDistBetweenLaserPoints);
    96         bool lastPointWasValid = 
true;
    97         bool thisIsTheFirst = 
true;
    98         bool lastPointWasInserted = 
false;
   106         const size_t nPointsAtStart = 
obj.size();
   107         size_t nextPtIdx = nPointsAtStart;
   110             const size_t expectedMaxSize =
   113                  (
obj.insertionOptions.also_interpolate ? 3 : 1));
   114             obj.m_x.resize(expectedMaxSize);
   115             obj.m_y.resize(expectedMaxSize);
   116             obj.m_z.resize(expectedMaxSize);
   125             sincos_vals = 
obj.m_scans_sincos_cache.getSinCosForScan(rangeScan);
   128         Eigen::Array<float, Eigen::Dynamic, 1> scan_gx(sizeRangeScan + 3),
   129             scan_gy(sizeRangeScan + 3),
   136             size_t nPackets = sizeRangeScan / 4;
   137             if ((sizeRangeScan & 0x03) != 0) nPackets++;
   147             const __m128 m00_4val =
   149             const __m128 m01_4val = _mm_set1_ps(m01);
   150             const __m128 m03_4val = _mm_set1_ps(m03);
   152             const __m128 m10_4val = _mm_set1_ps(m10);
   153             const __m128 m11_4val = _mm_set1_ps(m11);
   154             const __m128 m13_4val = _mm_set1_ps(m13);
   156             const __m128 m20_4val = _mm_set1_ps(m20);
   157             const __m128 m21_4val = _mm_set1_ps(m21);
   158             const __m128 m23_4val = _mm_set1_ps(m23);
   167             const float* ptr_in_scan = &rangeScan.
scan[0];
   168             const float* ptr_in_cos = &sincos_vals.
ccos[0];
   169             const float* ptr_in_sin = &sincos_vals.
csin[0];
   171             float* ptr_out_x = &scan_gx[0];
   172             float* ptr_out_y = &scan_gy[0];
   173             float* ptr_out_z = &scan_gz[0];
   175             for (; nPackets; nPackets--, ptr_in_scan += 4, ptr_in_cos += 4,
   176                              ptr_in_sin += 4, ptr_out_x += 4, ptr_out_y += 4,
   179                 const __m128 scan_4vals =
   180                     _mm_loadu_ps(ptr_in_scan);  
   183                     _mm_mul_ps(scan_4vals, _mm_load_ps(ptr_in_cos));
   185                     _mm_mul_ps(scan_4vals, _mm_load_ps(ptr_in_sin));
   188                     ptr_out_x, _mm_add_ps(
   189                                    m03_4val, _mm_add_ps(
   190                                                  _mm_mul_ps(xs, m00_4val),
   191                                                  _mm_mul_ps(ys, m01_4val))));
   193                     ptr_out_y, _mm_add_ps(
   194                                    m13_4val, _mm_add_ps(
   195                                                  _mm_mul_ps(xs, m10_4val),
   196                                                  _mm_mul_ps(ys, m11_4val))));
   198                     ptr_out_z, _mm_add_ps(
   199                                    m23_4val, _mm_add_ps(
   200                                                  _mm_mul_ps(xs, m20_4val),
   201                                                  _mm_mul_ps(ys, m21_4val))));
   203 #else  // MRPT_HAS_SSE2   206             Eigen::Array<float, Eigen::Dynamic, 1> scan_x(sizeRangeScan + 3),
   207                 scan_y(sizeRangeScan + 3);
   211                 const_cast<float*>(&rangeScan.
scan[0]), rangeScan.
scan.
size(),
   216                 const_cast<float*>(&sincos_vals.
ccos[0]), rangeScan.
scan.
size(),
   219                 const_cast<float*>(&sincos_vals.
csin[0]), rangeScan.
scan.
size(),
   223             scan_x = scan_vals.array() * ccos.array();
   224             scan_y = scan_vals.array() * csin.array();
   228             scan_gx = m00 * scan_x + m01 * scan_y + m03;
   229             scan_gy = m10 * scan_x + m11 * scan_y + m13;
   230             scan_gz = m20 * scan_x + m21 * scan_y + m23;
   231 #endif  // MRPT_HAS_SSE2   234         for (
int i = 0; i < sizeRangeScan; i++)
   245                         obj, lx, ly, lz, lric);
   247                 lastPointWasInserted = 
false;
   250                 bool pt_pass_min_dist = 
true;
   252                 if (useMinDist || 
obj.insertionOptions.also_interpolate)
   254                     if (!lastPointWasValid)
   255                         pt_pass_min_dist = 
false;
   261                         pt_pass_min_dist = (d2 > minDistSqrBetweenLaserPoints);
   265                 if (thisIsTheFirst || pt_pass_min_dist)
   267                     thisIsTheFirst = 
false;
   271                     if (
obj.insertionOptions.also_interpolate && i > 1)
   273                         float changeInDirection;
   274                         const float d = std::sqrt(d2);
   276                         if ((lx != lx_1 || ly != ly_1) &&
   277                             (lx_1 != lx_2 || ly_1 != ly_2))
   278                             changeInDirection = atan2(ly - ly_1, lx - lx_1) -
   279                                                 atan2(ly_1 - ly_2, lx_1 - lx_2);
   281                             changeInDirection = 0;
   284                         if (d >= 2 * 
obj.insertionOptions
   285                                          .minDistBetweenLaserPoints &&
   286                             d < 
obj.insertionOptions
   287                                     .maxDistForInterpolatePoints &&
   288                             fabs(changeInDirection) < 
DEG2RAD(5))
   291                                 d / (2 * sqrt(minDistSqrBetweenLaserPoints)));
   293                             for (
int q = 1; 
q < nInterpol; 
q++)
   295                                 float i_x = lx_1 + 
q * (lx - lx_1) / nInterpol;
   296                                 float i_y = ly_1 + 
q * (ly - ly_1) / nInterpol;
   297                                 float i_z = lz_1 + 
q * (lz - lz_1) / nInterpol;
   298                                 if (!
obj.m_heightfilter_enabled ||
   299                                     (i_z >= 
obj.m_heightfilter_z_min &&
   300                                      i_z <= 
obj.m_heightfilter_z_max))
   302                                     obj.m_x.push_back(i_x);
   303                                     obj.m_y.push_back(i_y);
   304                                     obj.m_z.push_back(i_z);
   315                     if (!
obj.m_heightfilter_enabled ||
   316                         (lz >= 
obj.m_heightfilter_z_min &&
   317                          lz <= 
obj.m_heightfilter_z_max))
   319                         obj.m_x[nextPtIdx] = lx;
   320                         obj.m_y[nextPtIdx] = ly;
   321                         obj.m_z[nextPtIdx] = lz;
   330                         lastPointWasInserted = 
true;
   345             lastPointWasValid = rangeScan.
validRange[i] != 0;
   349         if (lastPointWasValid && !lastPointWasInserted)
   351             if (!
obj.m_heightfilter_enabled ||
   352                 (lz >= 
obj.m_heightfilter_z_min &&
   353                  lz <= 
obj.m_heightfilter_z_max))
   355                 obj.m_x[nextPtIdx] = lx;
   356                 obj.m_y[nextPtIdx] = ly;
   357                 obj.m_z[nextPtIdx] = lz;
   367         obj.m_x.resize(nextPtIdx);
   368         obj.m_y.resize(nextPtIdx);
   369         obj.m_z.resize(nextPtIdx);
   378         obj.mark_as_modified();
   388         if (!
obj.insertionOptions.addToExistingPointsMap)
   395         const size_t sizeRangeScan = rangeScan.
points3D_x.size();
   398         if (
obj.m_x.size() + sizeRangeScan > 
obj.m_x.capacity())
   399             obj.reserve(
size_t(
obj.m_x.size() + 1.1 * sizeRangeScan));
   406         float m00 = lric.
HM(0, 0);
   407         float m01 = lric.
HM(0, 1);
   408         float m02 = lric.
HM(0, 2);
   409         float m03 = lric.
HM(0, 3);
   410         float m10 = lric.
HM(1, 0);
   411         float m11 = lric.
HM(1, 1);
   412         float m12 = lric.
HM(1, 2);
   413         float m13 = lric.
HM(1, 3);
   414         float m20 = lric.
HM(2, 0);
   415         float m21 = lric.
HM(2, 1);
   416         float m22 = lric.
HM(2, 2);
   417         float m23 = lric.
HM(2, 3);
   419         float lx_1, ly_1, lz_1, lx = 0, ly = 0,
   427         float minDistSqrBetweenLaserPoints =
   428             square(
obj.insertionOptions.minDistBetweenLaserPoints);
   431         if (
obj.insertionOptions.minDistBetweenLaserPoints <= 0)
   432             minDistSqrBetweenLaserPoints = -1;
   437         bool lastPointWasValid = 
true;
   438         bool thisIsTheFirst = 
true;
   439         bool lastPointWasInserted = 
false;
   444         for (
size_t i = 0; i < sizeRangeScan; i++)
   449                 obj.insertionOptions.insertInvalidPoints)
   465                         obj, lx, ly, lz, lric);
   467                 lastPointWasInserted = 
false;
   472                 if (thisIsTheFirst ||
   473                     (lastPointWasValid && (d2 > minDistSqrBetweenLaserPoints)))
   475                     thisIsTheFirst = 
false;
   477                     obj.m_x.push_back(lx);
   478                     obj.m_y.push_back(ly);
   479                     obj.m_z.push_back(lz);
   485                     lastPointWasInserted = 
true;
   492                 lastPointWasValid = 
true;
   496                 lastPointWasValid = 
false;
   504         if (lastPointWasValid && !lastPointWasInserted)
   506             if (lx != 0 || ly != 0 || lz != 0)
   508                 obj.m_x.push_back(lx);
   509                 obj.m_y.push_back(ly);
   510                 obj.m_z.push_back(lz);
 double DEG2RAD(const double x)
Degrees to radians. 
 
GLdouble GLdouble GLdouble GLdouble q
 
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. 
 
GLsizei GLsizei GLuint * obj
 
size_t getScanSize() const
Get number of scan rays. 
 
mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< char > > validRange
It's false (=0) on no reflected rays, referenced to elements in scan. 
 
std::vector< float > points3D_z
 
static void templ_loadFromRangeScan(Derived &obj, const mrpt::obs::CObservation3DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose)
 
T square(const T x)
Inline function for the square of a number. 
 
mrpt::math::CVectorFloat ccos
 
std::vector< float > points3D_y
 
mrpt::containers::ContainerReadOnlyProxyAccessor< mrpt::aligned_std_vector< float > > scan
The range values of the scan, in meters. 
 
void composeFrom(const CPose3D &A, const CPose3D &B)
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids th...
 
mrpt::math::CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot. 
 
float scan_x
In internal_loadFromRangeScan3D_prepareOneRange, these are the local coordinates of the scan points b...
 
static void templ_loadFromRangeScan(Derived &obj, const mrpt::obs::CObservation2DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose)
 
bool hasPoints3D
true means the field points3D contains valid data. 
 
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
 
mrpt::math::CVectorFloat csin
 
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
 
A pair of vectors with the cos and sin values. 
 
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot. 
 
A class used to store a 3D pose (a 3D translation + a rotation in 3D). 
 
std::vector< float > points3D_x
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera...
 
Helper struct used for internal_loadFromRangeScan3D_prepareOneRange() 
 
mrpt::math::CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot. 
 
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
 
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan. 
 
Helper struct used for internal_loadFromRangeScan2D_prepareOneRange() 
 
int round(const T value)
Returns the closer integer (int) to x.