18 #ifndef GZ_MATH_EIGEN3_UTIL_HH_
19 #define GZ_MATH_EIGEN3_UTIL_HH_
23 #include <Eigen/Geometry>
24 #include <Eigen/Eigenvalues>
34 namespace gz::math::eigen3
43 if (_vertices.
empty())
44 return Eigen::Matrix3d::Identity();
46 Eigen::Matrix<double, 9, 1> cumulants;
48 for (
const auto &vertex : _vertices)
51 cumulants(0) += point(0);
52 cumulants(1) += point(1);
53 cumulants(2) += point(2);
54 cumulants(3) += point(0) * point(0);
55 cumulants(4) += point(0) * point(1);
56 cumulants(5) += point(0) * point(2);
57 cumulants(6) += point(1) * point(1);
58 cumulants(7) += point(1) * point(2);
59 cumulants(8) += point(2) * point(2);
64 cumulants /=
static_cast<double>(_vertices.
size());
66 covariance(0, 0) = cumulants(3) - cumulants(0) * cumulants(0);
67 covariance(1, 1) = cumulants(6) - cumulants(1) * cumulants(1);
68 covariance(2, 2) = cumulants(8) - cumulants(2) * cumulants(2);
69 covariance(0, 1) = cumulants(4) - cumulants(0) * cumulants(1);
70 covariance(1, 0) = covariance(0, 1);
71 covariance(0, 2) = cumulants(5) - cumulants(0) * cumulants(2);
72 covariance(2, 0) = covariance(0, 2);
73 covariance(1, 2) = cumulants(7) - cumulants(1) * cumulants(2);
74 covariance(2, 1) = covariance(1, 2);
89 if (_vertices.
empty())
93 for (
const auto &point : _vertices)
95 mean /=
static_cast<double>(_vertices.
size());
101 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d>
102 eigenSolver(covariance, Eigen::ComputeEigenvectors);
108 eigenVectorsPCA.col(2) =
109 eigenVectorsPCA.col(0).cross(eigenVectorsPCA.col(1));
114 projectionTransform.block<3, 3>(0, 0) = eigenVectorsPCA.transpose();
115 projectionTransform.block<3, 1>(0, 3) =
116 -1.0f * (projectionTransform.block<3, 3>(0, 0) * centroid);
122 for (
const auto &point : _vertices)
127 minPoint = minPoint.cwiseMin(tfPoint.head<3>());
128 maxPoint = maxPoint.cwiseMax(tfPoint.head<3>());
138 eigenVectorsPCA * meanDiagonal + centroid;
141 maxPoint.x() - minPoint.x(),
142 maxPoint.y() - minPoint.y(),
143 maxPoint.z() - minPoint.z()