Gazebo Math

API Reference

7.5.1
gz/math/eigen3/Util.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2021 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef GZ_MATH_EIGEN3_UTIL_HH_
19 #define GZ_MATH_EIGEN3_UTIL_HH_
20 
21 #include <vector>
22 
23 #include <Eigen/Geometry>
24 #include <Eigen/Eigenvalues>
25 
27 #include <gz/math/Matrix3.hh>
28 #include <gz/math/OrientedBox.hh>
29 #include <gz/math/Pose3.hh>
30 #include <gz/math/Quaternion.hh>
31 #include <gz/math/Vector3.hh>
33 
34 namespace gz::math::eigen3
35 {
41  const std::vector<math::Vector3d> &_vertices)
42  {
43  if (_vertices.empty())
44  return Eigen::Matrix3d::Identity();
45 
46  Eigen::Matrix<double, 9, 1> cumulants;
47  cumulants.setZero();
48  for (const auto &vertex : _vertices)
49  {
50  const Eigen::Vector3d &point = math::eigen3::convert(vertex);
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);
60  }
61 
62  Eigen::Matrix3d covariance;
63 
64  cumulants /= static_cast<double>(_vertices.size());
65 
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);
75  return covariance;
76  }
77 
84  const std::vector<math::Vector3d> &_vertices)
85  {
87 
88  // Return an empty box if there are no vertices
89  if (_vertices.empty())
90  return box;
91 
93  for (const auto &point : _vertices)
94  mean += point;
95  mean /= static_cast<double>(_vertices.size());
96 
98  Eigen::Matrix3d covariance = covarianceMatrix(_vertices);
99 
100  // Eigen Vectors
101  Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d>
102  eigenSolver(covariance, Eigen::ComputeEigenvectors);
103  Eigen::Matrix3d eigenVectorsPCA = eigenSolver.eigenvectors();
104 
105  // This line is necessary for proper orientation in some cases.
106  // The numbers come out the same without it, but the signs are
107  // different and the box doesn't get correctly oriented in some cases.
108  eigenVectorsPCA.col(2) =
109  eigenVectorsPCA.col(0).cross(eigenVectorsPCA.col(1));
110 
111  // Transform the original cloud to the origin where the principal
112  // components correspond to the axes.
113  Eigen::Matrix4d projectionTransform(Eigen::Matrix4d::Identity());
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);
117 
119  Eigen::Vector3d maxPoint(-INF_I32, -INF_I32, -INF_I32);
120 
121  // Get the minimum and maximum points of the transformed cloud.
122  for (const auto &point : _vertices)
123  {
124  Eigen::Vector4d pt(0, 0, 0, 1);
125  pt.head<3>() = math::eigen3::convert(point);
126  Eigen::Vector4d tfPoint = projectionTransform * pt;
127  minPoint = minPoint.cwiseMin(tfPoint.head<3>());
128  maxPoint = maxPoint.cwiseMax(tfPoint.head<3>());
129  }
130 
131  const Eigen::Vector3d meanDiagonal = 0.5f * (maxPoint + minPoint);
132 
133  // quaternion is calculated using the eigenvectors (which determines
134  // how the final box gets rotated), and the transform to put the box
135  // in correct location is calculated
136  const Eigen::Quaterniond bboxQuaternion(eigenVectorsPCA);
137  const Eigen::Vector3d bboxTransform =
138  eigenVectorsPCA * meanDiagonal + centroid;
139 
140  math::Vector3d size(
141  maxPoint.x() - minPoint.x(),
142  maxPoint.y() - minPoint.y(),
143  maxPoint.z() - minPoint.z()
144  );
145  math::Pose3d pose;
146  pose.Rot() = math::eigen3::convert(bboxQuaternion);
147  pose.Pos() = math::eigen3::convert(bboxTransform);
148 
149  box.Size(size);
150  box.Pose(pose);
151  return box;
152  }
153 } // namespace gz::math::eigen3
154 #endif // GZ_MATH_EIGEN3_UTIL_HH_