SLAMflex SE  0.1.0
SLAMflex provides detection and tracking of dominant planes for smartphone devices. This plane can then be used to show AR content relative to the plane orientation. The detection of plane is performed in the field of view of the smartphone camera. In subsequent frames it is tracked. The interface returns the plane position and orientation.
so3.h
Go to the documentation of this file.
1 // -*- c++ -*-
2 
3 // Copyright (C) 2005,2009 Tom Drummond (twd20@cam.ac.uk)
4 //
5 // This file is part of the TooN Library. This library is free
6 // software; you can redistribute it and/or modify it under the
7 // terms of the GNU General Public License as published by the
8 // Free Software Foundation; either version 2, or (at your option)
9 // any later version.
10 
11 // This library is distributed in the hope that it will be useful,
12 // but WITHOUT ANY WARRANTY; without even the implied warranty of
13 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 // GNU General Public License for more details.
15 
16 // You should have received a copy of the GNU General Public License along
17 // with this library; see the file COPYING. If not, write to the Free
18 // Software Foundation, 59 Temple Place - Suite 330, Boston, MA 02111-1307,
19 // USA.
20 
21 // As a special exception, you may use this file as part of a free software
22 // library without restriction. Specifically, if other files instantiate
23 // templates or use macros or inline functions from this file, or you compile
24 // this file and link it with other files to produce an executable, this
25 // file does not by itself cause the resulting executable to be covered by
26 // the GNU General Public License. This exception does not however
27 // invalidate any other reasons why the executable file might be covered by
28 // the GNU General Public License.
29 
30 #ifndef TOON_INCLUDE_SO3_H
31 #define TOON_INCLUDE_SO3_H
32 
33 #include "TooN.h"
34 #include "helpers.h"
35 #include <cassert>
36 
37 namespace TooN {
38 
39 template <typename Precision> class SO3;
40 template <typename Precision> class SE3;
41 
42 template<class Precision> inline std::istream & operator>>(std::istream &, SO3<Precision> & );
43 template<class Precision> inline std::istream & operator>>(std::istream &, SE3<Precision> & );
44 
52 template <typename Precision = double>
53 class SO3 {
54 public:
55  friend std::istream& operator>> <Precision> (std::istream& is, SO3<Precision> & rhs);
56  friend std::istream& operator>> <Precision> (std::istream& is, SE3<Precision> & rhs);
57  friend class SE3<Precision>;
58 
61 
63  template <int S, typename P, typename A>
64  SO3(const Vector<S, P, A> & v) { *this = exp(v); }
65 
67  template <int R, int C, typename P, typename A>
68  SO3(const Matrix<R,C,P,A>& rhs) { *this = rhs; }
69 
75  template <int S1, int S2, typename P1, typename P2, typename A1, typename A2>
76  SO3(const Vector<S1, P1, A1> & a, const Vector<S2, P2, A2> & b ){
77  SizeMismatch<3,S1>::test(3, a.size());
78  SizeMismatch<3,S2>::test(3, b.size());
79  Vector<3, Precision> n = a ^ b;
80  if(norm_sq(n) == 0) {
81  //check that the vectors are in the same direction if cross product is 0. If not,
82  //this means that the rotation is 180 degrees, which leads to an ambiguity in the rotation axis.
83  assert(a*b>=0);
85  return;
86  }
87  n = unit(n);
88  Matrix<3> R1;
89  R1.T()[0] = unit(a);
90  R1.T()[1] = n;
91  R1.T()[2] = n ^ R1.T()[0];
92  my_matrix.T()[0] = unit(b);
93  my_matrix.T()[1] = n;
94  my_matrix.T()[2] = n ^ my_matrix.T()[0];
95  my_matrix = my_matrix * R1.T();
96  }
97 
100  template <int R, int C, typename P, typename A>
101  SO3& operator=(const Matrix<R,C,P,A> & rhs) {
102  my_matrix = rhs;
103  coerce();
104  return *this;
105  }
106 
108  void coerce() {
109  my_matrix[0] = unit(my_matrix[0]);
110  my_matrix[1] -= my_matrix[0] * (my_matrix[0]*my_matrix[1]);
111  my_matrix[1] = unit(my_matrix[1]);
112  my_matrix[2] -= my_matrix[0] * (my_matrix[0]*my_matrix[2]);
113  my_matrix[2] -= my_matrix[1] * (my_matrix[1]*my_matrix[2]);
114  my_matrix[2] = unit(my_matrix[2]);
115  // check for positive determinant <=> right handed coordinate system of row vectors
116  assert( (my_matrix[0] ^ my_matrix[1]) * my_matrix[2] > 0 );
117  }
118 
121  template<int S, typename VP, typename A> inline static SO3 exp(const Vector<S,VP,A>& vect);
122 
125  inline Vector<3, Precision> ln() const;
126 
128  SO3 inverse() const { return SO3(*this, Invert()); }
129 
131  SO3& operator *=(const SO3& rhs) {
132  *this = *this * rhs;
133  return *this;
134  }
135 
137  template<typename P>
140  }
141 
143  const Matrix<3,3, Precision> & get_matrix() const {return my_matrix;}
144 
149  inline static Matrix<3,3, Precision> generator(int i){
151  result[(i+1)%3][(i+2)%3] = -1;
152  result[(i+2)%3][(i+1)%3] = 1;
153  return result;
154  }
155 
157  template<typename Base>
159  {
160  Vector<3, Precision> result;
161  result[i]=0;
162  result[(i+1)%3] = - pos[(i+2)%3];
163  result[(i+2)%3] = pos[(i+1)%3];
164  return result;
165  }
166 
171  template <int S, typename A>
173  {
174  SizeMismatch<3, S>::test(3, vect.size());
175  return *this * vect;
176  }
177 
178  template <typename PA, typename PB>
179  inline SO3(const SO3<PA>& a, const SO3<PB>& b) : my_matrix(a.get_matrix()*b.get_matrix()) {}
180 
181 private:
182  struct Invert {};
183  inline SO3(const SO3& so3, const Invert&) : my_matrix(so3.my_matrix.T()) {}
184 
186 };
187 
190 template <typename Precision>
191 inline std::ostream& operator<< (std::ostream& os, const SO3<Precision>& rhs){
192  return os << rhs.get_matrix();
193 }
194 
197 template <typename Precision>
198 inline std::istream& operator>>(std::istream& is, SO3<Precision>& rhs){
199  return is >> rhs.my_matrix;
200  rhs.coerce();
201 }
202 
214 template <typename Precision, int S, typename VP, typename VA, typename MA>
215 inline void rodrigues_so3_exp(const Vector<S,VP, VA>& w, const Precision A, const Precision B, Matrix<3,3,Precision,MA>& R){
216  SizeMismatch<3,S>::test(3, w.size());
217  {
218  const Precision wx2 = (Precision)w[0]*w[0];
219  const Precision wy2 = (Precision)w[1]*w[1];
220  const Precision wz2 = (Precision)w[2]*w[2];
221 
222  R[0][0] = 1.0 - B*(wy2 + wz2);
223  R[1][1] = 1.0 - B*(wx2 + wz2);
224  R[2][2] = 1.0 - B*(wx2 + wy2);
225  }
226  {
227  const Precision a = A*w[2];
228  const Precision b = B*(w[0]*w[1]);
229  R[0][1] = b - a;
230  R[1][0] = b + a;
231  }
232  {
233  const Precision a = A*w[1];
234  const Precision b = B*(w[0]*w[2]);
235  R[0][2] = b + a;
236  R[2][0] = b - a;
237  }
238  {
239  const Precision a = A*w[0];
240  const Precision b = B*(w[1]*w[2]);
241  R[1][2] = b - a;
242  R[2][1] = b + a;
243  }
244 }
245 
248 template <typename Precision>
249 template<int S, typename VP, typename VA>
251  using std::sqrt;
252  using std::sin;
253  using std::cos;
254  SizeMismatch<3,S>::test(3, w.size());
255 
256  static const Precision one_6th = 1.0/6.0;
257  static const Precision one_20th = 1.0/20.0;
258 
259  SO3<Precision> result;
260 
261  const Precision theta_sq = w*w;
262  const Precision theta = sqrt(theta_sq);
263  Precision A, B;
264  //Use a Taylor series expansion near zero. This is required for
265  //accuracy, since sin t / t and (1-cos t)/t^2 are both 0/0.
266  if (theta_sq < 1e-8) {
267  A = 1.0 - one_6th * theta_sq;
268  B = 0.5;
269  } else {
270  if (theta_sq < 1e-6) {
271  B = 0.5 - 0.25 * one_6th * theta_sq;
272  A = 1.0 - theta_sq * one_6th*(1.0 - one_20th * theta_sq);
273  } else {
274  const Precision inv_theta = 1.0/theta;
275  A = sin(theta) * inv_theta;
276  B = (1 - cos(theta)) * (inv_theta * inv_theta);
277  }
278  }
279  rodrigues_so3_exp(w, A, B, result.my_matrix);
280  return result;
281 }
282 
283 template <typename Precision>
285  Vector<3, Precision> result;
286 
287  const Precision cos_angle = (my_matrix[0][0] + my_matrix[1][1] + my_matrix[2][2] - 1.0) * 0.5;
288  result[0] = (my_matrix[2][1]-my_matrix[1][2])/2;
289  result[1] = (my_matrix[0][2]-my_matrix[2][0])/2;
290  result[2] = (my_matrix[1][0]-my_matrix[0][1])/2;
291 
292  Precision sin_angle_abs = sqrt(result*result);
293  if (cos_angle > M_SQRT1_2) { // [0 - Pi/4[ use asin
294  if(sin_angle_abs > 0){
295  result *= asin(sin_angle_abs) / sin_angle_abs;
296  }
297  } else if( cos_angle > -M_SQRT1_2) { // [Pi/4 - 3Pi/4[ use acos, but antisymmetric part
298  const Precision angle = acos(cos_angle);
299  result *= angle / sin_angle_abs;
300  } else { // rest use symmetric part
301  // antisymmetric part vanishes, but still large rotation, need information from symmetric part
302  const Precision angle = M_PI - asin(sin_angle_abs);
303  const Precision d0 = my_matrix[0][0] - cos_angle,
304  d1 = my_matrix[1][1] - cos_angle,
305  d2 = my_matrix[2][2] - cos_angle;
307  if(d0*d0 > d1*d1 && d0*d0 > d2*d2){ // first is largest, fill with first column
308  r2[0] = d0;
309  r2[1] = (my_matrix[1][0]+my_matrix[0][1])/2;
310  r2[2] = (my_matrix[0][2]+my_matrix[2][0])/2;
311  } else if(d1*d1 > d2*d2) { // second is largest, fill with second column
312  r2[0] = (my_matrix[1][0]+my_matrix[0][1])/2;
313  r2[1] = d1;
314  r2[2] = (my_matrix[2][1]+my_matrix[1][2])/2;
315  } else { // third is largest, fill with third column
316  r2[0] = (my_matrix[0][2]+my_matrix[2][0])/2;
317  r2[1] = (my_matrix[2][1]+my_matrix[1][2])/2;
318  r2[2] = d2;
319  }
320  // flip, if we point in the wrong direction!
321  if(r2 * result < 0)
322  r2 *= -1;
323  r2 = unit(r2);
324  result = TooN::operator*(angle,r2);
325  }
326  return result;
327 }
328 
331 template<int S, typename P, typename PV, typename A> inline
333  return lhs.get_matrix() * rhs;
334 }
335 
338 template<int S, typename P, typename PV, typename A> inline
340  return lhs * rhs.get_matrix();
341 }
342 
345 template<int R, int C, typename P, typename PM, typename A> inline
347  return lhs.get_matrix() * rhs;
348 }
349 
352 template<int R, int C, typename P, typename PM, typename A> inline
354  return lhs * rhs.get_matrix();
355 }
356 
357 #if 0 // will be moved to another header file ?
358 
359 template <class A> inline
360 Vector<3> transform(const SO3& pose, const FixedVector<3,A>& x) { return pose*x; }
361 
362 template <class A1, class A2> inline
363 Vector<3> transform(const SO3& pose, const FixedVector<3,A1>& x, FixedMatrix<3,3,A2>& J_x)
364 {
365  J_x = pose.get_matrix();
366  return pose * x;
367 }
368 
369 template <class A1, class A2, class A3> inline
370 Vector<3> transform(const SO3& pose, const FixedVector<3,A1>& x, FixedMatrix<3,3,A2>& J_x, FixedMatrix<3,3,A3>& J_pose)
371 {
372  J_x = pose.get_matrix();
373  const Vector<3> cx = pose * x;
374  J_pose[0][0] = J_pose[1][1] = J_pose[2][2] = 0;
375  J_pose[1][0] = -(J_pose[0][1] = cx[2]);
376  J_pose[0][2] = -(J_pose[2][0] = cx[1]);
377  J_pose[2][1] = -(J_pose[1][2] = cx[0]);
378  return cx;
379 }
380 
381 template <class A1, class A2, class A3> inline
382 Vector<2> project_transformed_point(const SO3& pose, const FixedVector<3,A1>& in_frame, FixedMatrix<2,3,A2>& J_x, FixedMatrix<2,3,A3>& J_pose)
383 {
384  const double z_inv = 1.0/in_frame[2];
385  const double x_z_inv = in_frame[0]*z_inv;
386  const double y_z_inv = in_frame[1]*z_inv;
387  const double cross = x_z_inv * y_z_inv;
388  J_pose[0][0] = -cross;
389  J_pose[0][1] = 1 + x_z_inv*x_z_inv;
390  J_pose[0][2] = -y_z_inv;
391  J_pose[1][0] = -1 - y_z_inv*y_z_inv;
392  J_pose[1][1] = cross;
393  J_pose[1][2] = x_z_inv;
394 
395  const TooN::Matrix<3>& R = pose.get_matrix();
396  J_x[0][0] = z_inv*(R[0][0] - x_z_inv * R[2][0]);
397  J_x[0][1] = z_inv*(R[0][1] - x_z_inv * R[2][1]);
398  J_x[0][2] = z_inv*(R[0][2] - x_z_inv * R[2][2]);
399  J_x[1][0] = z_inv*(R[1][0] - y_z_inv * R[2][0]);
400  J_x[1][1] = z_inv*(R[1][1] - y_z_inv * R[2][1]);
401  J_x[1][2] = z_inv*(R[1][2] - y_z_inv * R[2][2]);
402 
403  return makeVector(x_z_inv, y_z_inv);
404 }
405 
406 
407 template <class A1> inline
408 Vector<2> transform_and_project(const SO3& pose, const FixedVector<3,A1>& x)
409 {
410  return project(transform(pose,x));
411 }
412 
413 template <class A1, class A2, class A3> inline
414 Vector<2> transform_and_project(const SO3& pose, const FixedVector<3,A1>& x, FixedMatrix<2,3,A2>& J_x, FixedMatrix<2,3,A3>& J_pose)
415 {
416  return project_transformed_point(pose, transform(pose,x), J_x, J_pose);
417 }
418 
419 #endif
420 
421 }
422 
423 #endif
SO3 inverse() const
Returns the inverse of this matrix (=the transpose, so this is a fast operation)
Definition: so3.h:128
static SO3 exp(const Vector< S, VP, A > &vect)
Definition: so3.h:39
static Operator< Internal::Identity< Internal::One > > Identity
Definition: objects.h:748
Everything lives inside this namespace.
Definition: allocator.hh:48
SO3 & operator*=(const SO3 &rhs)
Right-multiply by another rotation matrix.
Definition: so3.h:131
static void test(int s1, int s2)
Vector< 3, typename Internal::MultiplyType< P, PV >::type > operator*(const SO3< P > &lhs, const Vector< S, PV, A > &rhs)
Definition: so3.h:332
SO3()
Default constructor. Initialises the matrix to the identity (no rotation)
Definition: so3.h:60
Vector< 3, Precision > ln() const
Definition: so3.h:284
Matrix< R, 3, typename Internal::MultiplyType< PM, P >::type > operator*(const Matrix< R, C, PM, A > &lhs, const SO3< P > &rhs)
Definition: so3.h:353
SO3(const Vector< S1, P1, A1 > &a, const Vector< S2, P2, A2 > &b)
Definition: so3.h:76
SO3 & operator=(const Matrix< R, C, P, A > &rhs)
Definition: so3.h:101
Vector< 3, Precision > adjoint(const Vector< S, Precision, A > &vect) const
Definition: so3.h:172
Definition: se3.h:50
int transform(const BasicImage< S > &in, BasicImage< T > &out, const TooN::Matrix< 2 > &M, const TooN::Vector< 2 > &inOrig, const TooN::Vector< 2 > &outOrig, const T defaultValue=T())
Definition: vision.h:304
SO3(const SO3 &so3, const Invert &)
Definition: so3.h:183
void coerce()
Modifies the matrix to make sure it is a valid rotation matrix.
Definition: so3.h:108
Vector< 1 > makeVector(double x1)
Definition: make_vector.hh:4
Precision norm_sq(const Vector< Size, Precision, Base > &v)
Definition: helpers.h:79
std::istream & operator>>(std::istream &is, SO3< Precision > &rhs)
Definition: so3.h:198
void rodrigues_so3_exp(const Vector< S, VP, VA > &w, const Precision A, const Precision B, Matrix< 3, 3, Precision, MA > &R)
Definition: so3.h:215
Vector< 3, typename Internal::MultiplyType< PV, P >::type > operator*(const Vector< S, PV, A > &lhs, const SO3< P > &rhs)
Definition: so3.h:339
Vector< Size, Precision > unit(const Vector< Size, Precision, Base > &v)
Definition: helpers.h:126
SO3(const SO3< PA > &a, const SO3< PB > &b)
Definition: so3.h:179
SO3(const Matrix< R, C, P, A > &rhs)
Construct from a rotation matrix.
Definition: so3.h:68
std::istream & operator>>(std::istream &is, Vector< Size, Precision, Base > &v)
Definition: operators.hh:657
static Matrix< 3, 3, Precision > generator(int i)
Definition: so3.h:149
SO3< typename Internal::MultiplyType< Precision, P >::type > operator*(const SO3< P > &rhs) const
Right-multiply by another rotation matrix.
Definition: so3.h:138
Matrix< 3, C, typename Internal::MultiplyType< P, PM >::type > operator*(const SO3< P > &lhs, const Matrix< R, C, PM, A > &rhs)
Definition: so3.h:346
static Vector< 3, Precision > generator_field(int i, const Vector< 3, Precision, Base > &pos)
Returns the i-th generator times pos.
Definition: so3.h:158
Vector< Internal::Sizer< S1, S2 >::size, typename Internal::MultiplyType< P1, P2 >::type > operator*(const DiagonalMatrix< S1, P1, B1 > &d, const Vector< S2, P2, B2 > &v)
Definition: diagmatrix.h:111
Matrix< 3, 3, Precision > my_matrix
Definition: so3.h:185
const Matrix< 3, 3, Precision > & get_matrix() const
Returns the SO3 as a Matrix<3>
Definition: so3.h:143
static Operator< Internal::Zero > Zeros
Definition: objects.h:727
Vector<(Size==Dynamic?Dynamic:Size-1), Precision > project(const Vector< Size, Precision, Base > &v)
Definition: helpers.h:157
SO3(const Vector< S, P, A > &v)
Construct from the axis of rotation (and angle given by the magnitude).
Definition: so3.h:64