39 #ifndef PCL_COMMON_EIGEN_IMPL_HPP_
40 #define PCL_COMMON_EIGEN_IMPL_HPP_
42 #include <pcl/pcl_macros.h>
47 const Eigen::Vector3f& y_direction,
48 Eigen::Affine3f& transformation)
50 Eigen::Vector3f tmp0 = (y_direction.cross(z_axis)).normalized();
51 Eigen::Vector3f tmp1 = (z_axis.cross(tmp0)).normalized();
52 Eigen::Vector3f tmp2 = z_axis.normalized();
54 transformation(0,0)=tmp0[0]; transformation(0,1)=tmp0[1]; transformation(0,2)=tmp0[2]; transformation(0,3)=0.0f;
55 transformation(1,0)=tmp1[0]; transformation(1,1)=tmp1[1]; transformation(1,2)=tmp1[2]; transformation(1,3)=0.0f;
56 transformation(2,0)=tmp2[0]; transformation(2,1)=tmp2[1]; transformation(2,2)=tmp2[2]; transformation(2,3)=0.0f;
57 transformation(3,0)=0.0f; transformation(3,1)=0.0f; transformation(3,2)=0.0f; transformation(3,3)=1.0f;
63 const Eigen::Vector3f& y_direction)
65 Eigen::Affine3f transformation;
67 return (transformation);
73 const Eigen::Vector3f& y_direction,
74 Eigen::Affine3f& transformation)
76 Eigen::Vector3f tmp2 = (x_axis.cross(y_direction)).normalized();
77 Eigen::Vector3f tmp1 = (tmp2.cross(x_axis)).normalized();
78 Eigen::Vector3f tmp0 = x_axis.normalized();
80 transformation(0,0)=tmp0[0]; transformation(0,1)=tmp0[1]; transformation(0,2)=tmp0[2]; transformation(0,3)=0.0f;
81 transformation(1,0)=tmp1[0]; transformation(1,1)=tmp1[1]; transformation(1,2)=tmp1[2]; transformation(1,3)=0.0f;
82 transformation(2,0)=tmp2[0]; transformation(2,1)=tmp2[1]; transformation(2,2)=tmp2[2]; transformation(2,3)=0.0f;
83 transformation(3,0)=0.0f; transformation(3,1)=0.0f; transformation(3,2)=0.0f; transformation(3,3)=1.0f;
89 const Eigen::Vector3f& y_direction)
91 Eigen::Affine3f transformation;
93 return (transformation);
99 const Eigen::Vector3f& z_axis,
100 Eigen::Affine3f& transformation)
108 const Eigen::Vector3f& z_axis)
110 Eigen::Affine3f transformation;
112 return (transformation);
117 const Eigen::Vector3f& z_axis,
118 const Eigen::Vector3f& origin,
119 Eigen::Affine3f& transformation)
122 Eigen::Vector3f translation = transformation*origin;
123 transformation(0,3)=-translation[0]; transformation(1,3)=-translation[1]; transformation(2,3)=-translation[2];
130 roll = atan2f(t(2,1), t(2,2));
131 pitch = asinf(-t(2,0));
132 yaw = atan2f(t(1,0), t(0,0));
138 float& x,
float& y,
float& z,
139 float& roll,
float& pitch,
float& yaw)
144 roll = atan2f(t(2,1), t(2,2));
145 pitch = asinf(-t(2,0));
146 yaw = atan2f(t(1,0), t(0,0));
150 template <
typename Scalar>
void
152 Scalar roll, Scalar pitch, Scalar yaw,
153 Eigen::Transform<Scalar, 3, Eigen::Affine> &t)
155 Scalar A = cos (yaw),
B = sin (yaw), C = cos (pitch), D = sin (pitch),
156 E = cos (roll), F = sin (roll), DE = D*E, DF = D*F;
158 t (0, 0) = A*C; t (0, 1) = A*DF -
B*E; t (0, 2) =
B*F + A*DE; t (0, 3) = x;
159 t (1, 0) =
B*C; t (1, 1) = A*E +
B*DF; t (1, 2) =
B*DE - A*F; t (1, 3) = y;
160 t (2, 0) = -D; t (2, 1) = C*F; t (2, 2) = C*E; t (2, 3) = z;
161 t (3, 0) = 0; t (3, 1) = 0; t (3, 2) = 0; t (3, 3) = 1;
174 template <
typename Derived>
void
177 uint32_t rows =
static_cast<uint32_t
> (matrix.rows ()), cols = static_cast<uint32_t> (matrix.cols ());
178 file.write (reinterpret_cast<char*> (&rows),
sizeof (rows));
179 file.write (reinterpret_cast<char*> (&cols),
sizeof (cols));
180 for (uint32_t i = 0; i < rows; ++i)
181 for (uint32_t j = 0; j < cols; ++j)
183 typename Derived::Scalar tmp = matrix(i,j);
184 file.write (reinterpret_cast<const char*> (&tmp),
sizeof (tmp));
189 template <
typename Derived>
void
192 Eigen::MatrixBase<Derived> &matrix =
const_cast<Eigen::MatrixBase<Derived> &
> (matrix_);
195 file.read (reinterpret_cast<char*> (&rows),
sizeof (rows));
196 file.read (reinterpret_cast<char*> (&cols),
sizeof (cols));
197 if (matrix.rows () !=
static_cast<int>(rows) || matrix.cols () !=
static_cast<int>(cols))
198 matrix.derived().resize(rows, cols);
200 for (uint32_t i = 0; i < rows; ++i)
201 for (uint32_t j = 0; j < cols; ++j)
203 typename Derived::Scalar tmp;
204 file.read (reinterpret_cast<char*> (&tmp),
sizeof (tmp));
210 template <
typename Derived,
typename OtherDerived>
211 typename Eigen::internal::umeyama_transform_matrix_type<Derived, OtherDerived>::type
212 pcl::umeyama (
const Eigen::MatrixBase<Derived>& src,
const Eigen::MatrixBase<OtherDerived>& dst,
bool with_scaling)
214 typedef typename Eigen::internal::umeyama_transform_matrix_type<Derived, OtherDerived>::type TransformationMatrixType;
215 typedef typename Eigen::internal::traits<TransformationMatrixType>::Scalar Scalar;
216 typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;
217 typedef typename Derived::Index Index;
219 EIGEN_STATIC_ASSERT (!Eigen::NumTraits<Scalar>::IsComplex, NUMERIC_TYPE_MUST_BE_REAL)
220 EIGEN_STATIC_ASSERT ((Eigen::internal::is_same<Scalar,
typename Eigen::internal::traits<OtherDerived>::Scalar>::value),
221 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
223 enum { Dimension = PCL_EIGEN_SIZE_MIN_PREFER_DYNAMIC (Derived::RowsAtCompileTime, OtherDerived::RowsAtCompileTime) };
225 typedef Eigen::Matrix<Scalar, Dimension, 1> VectorType;
226 typedef Eigen::Matrix<Scalar, Dimension, Dimension> MatrixType;
227 typedef typename Eigen::internal::plain_matrix_type_row_major<Derived>::type RowMajorMatrixType;
229 const Index m = src.rows ();
230 const Index n = src.cols ();
233 const RealScalar one_over_n = 1 /
static_cast<RealScalar
> (n);
236 const VectorType src_mean = src.rowwise ().sum () * one_over_n;
237 const VectorType dst_mean = dst.rowwise ().sum () * one_over_n;
240 const RowMajorMatrixType src_demean = src.colwise () - src_mean;
241 const RowMajorMatrixType dst_demean = dst.colwise () - dst_mean;
244 const Scalar src_var = src_demean.rowwise ().squaredNorm ().sum () * one_over_n;
247 const MatrixType sigma (one_over_n * dst_demean * src_demean.transpose ());
249 Eigen::JacobiSVD<MatrixType> svd (sigma, Eigen::ComputeFullU | Eigen::ComputeFullV);
252 TransformationMatrixType Rt = TransformationMatrixType::Identity (m + 1, m + 1);
255 VectorType S = VectorType::Ones (m);
256 if (sigma.determinant () < 0)
260 const VectorType& d = svd.singularValues ();
262 for (Index i = 0; i < m; ++i)
263 if (!Eigen::internal::isMuchSmallerThan (d.coeff (i), d.coeff (0)))
267 if (svd.matrixU ().determinant () * svd.matrixV ().determinant () > 0)
268 Rt.block (0, 0, m, m).noalias () = svd.matrixU () * svd.matrixV ().transpose ();
271 const Scalar s = S (m - 1);
273 Rt.block (0, 0, m, m).noalias () = svd.matrixU () * S.asDiagonal () * svd.matrixV ().transpose ();
279 Rt.block (0, 0, m, m).noalias () = svd.matrixU () * S.asDiagonal () * svd.matrixV ().transpose ();
286 const Scalar c = 1 / src_var * svd.singularValues ().dot (S);
289 Rt.col (m).head (m) = dst_mean;
290 Rt.col (m).head (m).noalias () -= c * Rt.topLeftCorner (m, m) * src_mean;
291 Rt.block (0, 0, m, m) *= c;
295 Rt.col (m).head (m) = dst_mean;
296 Rt.col (m).head (m).noalias () -= Rt.topLeftCorner (m, m) * src_mean;
302 #endif //PCL_COMMON_EIGEN_IMPL_HPP_
void loadBinary(Eigen::MatrixBase< Derived > const &matrix, std::istream &file)
Read a matrix from an input stream.
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=...
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 orign to (0,0,0) and rotate z_axis into (0...
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.
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=...
void saveBinary(const Eigen::MatrixBase< Derived > &matrix, std::ostream &file)
Write a matrix to an output 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 (XYZ-convention) ...
void getEulerAngles(const Eigen::Affine3f &t, float &roll, float &pitch, float &yaw)
Extract the Euler angles (XYZ-convention) from the given transformation.
void getTranslationAndEulerAngles(const Eigen::Affine3f &t, float &x, float &y, float &z, float &roll, float &pitch, float &yaw)
Extract x,y,z and the Euler angles (XYZ-convention) from the given transformation.