TooN
se3.h
1 // -*- c++ -*-
2 
3 // Copyright (C) 2005,2009 Tom Drummond (twd20@cam.ac.uk)
4 
5 //All rights reserved.
6 //
7 //Redistribution and use in source and binary forms, with or without
8 //modification, are permitted provided that the following conditions
9 //are met:
10 //1. Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 //2. Redistributions in binary form must reproduce the above copyright
13 // notice, this list of conditions and the following disclaimer in the
14 // documentation and/or other materials provided with the distribution.
15 //
16 //THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND OTHER CONTRIBUTORS ``AS IS''
17 //AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 //IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 //ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR OTHER CONTRIBUTORS BE
20 //LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 //CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 //SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 //INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 //CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 //ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 //POSSIBILITY OF SUCH DAMAGE.
27 
28 #ifndef TOON_INCLUDE_SE3_H
29 #define TOON_INCLUDE_SE3_H
30 
31 #include <TooN/so3.h>
32 
33 namespace TooN {
34 
35 
47 template <typename Precision = DefaultPrecision>
48 class SE3 {
49 public:
51  inline SE3() : my_translation(Zeros) {}
52 
53  template <int S, typename P, typename A>
54  SE3(const SO3<Precision> & R, const Vector<S, P, A>& T) : my_rotation(R), my_translation(T) {}
55  template <int S, typename P, typename A>
56  SE3(const Vector<S, P, A> & v) { *this = exp(v); }
57 
58  template <class IP, int S, typename P, typename A>
59  SE3(const Operator<Internal::Identity<IP> >&, const Vector<S, P, A>& T) : my_translation(T) {}
60 
62  inline SO3<Precision>& get_rotation(){return my_rotation;}
64  inline const SO3<Precision>& get_rotation() const {return my_rotation;}
65 
67  inline Vector<3, Precision>& get_translation() {return my_translation;}
69  inline const Vector<3, Precision>& get_translation() const {return my_translation;}
70 
74  template <int S, typename P, typename A>
75  static inline SE3 exp(const Vector<S, P, A>& vect);
76 
77 
80  static inline Vector<6, Precision> ln(const SE3& se3);
82  inline Vector<6, Precision> ln() const { return SE3::ln(*this); }
83 
84  inline SE3 inverse() const {
85  const SO3<Precision> rinv = get_rotation().inverse();
86  return SE3(rinv, -(rinv*my_translation));
87  }
88 
91  template<typename P>
92  inline SE3& operator *=(const SE3<P> & rhs) {
94  get_rotation() *= rhs.get_rotation();
95  return *this;
96  }
97 
100  template<typename P>
103  }
104 
105  inline SE3& left_multiply_by(const SE3& left) {
107  get_rotation() = left.get_rotation() * get_rotation();
108  return *this;
109  }
110 
111  static inline Matrix<4,4,Precision> generator(int i){
112  Matrix<4,4,Precision> result(Zeros);
113  if(i < 3){
114  result[i][3]=1;
115  return result;
116  }
117  result[(i+1)%3][(i+2)%3] = -1;
118  result[(i+2)%3][(i+1)%3] = 1;
119  return result;
120  }
121 
123  template<typename Base>
125  {
126  Vector<4, Precision> result(Zeros);
127  if(i < 3){
128  result[i]=pos[3];
129  return result;
130  }
131  result[(i+1)%3] = - pos[(i+2)%3];
132  result[(i+2)%3] = pos[(i+1)%3];
133  return result;
134  }
135 
141  template<int S, typename P2, typename Accessor>
142  inline Vector<6, Precision> adjoint(const Vector<S,P2, Accessor>& vect)const;
143 
146  template<int S, typename P2, typename Accessor>
148 
150  template <int R, int C, typename P2, typename Accessor>
152 
154  template <int R, int C, typename P2, typename Accessor>
156 
157 private:
158  SO3<Precision> my_rotation;
159  Vector<3, Precision> my_translation;
160 };
161 
162 // transfers a vector in the Lie algebra
163 // from one coord frame to another
164 // so that exp(adjoint(vect)) = (*this) * exp(vect) * (this->inverse())
165 template<typename Precision>
166 template<int S, typename P2, typename Accessor>
168  SizeMismatch<6,S>::test(6, vect.size());
169  Vector<6, Precision> result;
170  result.template slice<3,3>() = get_rotation() * vect.template slice<3,3>();
171  result.template slice<0,3>() = get_rotation() * vect.template slice<0,3>();
172  result.template slice<0,3>() += get_translation() ^ result.template slice<3,3>();
173  return result;
174 }
175 
176 // tansfers covectors between frames
177 // (using the transpose of the inverse of the adjoint)
178 // so that trinvadjoint(vect1) * adjoint(vect2) = vect1 * vect2
179 template<typename Precision>
180 template<int S, typename P2, typename Accessor>
182  SizeMismatch<6,S>::test(6, vect.size());
183  Vector<6, Precision> result;
184  result.template slice<3,3>() = get_rotation() * vect.template slice<3,3>();
185  result.template slice<0,3>() = get_rotation() * vect.template slice<0,3>();
186  result.template slice<3,3>() += get_translation() ^ result.template slice<0,3>();
187  return result;
188 }
189 
190 template<typename Precision>
191 template<int R, int C, typename P2, typename Accessor>
193  SizeMismatch<6,R>::test(6, M.num_cols());
194  SizeMismatch<6,C>::test(6, M.num_rows());
195 
196  Matrix<6,6,Precision> result;
197  for(int i=0; i<6; i++){
198  result.T()[i] = adjoint(M.T()[i]);
199  }
200  for(int i=0; i<6; i++){
201  result[i] = adjoint(result[i]);
202  }
203  return result;
204 }
205 
206 template<typename Precision>
207 template<int R, int C, typename P2, typename Accessor>
209  SizeMismatch<6,R>::test(6, M.num_cols());
210  SizeMismatch<6,C>::test(6, M.num_rows());
211 
212  Matrix<6,6,Precision> result;
213  for(int i=0; i<6; i++){
214  result.T()[i] = trinvadjoint(M.T()[i]);
215  }
216  for(int i=0; i<6; i++){
217  result[i] = trinvadjoint(result[i]);
218  }
219  return result;
220 }
221 
224 template <typename Precision>
225 inline std::ostream& operator <<(std::ostream& os, const SE3<Precision>& rhs){
226  std::streamsize fw = os.width();
227  for(int i=0; i<3; i++){
228  os.width(fw);
229  os << rhs.get_rotation().get_matrix()[i];
230  os.width(fw);
231  os << rhs.get_translation()[i] << '\n';
232  }
233  return os;
234 }
235 
236 
239 template <typename Precision>
240 inline std::istream& operator>>(std::istream& is, SE3<Precision>& rhs){
241  for(int i=0; i<3; i++){
242  is >> rhs.get_rotation().my_matrix[i].ref() >> rhs.get_translation()[i];
243  }
244  rhs.get_rotation().coerce();
245  return is;
246 }
247 
249 // operator * //
250 // SE3 * Vector //
252 
253 namespace Internal {
254 template<int S, typename PV, typename A, typename P>
255 struct SE3VMult;
256 }
257 
258 template<int S, typename PV, typename A, typename P>
259 struct Operator<Internal::SE3VMult<S,PV,A,P> > {
260  const SE3<P> & lhs;
261  const Vector<S,PV,A> & rhs;
262 
263  Operator(const SE3<P> & l, const Vector<S,PV,A> & r ) : lhs(l), rhs(r) {}
264 
265  template <int S0, typename P0, typename A0>
266  void eval(Vector<S0, P0, A0> & res ) const {
267  SizeMismatch<4,S>::test(4, rhs.size());
268  res.template slice<0,3>()=lhs.get_rotation() * rhs.template slice<0,3>();
269  res.template slice<0,3>()+=TooN::operator*(lhs.get_translation(),rhs[3]);
270  res[3] = rhs[3];
271  }
272  int size() const { return 4; }
273 };
274 
277 template<int S, typename PV, typename A, typename P> inline
280 }
281 
284 template <typename PV, typename A, typename P> inline
286  return lhs.get_translation() + lhs.get_rotation() * rhs;
287 }
288 
290 // operator * //
291 // Vector * SE3 //
293 
294 namespace Internal {
295 template<int S, typename PV, typename A, typename P>
296 struct VSE3Mult;
297 }
298 
299 template<int S, typename PV, typename A, typename P>
300 struct Operator<Internal::VSE3Mult<S,PV,A,P> > {
301  const Vector<S,PV,A> & lhs;
302  const SE3<P> & rhs;
303 
304  Operator( const Vector<S,PV,A> & l, const SE3<P> & r ) : lhs(l), rhs(r) {}
305 
306  template <int S0, typename P0, typename A0>
307  void eval(Vector<S0, P0, A0> & res ) const {
308  SizeMismatch<4,S>::test(4, lhs.size());
309  res.template slice<0,3>()=lhs.template slice<0,3>() * rhs.get_rotation();
310  res[3] = lhs[3];
311  res[3] += lhs.template slice<0,3>() * rhs.get_translation();
312  }
313  int size() const { return 4; }
314 };
315 
318 template<int S, typename PV, typename A, typename P> inline
321 }
322 
324 // operator * //
325 // SE3 * Matrix //
327 
328 namespace Internal {
329 template <int R, int C, typename PM, typename A, typename P>
330 struct SE3MMult;
331 }
332 
333 template<int R, int Cols, typename PM, typename A, typename P>
334 struct Operator<Internal::SE3MMult<R, Cols, PM, A, P> > {
335  const SE3<P> & lhs;
336  const Matrix<R,Cols,PM,A> & rhs;
337 
338  Operator(const SE3<P> & l, const Matrix<R,Cols,PM,A> & r ) : lhs(l), rhs(r) {}
339 
340  template <int R0, int C0, typename P0, typename A0>
341  void eval(Matrix<R0, C0, P0, A0> & res ) const {
342  SizeMismatch<4,R>::test(4, rhs.num_rows());
343  for(int i=0; i<rhs.num_cols(); ++i)
344  res.T()[i] = lhs * rhs.T()[i];
345  }
346  int num_cols() const { return rhs.num_cols(); }
347  int num_rows() const { return 4; }
348 };
349 
352 template <int R, int Cols, typename PM, typename A, typename P> inline
355 }
356 
358 // operator * //
359 // Matrix * SE3 //
361 
362 namespace Internal {
363 template <int Rows, int C, typename PM, typename A, typename P>
364 struct MSE3Mult;
365 }
366 
367 template<int Rows, int C, typename PM, typename A, typename P>
368 struct Operator<Internal::MSE3Mult<Rows, C, PM, A, P> > {
369  const Matrix<Rows,C,PM,A> & lhs;
370  const SE3<P> & rhs;
371 
372  Operator( const Matrix<Rows,C,PM,A> & l, const SE3<P> & r ) : lhs(l), rhs(r) {}
373 
374  template <int R0, int C0, typename P0, typename A0>
375  void eval(Matrix<R0, C0, P0, A0> & res ) const {
376  SizeMismatch<4, C>::test(4, lhs.num_cols());
377  for(int i=0; i<lhs.num_rows(); ++i)
378  res[i] = lhs[i] * rhs;
379  }
380  int num_cols() const { return 4; }
381  int num_rows() const { return lhs.num_rows(); }
382 };
383 
386 template <int Rows, int C, typename PM, typename A, typename P> inline
389 }
390 
391 template <typename Precision>
392 template <int S, typename P, typename VA>
394  SizeMismatch<6,S>::test(6, mu.size());
395  static const Precision one_6th = 1.0/6.0;
396  static const Precision one_20th = 1.0/20.0;
397  using std::sqrt;
398 
399  SE3<Precision> result;
400 
401  const Vector<3,Precision> w = mu.template slice<3,3>();
402  const Precision theta_sq = w*w;
403  const Precision theta = sqrt(theta_sq);
404  Precision A, B;
405 
406  const Vector<3,Precision> cross = w ^ mu.template slice<0,3>();
407  if (theta_sq < 1e-8) {
408  A = 1.0 - one_6th * theta_sq;
409  B = 0.5;
410  result.get_translation() = mu.template slice<0,3>() + 0.5 * cross;
411  } else {
412  Precision C;
413  if (theta_sq < 1e-6) {
414  C = one_6th*(1.0 - one_20th * theta_sq);
415  A = 1.0 - theta_sq * C;
416  B = 0.5 - 0.25 * one_6th * theta_sq;
417  } else {
418  const Precision inv_theta = 1.0/theta;
419  A = sin(theta) * inv_theta;
420  B = (1 - cos(theta)) * (inv_theta * inv_theta);
421  C = (1 - A) * (inv_theta * inv_theta);
422  }
423  result.get_translation() = mu.template slice<0,3>() + TooN::operator*(B, cross) + TooN::operator*(C, (w ^ cross));
424  }
425  rodrigues_so3_exp(w, A, B, result.get_rotation().my_matrix);
426  return result;
427 }
428 
429 template <typename Precision>
431  using std::sqrt;
432  Vector<3,Precision> rot = se3.get_rotation().ln();
433  const Precision theta = sqrt(rot*rot);
434 
435  Precision shtot = 0.5;
436  if(theta > 0.00001) {
437  shtot = sin(theta/2)/theta;
438  }
439 
440  // now do the rotation
441  const SO3<Precision> halfrotator = SO3<Precision>::exp(rot * -0.5);
442  Vector<3, Precision> rottrans = halfrotator * se3.get_translation();
443 
444  if(theta > 0.001){
445  rottrans -= TooN::operator*(rot, ((se3.get_translation() * rot) * (1-2*shtot) / (rot*rot)));
446  } else {
447  rottrans -= TooN::operator*(rot, ((se3.get_translation() * rot)/24));
448  }
449 
450  rottrans /= (2 * shtot);
451 
452  Vector<6, Precision> result;
453  result.template slice<0,3>()=rottrans;
454  result.template slice<3,3>()=rot;
455  return result;
456 }
457 
458 template <typename Precision>
459 inline SE3<Precision> operator*(const SO3<Precision>& lhs, const SE3<Precision>& rhs){
460  return SE3<Precision>(lhs*rhs.get_rotation(),lhs*rhs.get_translation());
461 }
462 
463 #if 0 // should be moved to another header file
464 
465  template <class A> inline
466  Vector<3> transform(const SE3& pose, const FixedVector<3,A>& x) { return pose.get_rotation()*x + pose.get_translation(); }
467 
468  template <class A> inline
469  Vector<3> transform_inverse_depth(const SE3& pose, const FixedVector<3,A>& uvq)
470  {
471  const Matrix<3>& R = pose.get_rotation().get_matrix();
472  const Vector<3> DqT = R.template slice<0,0,3,2>() * uvq.template slice<0,2>() + R.T()[2] + uvq[2] * pose.get_translation();
473  const double inv_z = 1.0/ DqT[2];
474  return makeVector(DqT[0]*inv_z, DqT[1]*inv_z, uvq[2]*inv_z);
475  }
476 
477  template <class A1, class A2> inline
478  Vector<3> transform(const SE3& pose, const FixedVector<3,A1>& x, FixedMatrix<3,3,A2>& J_x)
479  {
480  J_x = pose.get_rotation().get_matrix();
481  return pose * x;
482  }
483 
484 
485  template <class A1, class A2> inline
486  Vector<3> inverse_depth_point_jacobian(const SE3& pose, const double q, const FixedVector<3,A1>& DqT, const double inv_z, FixedMatrix<3,3,A2>& J_uvq)
487  {
488  const Matrix<3>& R = pose.get_rotation().get_matrix();
489  const Vector<3>& T = pose.get_translation();
490  const double u1 = DqT[0] * inv_z;
491  J_uvq[0][0] = inv_z * (R[0][0] - u1*R[2][0]);
492  J_uvq[0][1] = inv_z * (R[0][1] - u1*R[2][1]);
493  J_uvq[0][2] = inv_z * (T[0] - u1 * T[2]);
494 
495  const double v1 = DqT[1] * inv_z;
496  J_uvq[1][0] = inv_z * (R[1][0] - v1*R[2][0]);
497  J_uvq[1][1] = inv_z * (R[1][1] - v1*R[2][1]);
498  J_uvq[1][2] = inv_z * (T[1] - v1 * T[2]);
499 
500  const double q1 = q * inv_z;
501  J_uvq[2][0] = inv_z * (-q1 * R[2][0]);
502  J_uvq[2][1] = inv_z * (-q1 * R[2][1]);
503  J_uvq[2][2] = inv_z * (1.0 - q1 * T[2]);
504 
505  return makeVector(u1, v1, q1);
506  }
507 
508 
509  template <class A1, class A2> inline
510  Vector<3> transform_inverse_depth(const SE3& pose, const FixedVector<3,A1>& uvq, FixedMatrix<3,3,A2>& J_uvq)
511  {
512  const Matrix<3>& R = pose.get_rotation().get_matrix();
513  const Vector<3>& T = pose.get_translation();
514  const double q = uvq[2];
515  const Vector<3> DqT = R.template slice<0,0,3,2>() * uvq.template slice<0,2>() + R.T()[2] + q * T;
516  const double inv_z = 1.0 / DqT[2];
517 
518  return inverse_depth_point_jacobian(pose, q, DqT, inv_z, J_uvq);
519  }
520 
521  template <class A1, class A2, class A3> inline
522  Vector<3> transform(const SE3& pose, const FixedVector<3,A1>& x, FixedMatrix<3,3,A2>& J_x, FixedMatrix<3,6,A3>& J_pose)
523  {
524  J_x = pose.get_rotation().get_matrix();
525  Identity(J_pose.template slice<0,0,3,3>());
526  const Vector<3> cx = pose * x;
527  J_pose[0][3] = J_pose[1][4] = J_pose[2][5] = 0;
528  J_pose[1][3] = -(J_pose[0][4] = cx[2]);
529  J_pose[0][5] = -(J_pose[2][3] = cx[1]);
530  J_pose[2][4] = -(J_pose[1][5] = cx[0]);
531  return cx;
532  }
533 
534  template <class A1, class A2, class A3> inline
535  Vector<3> transform_inverse_depth(const SE3& pose, const FixedVector<3,A1>& uvq, FixedMatrix<3,3,A2>& J_uvq, FixedMatrix<3,6,A3>& J_pose)
536  {
537  const Matrix<3>& R = pose.get_rotation().get_matrix();
538  const Vector<3>& T = pose.get_translation();
539  const double q = uvq[2];
540  const Vector<3> DqT = R.template slice<0,0,3,2>() * uvq.template slice<0,2>() + R.T()[2] + q * T;
541  const double inv_z = 1.0 / DqT[2];
542 
543  const Vector<3> uvq1 = inverse_depth_point_jacobian(pose, q, DqT, inv_z, J_uvq);
544  const double q1 = uvq1[2];
545 
546  J_pose[0][1] = J_pose[1][0] = J_pose[2][0] = J_pose[2][1] = 0;
547  J_pose[0][0] = J_pose[1][1] = q1;
548  J_pose[0][2] = -uvq1[0] * q1;
549  J_pose[1][2] = -uvq1[1] * q1;
550  J_pose[2][2] = -q1 * q1;
551 
552  J_pose[0][3] = -uvq1[1]*uvq1[0];
553  J_pose[0][4] = 1 + uvq1[0]*uvq1[0];
554  J_pose[0][5] = -uvq1[1];
555 
556  J_pose[1][3] = -1 - uvq1[1]*uvq1[1];
557  J_pose[1][4] = uvq1[0] * uvq1[1];
558  J_pose[1][5] = uvq1[0];
559 
560  J_pose[2][3] = -uvq1[1]*q1;
561  J_pose[2][4] = uvq1[0]*q1;
562  J_pose[2][5] = 0;
563 
564  return uvq1;
565  }
566 
567  template <class A1, class A2, class A3> inline
568  Vector<2> project_transformed_point(const SE3& pose, const FixedVector<3,A1>& in_frame, FixedMatrix<2,3,A2>& J_x, FixedMatrix<2,6,A3>& J_pose)
569  {
570  const double z_inv = 1.0/in_frame[2];
571  const double x_z_inv = in_frame[0]*z_inv;
572  const double y_z_inv = in_frame[1]*z_inv;
573  const double cross = x_z_inv * y_z_inv;
574  J_pose[0][0] = J_pose[1][1] = z_inv;
575  J_pose[0][1] = J_pose[1][0] = 0;
576  J_pose[0][2] = -x_z_inv * z_inv;
577  J_pose[1][2] = -y_z_inv * z_inv;
578  J_pose[0][3] = -cross;
579  J_pose[0][4] = 1 + x_z_inv*x_z_inv;
580  J_pose[0][5] = -y_z_inv;
581  J_pose[1][3] = -1 - y_z_inv*y_z_inv;
582  J_pose[1][4] = cross;
583  J_pose[1][5] = x_z_inv;
584 
585  const TooN::Matrix<3>& R = pose.get_rotation().get_matrix();
586  J_x[0][0] = z_inv*(R[0][0] - x_z_inv * R[2][0]);
587  J_x[0][1] = z_inv*(R[0][1] - x_z_inv * R[2][1]);
588  J_x[0][2] = z_inv*(R[0][2] - x_z_inv * R[2][2]);
589  J_x[1][0] = z_inv*(R[1][0] - y_z_inv * R[2][0]);
590  J_x[1][1] = z_inv*(R[1][1] - y_z_inv * R[2][1]);
591  J_x[1][2] = z_inv*(R[1][2] - y_z_inv * R[2][2]);
592 
593  return makeVector(x_z_inv, y_z_inv);
594  }
595 
596 
597  template <class A1> inline
598  Vector<2> transform_and_project(const SE3& pose, const FixedVector<3,A1>& x)
599  {
600  return project(transform(pose,x));
601  }
602 
603  template <class A1> inline
604  Vector<2> transform_and_project_inverse_depth(const SE3& pose, const FixedVector<3,A1>& uvq)
605  {
606  const Matrix<3>& R = pose.get_rotation().get_matrix();
607  const Vector<3>& T = pose.get_translation();
608  const Vector<3> DqT = R.template slice<0,0,3,2>() * uvq.template slice<0,2>() + R.T()[2] + uvq[2] * T;
609  return project(DqT);
610  }
611 
612  template <class A1, class A2, class A3> inline
613  Vector<2> transform_and_project(const SE3& pose, const FixedVector<3,A1>& x, FixedMatrix<2,3,A2>& J_x, FixedMatrix<2,6,A3>& J_pose)
614  {
615  return project_transformed_point(pose, transform(pose,x), J_x, J_pose);
616  }
617 
618  template <class A1, class A2, class A3> inline
619  Vector<2> transform_and_project_inverse_depth(const SE3& pose, const FixedVector<3,A1>& uvq, FixedMatrix<2,3,A2>& J_uvq, FixedMatrix<2,6,A3>& J_pose)
620  {
621  const Matrix<3>& R = pose.get_rotation().get_matrix();
622  const Vector<3>& T = pose.get_translation();
623  const double q = uvq[2];
624  const Vector<3> DqT = R.template slice<0,0,3,2>() * uvq.template slice<0,2>() + R.T()[2] + q * T;
625  const Vector<2> uv = project_transformed_point(pose, DqT, J_uvq, J_pose);
626  J_uvq.T()[2] = J_pose.template slice<0,0,2,3>() * pose.get_translation();
627  J_pose.template slice<0,0,2,3>() *= q;
628  return uv;
629  }
630 
631 #endif
632 
633 }
634 
635 #endif
Represent a three-dimensional Euclidean transformation (a rotation and a translation).
Definition: se3.h:48
Vector<(Size==Dynamic?Dynamic:Size-1)+0, Precision > project(const Vector< Size, Precision, Base > &v)
For a vector v of length i, return .
Definition: helpers.h:182
Vector< 3, typename Internal::MultiplyType< P, PV >::type > operator*(const SE3< P > &lhs, const Vector< 3, PV, A > &rhs)
Right-multiply by a Vector.
Definition: se3.h:285
static SO3 exp(const Vector< S, VP, A > &vect)
Exponentiate a vector in the Lie algebra to generate a new SO3.
Pretty generic SFINAE introspection generator.
Definition: vec_test.cc:21
static Vector< 4, Precision > generator_field(int i, const Vector< 4, Precision, Base > &pos)
Returns the i-th generator times pos.
Definition: se3.h:124
std::istream & operator>>(std::istream &is, SE3< Precision > &rhs)
Reads an SE3 from a stream.
Definition: se3.h:240
SE3 & operator*=(const SE3< P > &rhs)
Right-multiply by another SE3 (concatenate the two transformations)
Definition: se3.h:92
Definition: se3.h:330
Vector< 4, typename Internal::MultiplyType< P, PV >::type > operator*(const Vector< S, PV, A > &lhs, const SE3< P > &rhs)
Left-multiply by a Vector.
Definition: se3.h:319
A matrix.
Definition: matrix.hh:105
Vector< 4, typename Internal::MultiplyType< P, PV >::type > operator*(const SE3< P > &lhs, const Vector< S, PV, A > &rhs)
Right-multiply by a Vector.
Definition: se3.h:278
Vector< 6, Precision > ln() const
Definition: se3.h:82
const SO3< Precision > & get_rotation() const
Definition: se3.h:64
Matrix< 4, Cols, typename Internal::MultiplyType< P, PM >::type > operator*(const SE3< P > &lhs, const Matrix< R, Cols, PM, A > &rhs)
Right-multiply by a Matrix.
Definition: se3.h:353
Definition: operators.hh:119
Vector< 6, Precision > trinvadjoint(const Vector< S, P2, Accessor > &vect) const
Transfer covectors between frames (using the transpose of the inverse of the adjoint) so that trinvad...
Definition: se3.h:181
Vector< 6, Precision > adjoint(const Vector< S, P2, Accessor > &vect) const
Transfer a matrix in the Lie Algebra from one co-ordinate frame to another.
Definition: se3.h:167
Definition: se3.h:296
Class to represent a three-dimensional rotation matrix.
Definition: so3.h:37
const Vector< 3, Precision > & get_translation() const
Definition: se3.h:69
Definition: objects.h:36
Definition: se3.h:255
Definition: se3.h:364
SE3< typename Internal::MultiplyType< Precision, P >::type > operator*(const SE3< P > &rhs) const
Right-multiply by another SE3 (concatenate the two transformations)
Definition: se3.h:101
SE3()
Default constructor. Initialises the the rotation to zero (the identity) and the translation to zero...
Definition: se3.h:51
Matrix< R, C, P > sqrt(const Matrix< R, C, P, B > &m)
computes a matrix square root of a matrix m by the product form of the Denman and Beavers iteration a...
Definition: helpers.h:350
Definition: size_mismatch.hh:103
Vector< 3, Precision > & get_translation()
Returns the translation part of the transformation as a Vector.
Definition: se3.h:67
static SE3 exp(const Vector< S, P, A > &vect)
Exponentiate a Vector in the Lie Algebra to generate a new SE3.
SO3< Precision > & get_rotation()
Returns the rotation part of the transformation as a SO3.
Definition: se3.h:62
Matrix< Rows, 4, typename Internal::MultiplyType< PM, P >::type > operator*(const Matrix< Rows, C, PM, A > &lhs, const SE3< P > &rhs)
Left-multiply by a Matrix.
Definition: se3.h:387