38 #ifndef HPP_FCL_INTERNAL_TOOLS_H
39 #define HPP_FCL_INTERNAL_TOOLS_H
52 template <
typename Derived>
53 static inline typename Derived::Scalar
triple(
54 const Eigen::MatrixBase<Derived>& x,
const Eigen::MatrixBase<Derived>& y,
55 const Eigen::MatrixBase<Derived>& z) {
56 return x.derived().dot(
y.derived().cross(z.derived()));
59 template <
typename Derived1,
typename Derived2,
typename Derived3>
61 const Eigen::MatrixBase<Derived2>& _u,
62 const Eigen::MatrixBase<Derived3>& _v) {
63 typedef typename Derived1::Scalar T;
65 Eigen::MatrixBase<Derived1>& w =
const_cast<Eigen::MatrixBase<Derived1>&
>(_w);
66 Eigen::MatrixBase<Derived2>& u =
const_cast<Eigen::MatrixBase<Derived2>&
>(_u);
67 Eigen::MatrixBase<Derived3>&
v =
const_cast<Eigen::MatrixBase<Derived3>&
>(_v);
70 if (std::abs(w[0]) >= std::abs(w[1])) {
71 inv_length = (T)1.0 / sqrt(w[0] * w[0] + w[2] * w[2]);
72 u[0] = -w[2] * inv_length;
74 u[2] = w[0] * inv_length;
76 v[1] = w[2] * u[0] - w[0] * u[2];
79 inv_length = (T)1.0 / sqrt(w[1] * w[1] + w[2] * w[2]);
81 u[1] = w[2] * inv_length;
82 u[2] = -w[1] * inv_length;
83 v[0] = w[1] * u[2] - w[2] * u[1];
90 template <
typename Derived,
typename OtherDerived>
92 const Eigen::MatrixBase<OtherDerived>& t1,
93 const Eigen::MatrixBase<Derived>& R2,
94 const Eigen::MatrixBase<OtherDerived>& t2,
95 const Eigen::MatrixBase<Derived>& R,
96 const Eigen::MatrixBase<OtherDerived>& t) {
97 const_cast<Eigen::MatrixBase<Derived>&
>(
R) = R1.transpose() * R2;
98 const_cast<Eigen::MatrixBase<OtherDerived>&
>(
t) = R1.transpose() * (t2 - t1);
103 template <
typename Derived,
typename Vector>
104 void eigen(
const Eigen::MatrixBase<Derived>& m,
105 typename Derived::Scalar dout[3], Vector* vout) {
106 typedef typename Derived::Scalar Scalar;
107 Derived
R(
m.derived());
110 Scalar tresh, theta, tau,
t, sm, s, h, g,
c;
115 Scalar
v[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}};
118 for (ip = 0; ip < n; ++ip) {
119 b[ip] = d[ip] =
R(ip, ip);
125 for (i = 0; i < 50; ++i) {
127 for (ip = 0; ip < n; ++ip)
128 for (iq = ip + 1; iq < n; ++iq) sm += std::abs(
R(ip, iq));
130 vout[0] <<
v[0][0],
v[0][1],
v[0][2];
131 vout[1] <<
v[1][0],
v[1][1],
v[1][2];
132 vout[2] <<
v[2][0],
v[2][1],
v[2][2];
140 tresh = 0.2 * sm / (n * n);
144 for (ip = 0; ip < n; ++ip) {
145 for (iq = ip + 1; iq < n; ++iq) {
146 g = 100.0 * std::abs(
R(ip, iq));
147 if (i > 3 && std::abs(d[ip]) + g == std::abs(d[ip]) &&
148 std::abs(d[iq]) + g == std::abs(d[iq]))
150 else if (std::abs(
R(ip, iq)) > tresh) {
152 if (std::abs(h) + g == std::abs(h))
155 theta = 0.5 * h / (
R(ip, iq));
156 t = 1.0 / (std::abs(theta) + std::sqrt(1.0 + theta * theta));
157 if (theta < 0.0)
t = -
t;
159 c = 1.0 / std::sqrt(1 +
t *
t);
168 for (j = 0; j < ip; ++j) {
171 R(j, ip) = g - s * (h + g * tau);
172 R(j, iq) = h + s * (g - h * tau);
174 for (j = ip + 1; j < iq; ++j) {
177 R(ip, j) = g - s * (h + g * tau);
178 R(j, iq) = h + s * (g - h * tau);
180 for (j = iq + 1; j < n; ++j) {
183 R(ip, j) = g - s * (h + g * tau);
184 R(iq, j) = h + s * (g - h * tau);
186 for (j = 0; j < n; ++j) {
189 v[j][ip] = g - s * (h + g * tau);
190 v[j][iq] = h + s * (g - h * tau);
196 for (ip = 0; ip < n; ++ip) {
203 std::cerr <<
"eigen: too many iterations in Jacobi transform." << std::endl;
208 template <
typename Derived,
typename OtherDerived>
209 bool isEqual(
const Eigen::MatrixBase<Derived>& lhs,
210 const Eigen::MatrixBase<OtherDerived>& rhs,
213 return ((lhs - rhs).array().abs() < tol).all();