41 #include <pcl/common/eigen.h>
42 #include <pcl/console/print.h>
52 template <
typename Scalar,
typename Roots>
inline void
55 roots (0) = Scalar (0);
56 Scalar d = Scalar (b * b - 4.0 * c);
60 Scalar sd = std::sqrt (d);
62 roots (2) = 0.5f * (b + sd);
63 roots (1) = 0.5f * (b - sd);
67 template <
typename Matrix,
typename Roots>
inline void
70 using Scalar =
typename Matrix::Scalar;
75 Scalar c0 = m (0, 0) * m (1, 1) * m (2, 2)
76 + Scalar (2) * m (0, 1) * m (0, 2) * m (1, 2)
77 - m (0, 0) * m (1, 2) * m (1, 2)
78 - m (1, 1) * m (0, 2) * m (0, 2)
79 - m (2, 2) * m (0, 1) * m (0, 1);
80 Scalar c1 = m (0, 0) * m (1, 1) -
86 Scalar c2 = m (0, 0) + m (1, 1) + m (2, 2);
88 if (std::abs (c0) < Eigen::NumTraits < Scalar > ::epsilon ())
92 constexpr Scalar s_inv3 = Scalar(1.0 / 3.0);
93 const Scalar s_sqrt3 = std::sqrt (Scalar (3.0));
96 Scalar c2_over_3 = c2 * s_inv3;
97 Scalar a_over_3 = (c1 - c2 * c2_over_3) * s_inv3;
98 if (a_over_3 > Scalar (0))
99 a_over_3 = Scalar (0);
101 Scalar half_b = Scalar (0.5) * (c0 + c2_over_3 * (Scalar (2) * c2_over_3 * c2_over_3 - c1));
103 Scalar q = half_b * half_b + a_over_3 * a_over_3 * a_over_3;
108 Scalar rho = std::sqrt (-a_over_3);
109 Scalar theta = std::atan2 (std::sqrt (-q), half_b) * s_inv3;
110 Scalar cos_theta = std::cos (theta);
111 Scalar sin_theta = std::sin (theta);
112 roots (0) = c2_over_3 + Scalar (2) * rho * cos_theta;
113 roots (1) = c2_over_3 - rho * (cos_theta + s_sqrt3 * sin_theta);
114 roots (2) = c2_over_3 - rho * (cos_theta - s_sqrt3 * sin_theta);
117 if (roots (0) >= roots (1))
118 std::swap (roots (0), roots (1));
119 if (roots (1) >= roots (2))
121 std::swap (roots (1), roots (2));
122 if (roots (0) >= roots (1))
123 std::swap (roots (0), roots (1));
132 template <
typename Matrix,
typename Vector>
inline void
133 eigen22 (
const Matrix& mat,
typename Matrix::Scalar& eigenvalue, Vector& eigenvector)
137 if (std::abs (mat.coeff (1)) <= std::numeric_limits<typename Matrix::Scalar>::min ())
139 if (mat.coeff (0) < mat.coeff (2))
141 eigenvalue = mat.coeff (0);
142 eigenvector[0] = 1.0;
143 eigenvector[1] = 0.0;
147 eigenvalue = mat.coeff (2);
148 eigenvector[0] = 0.0;
149 eigenvector[1] = 1.0;
155 typename Matrix::Scalar trace =
static_cast<typename Matrix::Scalar
> (0.5) * (mat.coeff (0) + mat.coeff (3));
156 typename Matrix::Scalar determinant = mat.coeff (0) * mat.coeff (3) - mat.coeff (1) * mat.coeff (1);
158 typename Matrix::Scalar temp = trace * trace - determinant;
163 eigenvalue = trace - std::sqrt (temp);
165 eigenvector[0] = -mat.coeff (1);
166 eigenvector[1] = mat.coeff (0) - eigenvalue;
167 eigenvector.normalize ();
171 template <
typename Matrix,
typename Vector>
inline void
172 eigen22 (
const Matrix& mat, Matrix& eigenvectors, Vector& eigenvalues)
176 if (std::abs (mat.coeff (1)) <= std::numeric_limits<typename Matrix::Scalar>::min ())
178 if (mat.coeff (0) < mat.coeff (3))
180 eigenvalues.coeffRef (0) = mat.coeff (0);
181 eigenvalues.coeffRef (1) = mat.coeff (3);
182 eigenvectors.coeffRef (0) = 1.0;
183 eigenvectors.coeffRef (1) = 0.0;
184 eigenvectors.coeffRef (2) = 0.0;
185 eigenvectors.coeffRef (3) = 1.0;
189 eigenvalues.coeffRef (0) = mat.coeff (3);
190 eigenvalues.coeffRef (1) = mat.coeff (0);
191 eigenvectors.coeffRef (0) = 0.0;
192 eigenvectors.coeffRef (1) = 1.0;
193 eigenvectors.coeffRef (2) = 1.0;
194 eigenvectors.coeffRef (3) = 0.0;
200 typename Matrix::Scalar trace =
static_cast<typename Matrix::Scalar
> (0.5) * (mat.coeff (0) + mat.coeff (3));
201 typename Matrix::Scalar determinant = mat.coeff (0) * mat.coeff (3) - mat.coeff (1) * mat.coeff (1);
203 typename Matrix::Scalar temp = trace * trace - determinant;
208 temp = std::sqrt (temp);
210 eigenvalues.coeffRef (0) = trace - temp;
211 eigenvalues.coeffRef (1) = trace + temp;
214 eigenvectors.coeffRef (0) = -mat.coeff (1);
215 eigenvectors.coeffRef (2) = mat.coeff (0) - eigenvalues.coeff (0);
216 typename Matrix::Scalar norm =
static_cast<typename Matrix::Scalar
> (1.0)
217 /
static_cast<typename Matrix::Scalar
> (std::sqrt (eigenvectors.coeffRef (0) * eigenvectors.coeffRef (0) + eigenvectors.coeffRef (2) * eigenvectors.coeffRef (2)));
218 eigenvectors.coeffRef (0) *= norm;
219 eigenvectors.coeffRef (2) *= norm;
220 eigenvectors.coeffRef (1) = eigenvectors.coeffRef (2);
221 eigenvectors.coeffRef (3) = -eigenvectors.coeffRef (0);
225 template <
typename Matrix,
typename Vector>
inline void
228 using Scalar =
typename Matrix::Scalar;
232 Scalar scale = mat.cwiseAbs ().maxCoeff ();
233 if (scale <= std::numeric_limits < Scalar > ::min ())
234 scale = Scalar (1.0);
236 Matrix scaledMat = mat / scale;
238 scaledMat.diagonal ().array () -= eigenvalue / scale;
240 Vector vec1 = scaledMat.row (0).cross (scaledMat.row (1));
241 Vector vec2 = scaledMat.row (0).cross (scaledMat.row (2));
242 Vector vec3 = scaledMat.row (1).cross (scaledMat.row (2));
244 Scalar len1 = vec1.squaredNorm ();
245 Scalar len2 = vec2.squaredNorm ();
246 Scalar len3 = vec3.squaredNorm ();
248 if (len1 >= len2 && len1 >= len3)
249 eigenvector = vec1 / std::sqrt (len1);
250 else if (len2 >= len1 && len2 >= len3)
251 eigenvector = vec2 / std::sqrt (len2);
253 eigenvector = vec3 / std::sqrt (len3);
259 template <
typename Vector,
typename Scalar>
275 using Scalar =
typename Matrix::Scalar;
276 using Index =
typename Matrix::Index;
279 crossProduct << scaledMatrix.row (0).cross (scaledMatrix.row (1)),
280 scaledMatrix.row (0).cross (scaledMatrix.row (2)),
281 scaledMatrix.row (1).cross (scaledMatrix.row (2));
284 const auto len = crossProduct.rowwise ().norm ();
287 const Scalar length = len.maxCoeff (&index);
288 return {crossProduct.row (index) / length, length};
294 template <
typename Matrix,
typename Vector>
inline void
295 eigen33 (
const Matrix& mat,
typename Matrix::Scalar& eigenvalue, Vector& eigenvector)
297 using Scalar =
typename Matrix::Scalar;
301 Scalar scale = mat.cwiseAbs ().maxCoeff ();
302 if (scale <= std::numeric_limits < Scalar > ::min ())
303 scale = Scalar (1.0);
305 Matrix scaledMat = mat / scale;
310 eigenvalue = eigenvalues (0) * scale;
311 if ( (eigenvalues (1) - eigenvalues (0)) > Eigen::NumTraits < Scalar > ::epsilon ()) {
314 scaledMat.diagonal ().array () -= eigenvalues (0);
315 eigenvector = detail::getLargest3x3Eigenvector<Vector> (scaledMat).vector;
317 else if ( (eigenvalues (2) - eigenvalues (0)) > Eigen::NumTraits < Scalar > ::epsilon ()) {
319 scaledMat.diagonal ().array () -= eigenvalues (2);
320 eigenvector = detail::getLargest3x3Eigenvector<Vector> (scaledMat).vector.unitOrthogonal ();
324 eigenvector << Scalar (1.0), Scalar (0.0), Scalar (0.0);
329 template <
typename Matrix,
typename Vector>
inline void
332 using Scalar =
typename Matrix::Scalar;
333 Scalar scale = mat.cwiseAbs ().maxCoeff ();
334 if (scale <= std::numeric_limits < Scalar > ::min ())
335 scale = Scalar (1.0);
337 Matrix scaledMat = mat / scale;
343 template <
typename Matrix,
typename Vector>
inline void
344 eigen33 (
const Matrix& mat, Matrix& evecs, Vector& evals)
346 using Scalar =
typename Matrix::Scalar;
350 Scalar scale = mat.cwiseAbs ().maxCoeff ();
351 if (scale <= std::numeric_limits < Scalar > ::min ())
352 scale = Scalar (1.0);
354 Matrix scaledMat = mat / scale;
359 if ( (evals (2) - evals (0)) <= Eigen::NumTraits < Scalar > ::epsilon ())
362 evecs.setIdentity ();
364 else if ( (evals (1) - evals (0)) <= Eigen::NumTraits < Scalar > ::epsilon ())
369 tmp.diagonal ().array () -= evals (2);
371 evecs.col (2) = detail::getLargest3x3Eigenvector<Vector> (tmp).vector;
372 evecs.col (1) = evecs.col (2).unitOrthogonal ();
373 evecs.col (0) = evecs.col (1).cross (evecs.col (2));
375 else if ( (evals (2) - evals (1)) <= Eigen::NumTraits < Scalar > ::epsilon ())
380 tmp.diagonal ().array () -= evals (0);
382 evecs.col (0) = detail::getLargest3x3Eigenvector<Vector> (tmp).vector;
383 evecs.col (1) = evecs.col (0).unitOrthogonal ();
384 evecs.col (2) = evecs.col (0).cross (evecs.col (1));
388 std::array<Scalar, 3> eigenVecLen;
390 for (
int i = 0; i < 3; ++i)
392 Matrix tmp = scaledMat;
393 tmp.diagonal ().array () -= evals (i);
394 const auto vec_len = detail::getLargest3x3Eigenvector<Vector> (tmp);
395 evecs.col (i) = vec_len.vector;
396 eigenVecLen[i] = vec_len.length;
401 const auto minmax_it = std::minmax_element (eigenVecLen.cbegin (), eigenVecLen.cend ());
402 int min_idx =
std::distance (eigenVecLen.cbegin (), minmax_it.first);
403 int max_idx =
std::distance (eigenVecLen.cbegin (), minmax_it.second);
404 int mid_idx = 3 - min_idx - max_idx;
406 evecs.col (min_idx) = evecs.col ( (min_idx + 1) % 3).cross (evecs.col ( (min_idx + 2) % 3)).normalized ();
407 evecs.col (mid_idx) = evecs.col ( (mid_idx + 1) % 3).cross (evecs.col ( (mid_idx + 2) % 3)).normalized ();
414 template <
typename Matrix>
inline typename Matrix::Scalar
417 using Scalar =
typename Matrix::Scalar;
418 Scalar det = matrix.coeff (0) * matrix.coeff (3) - matrix.coeff (1) * matrix.coeff (2);
423 inverse.coeffRef (0) = matrix.coeff (3);
424 inverse.coeffRef (1) = -matrix.coeff (1);
425 inverse.coeffRef (2) = -matrix.coeff (2);
426 inverse.coeffRef (3) = matrix.coeff (0);
433 template <
typename Matrix>
inline typename Matrix::Scalar
436 using Scalar =
typename Matrix::Scalar;
447 Scalar fd_ee = matrix.coeff (4) * matrix.coeff (8) - matrix.coeff (7) * matrix.coeff (5);
448 Scalar ce_bf = matrix.coeff (2) * matrix.coeff (5) - matrix.coeff (1) * matrix.coeff (8);
449 Scalar be_cd = matrix.coeff (1) * matrix.coeff (5) - matrix.coeff (2) * matrix.coeff (4);
451 Scalar det = matrix.coeff (0) * fd_ee + matrix.coeff (1) * ce_bf + matrix.coeff (2) * be_cd;
456 inverse.coeffRef (0) = fd_ee;
457 inverse.coeffRef (1) = inverse.coeffRef (3) = ce_bf;
458 inverse.coeffRef (2) = inverse.coeffRef (6) = be_cd;
459 inverse.coeffRef (4) = (matrix.coeff (0) * matrix.coeff (8) - matrix.coeff (2) * matrix.coeff (2));
460 inverse.coeffRef (5) = inverse.coeffRef (7) = (matrix.coeff (1) * matrix.coeff (2) - matrix.coeff (0) * matrix.coeff (5));
461 inverse.coeffRef (8) = (matrix.coeff (0) * matrix.coeff (4) - matrix.coeff (1) * matrix.coeff (1));
468 template <
typename Matrix>
inline typename Matrix::Scalar
471 using Scalar =
typename Matrix::Scalar;
478 Scalar ie_hf = matrix.coeff (8) * matrix.coeff (4) - matrix.coeff (7) * matrix.coeff (5);
479 Scalar hc_ib = matrix.coeff (7) * matrix.coeff (2) - matrix.coeff (8) * matrix.coeff (1);
480 Scalar fb_ec = matrix.coeff (5) * matrix.coeff (1) - matrix.coeff (4) * matrix.coeff (2);
481 Scalar det = matrix.coeff (0) * (ie_hf) + matrix.coeff (3) * (hc_ib) + matrix.coeff (6) * (fb_ec);
485 inverse.coeffRef (0) = ie_hf;
486 inverse.coeffRef (1) = hc_ib;
487 inverse.coeffRef (2) = fb_ec;
488 inverse.coeffRef (3) = matrix.coeff (6) * matrix.coeff (5) - matrix.coeff (8) * matrix.coeff (3);
489 inverse.coeffRef (4) = matrix.coeff (8) * matrix.coeff (0) - matrix.coeff (6) * matrix.coeff (2);
490 inverse.coeffRef (5) = matrix.coeff (3) * matrix.coeff (2) - matrix.coeff (5) * matrix.coeff (0);
491 inverse.coeffRef (6) = matrix.coeff (7) * matrix.coeff (3) - matrix.coeff (6) * matrix.coeff (4);
492 inverse.coeffRef (7) = matrix.coeff (6) * matrix.coeff (1) - matrix.coeff (7) * matrix.coeff (0);
493 inverse.coeffRef (8) = matrix.coeff (4) * matrix.coeff (0) - matrix.coeff (3) * matrix.coeff (1);
501 template <
typename Matrix>
inline typename Matrix::Scalar
505 return matrix.coeff (0) * (matrix.coeff (4) * matrix.coeff (8) - matrix.coeff (5) * matrix.coeff (7)) +
506 matrix.coeff (1) * (matrix.coeff (5) * matrix.coeff (6) - matrix.coeff (3) * matrix.coeff (8)) +
507 matrix.coeff (2) * (matrix.coeff (3) * matrix.coeff (7) - matrix.coeff (4) * matrix.coeff (6)) ;
513 const Eigen::Vector3f& y_direction,
514 Eigen::Affine3f& transformation)
516 Eigen::Vector3f tmp0 = (y_direction.cross(z_axis)).normalized();
517 Eigen::Vector3f tmp1 = (z_axis.cross(tmp0)).normalized();
518 Eigen::Vector3f tmp2 = z_axis.normalized();
520 transformation(0,0)=tmp0[0]; transformation(0,1)=tmp0[1]; transformation(0,2)=tmp0[2]; transformation(0,3)=0.0f;
521 transformation(1,0)=tmp1[0]; transformation(1,1)=tmp1[1]; transformation(1,2)=tmp1[2]; transformation(1,3)=0.0f;
522 transformation(2,0)=tmp2[0]; transformation(2,1)=tmp2[1]; transformation(2,2)=tmp2[2]; transformation(2,3)=0.0f;
523 transformation(3,0)=0.0f; transformation(3,1)=0.0f; transformation(3,2)=0.0f; transformation(3,3)=1.0f;
529 const Eigen::Vector3f& y_direction)
531 Eigen::Affine3f transformation;
533 return (transformation);
539 const Eigen::Vector3f& y_direction,
540 Eigen::Affine3f& transformation)
542 Eigen::Vector3f tmp2 = (x_axis.cross(y_direction)).normalized();
543 Eigen::Vector3f tmp1 = (tmp2.cross(x_axis)).normalized();
544 Eigen::Vector3f tmp0 = x_axis.normalized();
546 transformation(0,0)=tmp0[0]; transformation(0,1)=tmp0[1]; transformation(0,2)=tmp0[2]; transformation(0,3)=0.0f;
547 transformation(1,0)=tmp1[0]; transformation(1,1)=tmp1[1]; transformation(1,2)=tmp1[2]; transformation(1,3)=0.0f;
548 transformation(2,0)=tmp2[0]; transformation(2,1)=tmp2[1]; transformation(2,2)=tmp2[2]; transformation(2,3)=0.0f;
549 transformation(3,0)=0.0f; transformation(3,1)=0.0f; transformation(3,2)=0.0f; transformation(3,3)=1.0f;
555 const Eigen::Vector3f& y_direction)
557 Eigen::Affine3f transformation;
559 return (transformation);
565 const Eigen::Vector3f& z_axis,
566 Eigen::Affine3f& transformation)
574 const Eigen::Vector3f& z_axis)
576 Eigen::Affine3f transformation;
578 return (transformation);
584 const Eigen::Vector3f& z_axis,
585 const Eigen::Vector3f& origin,
586 Eigen::Affine3f& transformation)
589 Eigen::Vector3f translation = transformation*origin;
590 transformation(0,3)=-translation[0]; transformation(1,3)=-translation[1]; transformation(2,3)=-translation[2];
594 template <
typename Scalar>
void
595 getEulerAngles (
const Eigen::Transform<Scalar, 3, Eigen::Affine> &t, Scalar &roll, Scalar &pitch, Scalar &yaw)
597 roll = std::atan2 (t (2, 1), t (2, 2));
598 pitch = asin (-t (2, 0));
599 yaw = std::atan2 (t (1, 0), t (0, 0));
603 template <
typename Scalar>
void
605 Scalar &x, Scalar &y, Scalar &z,
606 Scalar &roll, Scalar &pitch, Scalar &yaw)
611 roll = std::atan2 (t (2, 1), t (2, 2));
612 pitch = asin (-t (2, 0));
613 yaw = std::atan2 (t (1, 0), t (0, 0));
617 template <
typename Scalar>
void
619 Scalar roll, Scalar pitch, Scalar yaw,
620 Eigen::Transform<Scalar, 3, Eigen::Affine> &t)
622 Scalar A = std::cos (yaw),
B = sin (yaw), C = std::cos (pitch), D = sin (pitch),
623 E = std::cos (roll), F = sin (roll), DE = D*E, DF = D*F;
625 t (0, 0) = A*C; t (0, 1) = A*DF -
B*E; t (0, 2) =
B*F + A*DE; t (0, 3) = x;
626 t (1, 0) =
B*C; t (1, 1) = A*E +
B*DF; t (1, 2) =
B*DE - A*F; t (1, 3) = y;
627 t (2, 0) = -D; t (2, 1) = C*F; t (2, 2) = C*E; t (2, 3) = z;
628 t (3, 0) = 0; t (3, 1) = 0; t (3, 2) = 0; t (3, 3) = 1;
632 template <
typename Derived>
void
633 saveBinary (
const Eigen::MatrixBase<Derived>& matrix, std::ostream& file)
635 std::uint32_t rows =
static_cast<std::uint32_t
> (matrix.rows ()), cols =
static_cast<std::uint32_t
> (matrix.cols ());
636 file.write (
reinterpret_cast<char*
> (&rows),
sizeof (rows));
637 file.write (
reinterpret_cast<char*
> (&cols),
sizeof (cols));
638 for (std::uint32_t i = 0; i < rows; ++i)
639 for (std::uint32_t j = 0; j < cols; ++j)
641 typename Derived::Scalar tmp = matrix(i,j);
642 file.write (
reinterpret_cast<const char*
> (&tmp),
sizeof (tmp));
647 template <
typename Derived>
void
648 loadBinary (Eigen::MatrixBase<Derived>
const & matrix_, std::istream& file)
650 Eigen::MatrixBase<Derived> &matrix =
const_cast<Eigen::MatrixBase<Derived> &
> (matrix_);
652 std::uint32_t rows, cols;
653 file.read (
reinterpret_cast<char*
> (&rows),
sizeof (rows));
654 file.read (
reinterpret_cast<char*
> (&cols),
sizeof (cols));
655 if (matrix.rows () !=
static_cast<int>(rows) || matrix.cols () !=
static_cast<int>(cols))
656 matrix.derived().resize(rows, cols);
658 for (std::uint32_t i = 0; i < rows; ++i)
659 for (std::uint32_t j = 0; j < cols; ++j)
661 typename Derived::Scalar tmp;
662 file.read (
reinterpret_cast<char*
> (&tmp),
sizeof (tmp));
668 template <
typename Derived,
typename OtherDerived>
669 typename Eigen::internal::umeyama_transform_matrix_type<Derived, OtherDerived>::type
670 umeyama (
const Eigen::MatrixBase<Derived>& src,
const Eigen::MatrixBase<OtherDerived>& dst,
bool with_scaling)
672 #if EIGEN_VERSION_AT_LEAST (3, 3, 0)
673 return Eigen::umeyama (src, dst, with_scaling);
675 using TransformationMatrixType =
typename Eigen::internal::umeyama_transform_matrix_type<Derived, OtherDerived>::type;
676 using Scalar =
typename Eigen::internal::traits<TransformationMatrixType>::Scalar;
677 using RealScalar =
typename Eigen::NumTraits<Scalar>::Real;
678 using Index =
typename Derived::Index;
680 static_assert (!Eigen::NumTraits<Scalar>::IsComplex,
"Numeric type must be real.");
681 static_assert ((Eigen::internal::is_same<Scalar,
typename Eigen::internal::traits<OtherDerived>::Scalar>::value),
682 "You mixed different numeric types. You need to use the cast method of matrixbase to cast numeric types explicitly.");
684 enum { Dimension = PCL_EIGEN_SIZE_MIN_PREFER_DYNAMIC (Derived::RowsAtCompileTime, OtherDerived::RowsAtCompileTime) };
686 using VectorType = Eigen::Matrix<Scalar, Dimension, 1>;
687 using MatrixType = Eigen::Matrix<Scalar, Dimension, Dimension>;
688 using RowMajorMatrixType =
typename Eigen::internal::plain_matrix_type_row_major<Derived>::type;
690 const Index m = src.rows ();
691 const Index n = src.cols ();
694 const RealScalar one_over_n = 1 /
static_cast<RealScalar
> (n);
697 const VectorType src_mean = src.rowwise ().sum () * one_over_n;
698 const VectorType dst_mean = dst.rowwise ().sum () * one_over_n;
701 const RowMajorMatrixType src_demean = src.colwise () - src_mean;
702 const RowMajorMatrixType dst_demean = dst.colwise () - dst_mean;
705 const Scalar src_var = src_demean.rowwise ().squaredNorm ().sum () * one_over_n;
708 const MatrixType sigma (one_over_n * dst_demean * src_demean.transpose ());
710 Eigen::JacobiSVD<MatrixType> svd (sigma, Eigen::ComputeFullU | Eigen::ComputeFullV);
713 TransformationMatrixType Rt = TransformationMatrixType::Identity (m + 1, m + 1);
716 VectorType S = VectorType::Ones (m);
718 if ( svd.matrixU ().determinant () * svd.matrixV ().determinant () < 0 )
722 Rt.block (0,0,m,m).noalias () = svd.matrixU () * S.asDiagonal () * svd.matrixV ().transpose ();
727 const Scalar c = Scalar (1)/ src_var * svd.singularValues ().dot (S);
730 Rt.col (m).head (m) = dst_mean;
731 Rt.col (m).head (m).noalias () -= c * Rt.topLeftCorner (m, m) * src_mean;
732 Rt.block (0, 0, m, m) *= c;
736 Rt.col (m).head (m) = dst_mean;
737 Rt.col (m).head (m).noalias () -= Rt.topLeftCorner (m, m) * src_mean;
745 template <
typename Scalar>
bool
747 Eigen::Matrix<Scalar, Eigen::Dynamic, 1> &line_out,
748 const Eigen::Transform<Scalar, 3, Eigen::Affine> &transformation)
750 if (line_in.innerSize () != 6 || line_out.innerSize () != 6)
752 PCL_DEBUG (
"transformLine: lines size != 6\n");
756 Eigen::Matrix<Scalar, 3, 1> point, vector;
757 point << line_in.template head<3> ();
758 vector << line_out.template tail<3> ();
762 line_out << point, vector;
767 template <
typename Scalar>
void
769 Eigen::Matrix<Scalar, 4, 1> &plane_out,
770 const Eigen::Transform<Scalar, 3, Eigen::Affine> &transformation)
772 Eigen::Hyperplane < Scalar, 3 > plane;
773 plane.coeffs () << plane_in;
774 plane.transform (transformation);
775 plane_out << plane.coeffs ();
778 #if !EIGEN_VERSION_AT_LEAST (3, 3, 2)
779 plane_out /= plane_out.template head<3> ().norm ();
784 template <
typename Scalar>
void
787 const Eigen::Transform<Scalar, 3, Eigen::Affine> &transformation)
789 std::vector<Scalar> values (plane_in->values.begin (), plane_in->values.end ());
790 Eigen::Matrix < Scalar, 4, 1 > v_plane_in (values.data ());
792 plane_out->values.resize (4);
793 std::copy_n(v_plane_in.data (), 4, plane_out->values.begin ());
797 template <
typename Scalar>
bool
799 const Eigen::Matrix<Scalar, Eigen::Dynamic, 1> &line_y,
800 const Scalar norm_limit,
801 const Scalar dot_limit)
803 if (line_x.innerSize () != 6 || line_y.innerSize () != 6)
805 PCL_DEBUG (
"checkCoordinateSystem: lines size != 6\n");
809 if (line_x.template head<3> () != line_y.template head<3> ())
811 PCL_DEBUG (
"checkCoorZdinateSystem: vector origins are different !\n");
817 Eigen::Matrix<Scalar, 3, 1> v_line_x (line_x.template tail<3> ()),
818 v_line_y (line_y.template tail<3> ()),
819 v_line_z (v_line_x.cross (v_line_y));
822 if (v_line_x.norm () < 1 - norm_limit || v_line_x.norm () > 1 + norm_limit)
824 PCL_DEBUG (
"checkCoordinateSystem: line_x norm %d != 1\n", v_line_x.norm ());
828 if (v_line_y.norm () < 1 - norm_limit || v_line_y.norm () > 1 + norm_limit)
830 PCL_DEBUG (
"checkCoordinateSystem: line_y norm %d != 1\n", v_line_y.norm ());
834 if (v_line_z.norm () < 1 - norm_limit || v_line_z.norm () > 1 + norm_limit)
836 PCL_DEBUG (
"checkCoordinateSystem: line_z norm %d != 1\n", v_line_z.norm ());
841 if (std::abs (v_line_x.dot (v_line_y)) > dot_limit)
843 PCL_DEBUG (
"checkCSAxis: line_x dot line_y %e = > %e\n", v_line_x.dot (v_line_y), dot_limit);
847 if (std::abs (v_line_x.dot (v_line_z)) > dot_limit)
849 PCL_DEBUG (
"checkCSAxis: line_x dot line_z = %e > %e\n", v_line_x.dot (v_line_z), dot_limit);
853 if (std::abs (v_line_y.dot (v_line_z)) > dot_limit)
855 PCL_DEBUG (
"checkCSAxis: line_y dot line_z = %e > %e\n", v_line_y.dot (v_line_z), dot_limit);
863 template <
typename Scalar>
bool
865 const Eigen::Matrix<Scalar, Eigen::Dynamic, 1> from_line_y,
866 const Eigen::Matrix<Scalar, Eigen::Dynamic, 1> to_line_x,
867 const Eigen::Matrix<Scalar, Eigen::Dynamic, 1> to_line_y,
868 Eigen::Transform<Scalar, 3, Eigen::Affine> &transformation)
870 if (from_line_x.innerSize () != 6 || from_line_y.innerSize () != 6 || to_line_x.innerSize () != 6 || to_line_y.innerSize () != 6)
872 PCL_DEBUG (
"transformBetween2CoordinateSystems: lines size != 6\n");
879 PCL_DEBUG (
"transformBetween2CoordinateSystems: coordinate systems invalid !\n");
884 Eigen::Matrix<Scalar, 3, 1> fr0 (from_line_x.template head<3>()),
885 fr1 (from_line_x.template head<3>() + from_line_x.template tail<3>()),
886 fr2 (from_line_y.template head<3>() + from_line_y.template tail<3>()),
888 to0 (to_line_x.template head<3>()),
889 to1 (to_line_x.template head<3>() + to_line_x.template tail<3>()),
890 to2 (to_line_y.template head<3>() + to_line_y.template tail<3>());
894 Eigen::Transform<Scalar, 3, Eigen::Affine> T2, T3 = Eigen::Transform<Scalar, 3, Eigen::Affine>::Identity ();
895 Eigen::Matrix<Scalar, 3, 1> x1, y1, z1, x2, y2, z2;
898 x1 = (fr1 - fr0).normalized ();
899 y1 = (fr2 - fr0).normalized ();
902 x2 = (to1 - to0).normalized ();
903 y2 = (to2 - to0).normalized ();
907 T2.linear () << x1, y1, x1.cross (y1);
910 T3.linear () << x2, y2, x2.cross (y2);
914 transformation = Eigen::Transform<Scalar, 3, Eigen::Affine>::Identity ();
915 transformation.linear () = T3.linear () * T2.linear ().inverse ();
916 transformation.translation () = to0 - (transformation.linear () * fr0);
void computeCorrespondingEigenVector(const Matrix &mat, const typename Matrix::Scalar &eigenvalue, Vector &eigenvector)
determines the corresponding eigenvector to the given eigenvalue of the symmetric positive semi defin...
void getTranslationAndEulerAngles(const Eigen::Transform< Scalar, 3, Eigen::Affine > &t, Scalar &x, Scalar &y, Scalar &z, Scalar &roll, Scalar &pitch, Scalar &yaw)
Extract x,y,z and the Euler angles (intrinsic rotations, ZYX-convention) from the given transformatio...
void getTransformationFromTwoUnitVectorsAndOrigin(const Eigen::Vector3f &y_direction, const Eigen::Vector3f &z_axis, const Eigen::Vector3f &origin, Eigen::Affine3f &transformation)
Get the transformation that will translate origin to (0,0,0) and rotate z_axis into (0,...
Matrix::Scalar determinant3x3Matrix(const Matrix &matrix)
Calculate the determinant of a 3x3 matrix.
Matrix::Scalar invert3x3SymMatrix(const Matrix &matrix, Matrix &inverse)
Calculate the inverse of a 3x3 symmetric matrix.
void loadBinary(Eigen::MatrixBase< Derived > const &matrix, std::istream &file)
Read a matrix from an input stream.
void getTransformation(Scalar x, Scalar y, Scalar z, Scalar roll, Scalar pitch, Scalar yaw, Eigen::Transform< Scalar, 3, Eigen::Affine > &t)
Create a transformation from the given translation and Euler angles (intrinsic rotations,...
void getEulerAngles(const Eigen::Transform< Scalar, 3, Eigen::Affine > &t, Scalar &roll, Scalar &pitch, Scalar &yaw)
Extract the Euler angles (intrinsic rotations, ZYX-convention) from the given transformation.
void eigen22(const Matrix &mat, typename Matrix::Scalar &eigenvalue, Vector &eigenvector)
determine the smallest eigenvalue and its corresponding eigenvector
void getTransformationFromTwoUnitVectors(const Eigen::Vector3f &y_direction, const Eigen::Vector3f &z_axis, Eigen::Affine3f &transformation)
Get the unique 3D rotation that will rotate z_axis into (0,0,1) and y_direction into a vector with x=...
void getTransFromUnitVectorsXY(const Eigen::Vector3f &x_axis, const Eigen::Vector3f &y_direction, Eigen::Affine3f &transformation)
Get the unique 3D rotation that will rotate x_axis into (1,0,0) and y_direction into a vector with z=...
Matrix::Scalar invert3x3Matrix(const Matrix &matrix, Matrix &inverse)
Calculate the inverse of a general 3x3 matrix.
void eigen33(const Matrix &mat, typename Matrix::Scalar &eigenvalue, Vector &eigenvector)
determines the eigenvector and eigenvalue of the smallest eigenvalue of the symmetric positive semi d...
void saveBinary(const Eigen::MatrixBase< Derived > &matrix, std::ostream &file)
Write a matrix to an output stream.
Matrix::Scalar invert2x2(const Matrix &matrix, Matrix &inverse)
Calculate the inverse of a 2x2 matrix.
void getTransFromUnitVectorsZY(const Eigen::Vector3f &z_axis, const Eigen::Vector3f &y_direction, Eigen::Affine3f &transformation)
Get the unique 3D rotation that will rotate z_axis into (0,0,1) and y_direction into a vector with x=...
static EigenVector< Vector, typename Matrix::Scalar > getLargest3x3Eigenvector(const Matrix scaledMatrix)
returns the unit vector along the largest eigen value as well as the length of the largest eigenvecto...
float distance(const PointT &p1, const PointT &p2)
bool checkCoordinateSystem(const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &line_x, const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &line_y, const Scalar norm_limit=1e-3, const Scalar dot_limit=1e-3)
Check coordinate system integrity.
void transformPlane(const Eigen::Matrix< Scalar, 4, 1 > &plane_in, Eigen::Matrix< Scalar, 4, 1 > &plane_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transformation)
Transform plane vectors using an affine matrix.
void transformPoint(const Eigen::Matrix< Scalar, 3, 1 > &point_in, Eigen::Matrix< Scalar, 3, 1 > &point_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transformation)
Transform a point using an affine matrix.
void transformVector(const Eigen::Matrix< Scalar, 3, 1 > &vector_in, Eigen::Matrix< Scalar, 3, 1 > &vector_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transformation)
Transform a vector using an affine matrix.
Eigen::internal::umeyama_transform_matrix_type< Derived, OtherDerived >::type umeyama(const Eigen::MatrixBase< Derived > &src, const Eigen::MatrixBase< OtherDerived > &dst, bool with_scaling=false)
Returns the transformation between two point sets.
bool transformBetween2CoordinateSystems(const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > from_line_x, const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > from_line_y, const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > to_line_x, const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > to_line_y, Eigen::Transform< Scalar, 3, Eigen::Affine > &transformation)
Compute the transformation between two coordinate systems.
bool transformLine(const Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &line_in, Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > &line_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transformation)
Transform a line using an affine matrix.
void computeRoots2(const Scalar &b, const Scalar &c, Roots &roots)
Compute the roots of a quadratic polynom x^2 + b*x + c = 0.
void computeRoots(const Matrix &m, Roots &roots)
computes the roots of the characteristic polynomial of the input matrix m, which are the eigenvalues
shared_ptr< ::pcl::ModelCoefficients > Ptr
shared_ptr< const ::pcl::ModelCoefficients > ConstPtr