hpp-fcl  3.0.0
HPP fork of FCL -- The Flexible Collision Library
tools.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2015, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #ifndef HPP_FCL_INTERNAL_TOOLS_H
39 #define HPP_FCL_INTERNAL_TOOLS_H
40 
41 #include <hpp/fcl/fwd.hh>
42 
43 #include <cmath>
44 #include <iostream>
45 #include <limits>
46 
47 #include <hpp/fcl/data_types.h>
48 
49 namespace hpp {
50 namespace fcl {
51 
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()));
57 }
58 
59 template <typename Derived1, typename Derived2, typename Derived3>
60 void generateCoordinateSystem(const Eigen::MatrixBase<Derived1>& _w,
61  const Eigen::MatrixBase<Derived2>& _u,
62  const Eigen::MatrixBase<Derived3>& _v) {
63  typedef typename Derived1::Scalar T;
64 
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);
68 
69  T inv_length;
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;
73  u[1] = (T)0;
74  u[2] = w[0] * inv_length;
75  v[0] = w[1] * u[2];
76  v[1] = w[2] * u[0] - w[0] * u[2];
77  v[2] = -w[1] * u[0];
78  } else {
79  inv_length = (T)1.0 / sqrt(w[1] * w[1] + w[2] * w[2]);
80  u[0] = (T)0;
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];
84  v[1] = -w[0] * u[2];
85  v[2] = w[0] * u[1];
86  }
87 }
88 
89 /* ----- Start Matrices ------ */
90 template <typename Derived, typename OtherDerived>
91 void relativeTransform(const Eigen::MatrixBase<Derived>& R1,
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);
99 }
100 
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());
108  int n = 3;
109  int j, iq, ip, i;
110  Scalar tresh, theta, tau, t, sm, s, h, g, c;
111 
112  Scalar b[3];
113  Scalar z[3];
114  Scalar v[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}};
115  Scalar d[3];
116 
117  for (ip = 0; ip < n; ++ip) {
118  b[ip] = d[ip] = R(ip, ip);
119  z[ip] = 0;
120  }
121 
122  for (i = 0; i < 50; ++i) {
123  sm = 0;
124  for (ip = 0; ip < n; ++ip)
125  for (iq = ip + 1; iq < n; ++iq) sm += std::abs(R(ip, iq));
126  if (sm == 0.0) {
127  vout[0] << v[0][0], v[0][1], v[0][2];
128  vout[1] << v[1][0], v[1][1], v[1][2];
129  vout[2] << v[2][0], v[2][1], v[2][2];
130  dout[0] = d[0];
131  dout[1] = d[1];
132  dout[2] = d[2];
133  return;
134  }
135 
136  if (i < 3)
137  tresh = 0.2 * sm / (n * n);
138  else
139  tresh = 0.0;
140 
141  for (ip = 0; ip < n; ++ip) {
142  for (iq = ip + 1; iq < n; ++iq) {
143  g = 100.0 * std::abs(R(ip, iq));
144  if (i > 3 && std::abs(d[ip]) + g == std::abs(d[ip]) &&
145  std::abs(d[iq]) + g == std::abs(d[iq]))
146  R(ip, iq) = 0.0;
147  else if (std::abs(R(ip, iq)) > tresh) {
148  h = d[iq] - d[ip];
149  if (std::abs(h) + g == std::abs(h))
150  t = (R(ip, iq)) / h;
151  else {
152  theta = 0.5 * h / (R(ip, iq));
153  t = 1.0 / (std::abs(theta) + std::sqrt(1.0 + theta * theta));
154  if (theta < 0.0) t = -t;
155  }
156  c = 1.0 / std::sqrt(1 + t * t);
157  s = t * c;
158  tau = s / (1.0 + c);
159  h = t * R(ip, iq);
160  z[ip] -= h;
161  z[iq] += h;
162  d[ip] -= h;
163  d[iq] += h;
164  R(ip, iq) = 0.0;
165  for (j = 0; j < ip; ++j) {
166  g = R(j, ip);
167  h = R(j, iq);
168  R(j, ip) = g - s * (h + g * tau);
169  R(j, iq) = h + s * (g - h * tau);
170  }
171  for (j = ip + 1; j < iq; ++j) {
172  g = R(ip, j);
173  h = R(j, iq);
174  R(ip, j) = g - s * (h + g * tau);
175  R(j, iq) = h + s * (g - h * tau);
176  }
177  for (j = iq + 1; j < n; ++j) {
178  g = R(ip, j);
179  h = R(iq, j);
180  R(ip, j) = g - s * (h + g * tau);
181  R(iq, j) = h + s * (g - h * tau);
182  }
183  for (j = 0; j < n; ++j) {
184  g = v[j][ip];
185  h = v[j][iq];
186  v[j][ip] = g - s * (h + g * tau);
187  v[j][iq] = h + s * (g - h * tau);
188  }
189  }
190  }
191  }
192  for (ip = 0; ip < n; ++ip) {
193  b[ip] += z[ip];
194  d[ip] = b[ip];
195  z[ip] = 0.0;
196  }
197  }
198 
199  std::cerr << "eigen: too many iterations in Jacobi transform." << std::endl;
200 
201  return;
202 }
203 
204 template <typename Derived, typename OtherDerived>
205 bool isEqual(const Eigen::MatrixBase<Derived>& lhs,
206  const Eigen::MatrixBase<OtherDerived>& rhs,
207  const FCL_REAL tol = std::numeric_limits<FCL_REAL>::epsilon() *
208  100) {
209  return ((lhs - rhs).array().abs() < tol).all();
210 }
211 
212 } // namespace fcl
213 } // namespace hpp
214 
215 #endif
void eigen(const Eigen::MatrixBase< Derived > &m, typename Derived::Scalar dout[3], Vector *vout)
compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen ve...
Definition: tools.h:104
bool isEqual(const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const FCL_REAL tol=std::numeric_limits< FCL_REAL >::epsilon() *100)
Definition: tools.h:205
void relativeTransform(const Eigen::MatrixBase< Derived > &R1, const Eigen::MatrixBase< OtherDerived > &t1, const Eigen::MatrixBase< Derived > &R2, const Eigen::MatrixBase< OtherDerived > &t2, const Eigen::MatrixBase< Derived > &R, const Eigen::MatrixBase< OtherDerived > &t)
Definition: tools.h:91
double FCL_REAL
Definition: data_types.h:66
void generateCoordinateSystem(const Eigen::MatrixBase< Derived1 > &_w, const Eigen::MatrixBase< Derived2 > &_u, const Eigen::MatrixBase< Derived3 > &_v)
Definition: tools.h:60
Main namespace.
Definition: broadphase_bruteforce.h:44