9 #ifndef cpointsmap_crtp_common_H
10 #define cpointsmap_crtp_common_H
23 template <
class Derived>
34 obj.mark_as_modified();
43 if (!
obj.insertionOptions.addToExistingPointsMap)
46 const int sizeRangeScan = rangeScan.
scan.
size();
52 if (
obj.x.size()+sizeRangeScan >
obj.x.capacity() )
54 obj.reserve( (
size_t) (
obj.x.size() * 1.2f) + 3*sizeRangeScan );
63 float m00 = lric.
HM.get_unsafe(0,0);
64 float m01 = lric.
HM.get_unsafe(0,1);
65 float m03 = lric.
HM.get_unsafe(0,3);
66 float m10 = lric.
HM.get_unsafe(1,0);
67 float m11 = lric.
HM.get_unsafe(1,1);
68 float m13 = lric.
HM.get_unsafe(1,3);
69 float m20 = lric.
HM.get_unsafe(2,0);
70 float m21 = lric.
HM.get_unsafe(2,1);
71 float m23 = lric.
HM.get_unsafe(2,3);
73 float lx_1,ly_1,lz_1,lx=0,ly=0,lz=0;
77 lx_1 = -100; ly_1 = -100; lz_1 = -100;
78 lx_2 = -100; ly_2 = -100;
81 const bool useMinDist =
obj.insertionOptions.minDistBetweenLaserPoints>0;
82 const float minDistSqrBetweenLaserPoints =
square(
obj.insertionOptions.minDistBetweenLaserPoints );
87 bool lastPointWasValid =
true;
88 bool thisIsTheFirst =
true;
89 bool lastPointWasInserted =
false;
96 const size_t nPointsAtStart =
obj.size();
97 size_t nextPtIdx = nPointsAtStart;
100 const size_t expectedMaxSize = nPointsAtStart+(sizeRangeScan* (
obj.insertionOptions.also_interpolate ? 3:1) );
101 obj.x.resize( expectedMaxSize );
102 obj.y.resize( expectedMaxSize );
103 obj.z.resize( expectedMaxSize );
113 Eigen::Array<float,Eigen::Dynamic,1> scan_gx(sizeRangeScan+3), scan_gy(sizeRangeScan+3),scan_gz(sizeRangeScan+3);
117 size_t nPackets = sizeRangeScan/4;
118 if ( (sizeRangeScan & 0x03)!=0) nPackets++;
128 const __m128 m00_4val = _mm_set1_ps(m00);
129 const __m128 m01_4val = _mm_set1_ps(m01);
130 const __m128 m03_4val = _mm_set1_ps(m03);
132 const __m128 m10_4val = _mm_set1_ps(m10);
133 const __m128 m11_4val = _mm_set1_ps(m11);
134 const __m128 m13_4val = _mm_set1_ps(m13);
136 const __m128 m20_4val = _mm_set1_ps(m20);
137 const __m128 m21_4val = _mm_set1_ps(m21);
138 const __m128 m23_4val = _mm_set1_ps(m23);
144 const float *ptr_in_scan = &rangeScan.
scan[0];
145 const float *ptr_in_cos = &sincos_vals.
ccos[0];
146 const float *ptr_in_sin = &sincos_vals.
csin[0];
148 float *ptr_out_x = &scan_gx[0];
149 float *ptr_out_y = &scan_gy[0];
150 float *ptr_out_z = &scan_gz[0];
152 for( ; nPackets; nPackets--, ptr_in_scan+=4, ptr_in_cos+=4, ptr_in_sin+=4, ptr_out_x+=4, ptr_out_y+=4, ptr_out_z+=4 )
154 const __m128 scan_4vals = _mm_loadu_ps(ptr_in_scan);
156 const __m128 xs = _mm_mul_ps(scan_4vals, _mm_load_ps(ptr_in_cos) );
157 const __m128 ys = _mm_mul_ps(scan_4vals, _mm_load_ps(ptr_in_sin) );
159 _mm_store_ps(ptr_out_x, _mm_add_ps(m03_4val, _mm_add_ps( _mm_mul_ps(xs,m00_4val), _mm_mul_ps(ys,m01_4val) ) ) );
160 _mm_store_ps(ptr_out_y, _mm_add_ps(m13_4val, _mm_add_ps( _mm_mul_ps(xs,m10_4val), _mm_mul_ps(ys,m11_4val) ) ) );
161 _mm_store_ps(ptr_out_z, _mm_add_ps(m23_4val, _mm_add_ps( _mm_mul_ps(xs,m20_4val), _mm_mul_ps(ys,m21_4val) ) ) );
165 Eigen::Array<float,Eigen::Dynamic,1> scan_x(sizeRangeScan+3), scan_y(sizeRangeScan+3);
168 const Eigen::Map<Eigen::Matrix<float,Eigen::Dynamic,1> > scan_vals(
const_cast<float*
>(&rangeScan.
scan[0]),rangeScan.
scan.
size(),1 );
170 const Eigen::Map<Eigen::Matrix<float,Eigen::Dynamic,1> > ccos(
const_cast<float*
>(&sincos_vals.
ccos[0]),rangeScan.
scan.
size(),1 );
171 const Eigen::Map<Eigen::Matrix<float,Eigen::Dynamic,1> > csin(
const_cast<float*
>(&sincos_vals.
csin[0]),rangeScan.
scan.
size(),1 );
174 scan_x = scan_vals.array() * ccos.array();
175 scan_y = scan_vals.array() * csin.array();
179 scan_gx = m00*scan_x+m01*scan_y+m03;
180 scan_gy = m10*scan_x+m11*scan_y+m13;
181 scan_gz = m20*scan_x+m21*scan_y+m23;
186 for (
int i=0;i<sizeRangeScan;i++)
197 lastPointWasInserted =
false;
200 bool pt_pass_min_dist =
true;
202 if (useMinDist ||
obj.insertionOptions.also_interpolate)
204 if (!lastPointWasValid)
205 pt_pass_min_dist =
false;
209 pt_pass_min_dist = (d2 > minDistSqrBetweenLaserPoints);
213 if ( thisIsTheFirst || pt_pass_min_dist )
215 thisIsTheFirst =
false;
218 if (
obj.insertionOptions.also_interpolate && i>1)
220 float changeInDirection;
221 const float d = std::sqrt( d2 );
223 if ((lx!=lx_1 || ly!=ly_1) && (lx_1!=lx_2 || ly_1!=ly_2) )
224 changeInDirection = atan2(ly-ly_1,lx-lx_1)-atan2(ly_1-ly_2,lx_1-lx_2);
225 else changeInDirection = 0;
228 if (d>=2*
obj.insertionOptions.minDistBetweenLaserPoints &&
229 d<
obj.insertionOptions.maxDistForInterpolatePoints &&
230 fabs(changeInDirection)<
DEG2RAD(5) )
234 for (
int q=1;
q<nInterpol;
q++)
236 float i_x = lx_1 +
q*(lx-lx_1)/nInterpol;
237 float i_y = ly_1 +
q*(ly-ly_1)/nInterpol;
238 float i_z = lz_1 +
q*(lz-lz_1)/nInterpol;
239 if( !
obj.m_heightfilter_enabled || ( i_z >=
obj.m_heightfilter_z_min && i_z <=
obj.m_heightfilter_z_max ) )
241 obj.x.push_back( i_x );
242 obj.y.push_back( i_y );
243 obj.z.push_back( i_z );
251 if( !
obj.m_heightfilter_enabled || (lz >=
obj.m_heightfilter_z_min && lz <=
obj.m_heightfilter_z_max ) )
253 obj.x[nextPtIdx] = lx;
254 obj.y[nextPtIdx] = ly;
255 obj.z[nextPtIdx] = lz;
261 lastPointWasInserted =
true;
277 lastPointWasValid = rangeScan.
validRange[i] != 0;
281 if (lastPointWasValid && !lastPointWasInserted)
283 if( !
obj.m_heightfilter_enabled || (lz >=
obj.m_heightfilter_z_min && lz <=
obj.m_heightfilter_z_max ) )
285 obj.x[nextPtIdx] = lx;
286 obj.y[nextPtIdx] = ly;
287 obj.z[nextPtIdx] = lz;
295 obj.x.resize( nextPtIdx );
296 obj.y.resize( nextPtIdx );
297 obj.z.resize( nextPtIdx );
307 obj.mark_as_modified();
316 if (!
obj.insertionOptions.addToExistingPointsMap)
322 const size_t sizeRangeScan = rangeScan.
points3D_x.size();
325 if (
obj.x.size()+sizeRangeScan>
obj.x.capacity() )
326 obj.reserve(
size_t(
obj.x.size() + 1.1*sizeRangeScan) );
334 float m00 = lric.
HM.get_unsafe(0,0);
335 float m01 = lric.
HM.get_unsafe(0,1);
336 float m02 = lric.
HM.get_unsafe(0,2);
337 float m03 = lric.
HM.get_unsafe(0,3);
338 float m10 = lric.
HM.get_unsafe(1,0);
339 float m11 = lric.
HM.get_unsafe(1,1);
340 float m12 = lric.
HM.get_unsafe(1,2);
341 float m13 = lric.
HM.get_unsafe(1,3);
342 float m20 = lric.
HM.get_unsafe(2,0);
343 float m21 = lric.
HM.get_unsafe(2,1);
344 float m22 = lric.
HM.get_unsafe(2,2);
345 float m23 = lric.
HM.get_unsafe(2,3);
347 float lx_1,ly_1,lz_1,lx=0,ly=0,lz=0;
350 lx_1 = -100; ly_1 = -100; lz_1 = -100;
352 float minDistSqrBetweenLaserPoints =
square(
obj.insertionOptions.minDistBetweenLaserPoints );
355 if (
obj.insertionOptions.minDistBetweenLaserPoints<=0)
356 minDistSqrBetweenLaserPoints = -1;
361 bool lastPointWasValid =
true;
362 bool thisIsTheFirst =
true;
363 bool lastPointWasInserted =
false;
368 for (
size_t i=0;i<sizeRangeScan;i++)
384 lastPointWasInserted =
false;
388 if ( thisIsTheFirst || (lastPointWasValid && (d2 > minDistSqrBetweenLaserPoints)) )
390 thisIsTheFirst =
false;
392 obj.x.push_back( lx );
393 obj.y.push_back( ly );
394 obj.z.push_back( lz );
398 lastPointWasInserted =
true;
405 lastPointWasValid =
true;
409 lastPointWasValid =
false;
416 if (lastPointWasValid && !lastPointWasInserted)
418 if (lx!=0 || ly!=0 || lz!=0)
420 obj.x.push_back( lx );
421 obj.y.push_back( ly );
422 obj.z.push_back( lz );
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< char > > validRange
It's false (=0) on no reflected rays, referenced to elements in scan.
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< float > > scan
The range values of the scan, in meters. Must have same length than validRange.
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement,...
bool hasPoints3D
true means the field points3D contains valid data.
std::vector< float > points3D_x
std::vector< float > points3D_y
std::vector< float > points3D_z
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera.
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).
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...
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
GLsizei GLsizei GLuint * obj
GLdouble GLdouble GLdouble GLdouble q
int round(const T value)
Returns the closer integer (int) to x.
T square(const T x)
Inline function for the square of a number.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double DEG2RAD(const double x)
Degrees to radians.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Helper struct used for internal_loadFromRangeScan2D_prepareOneRange()
mrpt::math::CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot.
Helper struct used for internal_loadFromRangeScan3D_prepareOneRange()
mrpt::math::CMatrixDouble44 HM
Homog matrix of the local sensor pose within the robot.
float scan_z
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)
static void templ_loadFromRangeScan(Derived &obj, const mrpt::obs::CObservation3DRangeScan &rangeScan, const mrpt::poses::CPose3D *robotPose)
A pair of vectors with the cos and sin values.
mrpt::math::CVectorFloat csin
mrpt::math::CVectorFloat ccos