28 #ifndef TOON_INCLUDE_SIM3_H 29 #define TOON_INCLUDE_SIM3_H 47 template <
typename Precision = DefaultPrecision>
51 inline SIM3() : my_scale(1) {}
53 template <
int S,
typename P,
typename A>
55 template <
int S,
typename P,
typename A>
71 inline const Precision &
get_scale()
const {
return my_scale; }
76 template <
int S,
typename P,
typename A>
85 inline SIM3 inverse()
const {
87 const Precision inv_scale = 1/my_scale;
112 inline SIM3& left_multiply_by(
const SIM3& left) {
126 result[(i+1)%3][(i+2)%3] = -1;
127 result[(i+2)%3][(i+1)%3] = 1;
137 template<
typename Base>
146 result[(i+1)%3] = - pos[(i+2)%3];
147 result[(i+2)%3] = pos[(i+1)%3];
150 result.template slice<0,3>() = pos.template slice<0,3>();
159 template<
int S,
typename P2,
typename Accessor>
164 template<
int S,
typename P2,
typename Accessor>
168 template <
int R,
int C,
typename P2,
typename Accessor>
172 template <
int R,
int C,
typename P2,
typename Accessor>
192 template<
typename Precision>
193 template<
int S,
typename P2,
typename Accessor>
197 result.template slice<3,3>() =
get_rotation() * vect.template slice<3,3>();
198 result.template slice<0,3>() =
get_rotation() * vect.template slice<0,3>();
199 result.template slice<0,3>() +=
get_translation() ^ result.template slice<3,3>();
206 template<
typename Precision>
207 template<
int S,
typename P2,
typename Accessor>
211 result.template slice<3,3>() =
get_rotation() * vect.template slice<3,3>();
212 result.template slice<0,3>() =
get_rotation() * vect.template slice<0,3>();
213 result.template slice<3,3>() +=
get_translation() ^ result.template slice<0,3>();
217 template<
typename Precision>
218 template<
int R,
int C,
typename P2,
typename Accessor>
224 for(
int i=0; i<7; i++){
225 result.T()[i] =
adjoint(M.T()[i]);
227 for(
int i=0; i<7; i++){
228 result[i] =
adjoint(result[i]);
233 template<
typename Precision>
234 template<
int R,
int C,
typename P2,
typename Accessor>
240 for(
int i=0; i<7; i++){
243 for(
int i=0; i<7; i++){
251 template <
typename Precision>
252 inline std::ostream& operator <<(std::ostream& os, const SIM3<Precision>& rhs){
253 std::streamsize fw = os.width();
254 for(
int i=0; i<3; i++){
256 os << rhs.get_rotation().get_matrix()[i] * rhs.get_scale();
258 os << rhs.get_translation()[i] <<
'\n';
266 template <
typename Precision>
268 for(
int i=0; i<3; i++){
282 template<
int S,
typename PV,
typename A,
typename P>
286 template<
int S,
typename PV,
typename A,
typename P>
293 template <
int S0,
typename P0,
typename A0>
296 res.template slice<0,3>()=lhs.get_rotation() * (lhs.get_scale() * rhs.template slice<0,3>());
297 res.template slice<0,3>()+=TooN::operator*(lhs.get_translation(),rhs[3]);
300 int size()
const {
return 4; }
305 template<
int S,
typename PV,
typename A,
typename P>
inline 312 template <
typename PV,
typename A,
typename P>
inline 323 template<
int S,
typename PV,
typename A,
typename P>
327 template<
int S,
typename PV,
typename A,
typename P>
334 template <
int S0,
typename P0,
typename A0>
341 int size()
const {
return 4; }
346 template<
int S,
typename PV,
typename A,
typename P>
inline 357 template <
int R,
int C,
typename PM,
typename A,
typename P>
361 template<
int R,
int Cols,
typename PM,
typename A,
typename P>
362 struct Operator<Internal::SIM3MMult<R, Cols, PM, A, P> > {
368 template <
int R0,
int C0,
typename P0,
typename A0>
371 for(
int i=0; i<rhs.num_cols(); ++i)
372 res.T()[i] = lhs * rhs.T()[i];
374 int num_cols()
const {
return rhs.num_cols(); }
375 int num_rows()
const {
return 4; }
380 template <
int R,
int Cols,
typename PM,
typename A,
typename P>
inline 391 template <
int Rows,
int C,
typename PM,
typename A,
typename P>
395 template<
int Rows,
int C,
typename PM,
typename A,
typename P>
396 struct Operator<Internal::MSIM3Mult<Rows, C, PM, A, P> > {
402 template <
int R0,
int C0,
typename P0,
typename A0>
405 for(
int i=0; i<lhs.num_rows(); ++i)
406 res[i] = lhs[i] * rhs;
408 int num_cols()
const {
return 4; }
409 int num_rows()
const {
return lhs.num_rows(); }
414 template <
int Rows,
int C,
typename PM,
typename A,
typename P>
inline 422 template <
typename Precision>
423 inline Vector<3, Precision> compute_rodrigues_coefficients_sim3(
const Precision & s,
const Precision & t ){
427 const Precision es =
exp(s);
432 static const Precision eps = 1e-6;
434 if(fabs(s) < eps && fabs(t) < eps){
435 coeff[0] = 1 + s/2 + s*s/6;
436 coeff[1] = 1/2 + s/3 - t*t/24 + s*s/8;
437 coeff[2] = 1/6 + s/8 - t*t/120 + s*s/20;
438 }
else if(fabs(s) < eps) {
439 coeff[0] = 1 + s/2 + s*s/6;
440 coeff[1] = (1-cos(t))/(t*t) + (sin(t)-cos(t)*t)*s/(t*t*t)+(2*sin(t)*t-t*t*cos(t)-2+2*cos(t))*s*s/(2*t*t*t*t);
441 coeff[2] = (t-sin(t))/(t*t*t) - (-t*t-2+2*cos(t)+2*sin(t)*t)*s/(2*t*t*t*t) - (-t*t*t+6*cos(t)*t+3*sin(t)*t*t-6*sin(t))*s*s/(6*t*t*t*t*t);
442 }
else if(fabs(t) < eps) {
443 coeff[0] = (es - 1)/s;
444 coeff[1] = (s*es+1-es)/(s*s) - (6*s*es+6-6*es+es*s*s*s-3*es*s*s)*t*t/(6*s*s*s*s);
445 coeff[2] = (es*s*s-2*s*es+2*es-2)/(2*s*s*s) - (es*s*s*s*s-4*es*s*s*s+12*es*s*s-24*s*es+24*es-24)*t*t/(24*s*s*s*s*s);
447 const Precision a = es * sin(t);
448 const Precision b = es * cos(t);
449 const Precision inv_s_theta = 1/(s*s + t*t);
451 coeff[0] = (es - 1)/s;
452 coeff[1] = (a*s + (1-b)*t) * inv_s_theta / t;
453 coeff[2] = (coeff[0] - ((b-1)*s + a*t) * inv_s_theta) / (t*t);
461 template <
typename Precision>
462 template <
int S,
typename P,
typename VA>
474 const Precision t =
norm(w);
480 result.
get_translation() = coeff[0] * mu.template slice<0,3>() + TooN::operator*(coeff[1], cross) + TooN::operator*(coeff[2], (w ^ cross));
485 template <
typename Precision>
493 result.template slice<3,3>() = sim3.
get_rotation().ln();
494 const Precision theta =
norm(result.template slice<3,3>());
512 template <
typename Precision>
Matrix< R, C, P > exp(const Matrix< R, C, P, B > &m)
computes the matrix exponential of a matrix m by scaling m by 1/(powers of 2), using Taylor series an...
Definition: helpers.h:330
Represent a three-dimensional Euclidean transformation (a rotation and a translation).
Definition: se3.h:48
Matrix< R, C, P > log(const Matrix< R, C, P, B > &m)
computes the matrix logarithm of a matrix m using the inverse scaling and squaring method...
Definition: helpers.h:373
Precision norm(const Vector< Size, Precision, Base > &v)
Compute the norm of v.
Definition: helpers.h:97
const SO3< Precision > & get_rotation() const
Definition: sim3.h:61
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
SO3< Precision > & get_rotation()
Returns the rotation part of the transformation as a SO3.
Definition: sim3.h:59
static SIM3 exp(const Vector< S, P, A > &vect)
Exponentiate a Vector in the Lie Algebra to generate a new SIM3.
Vector< 7, Precision > ln() const
Definition: sim3.h:83
Vector< 7, Precision > adjoint(const Vector< S, P2, Accessor > &vect) const
Transfer a matrix in the Lie Algebra from one co-ordinate frame to another.
Definition: sim3.h:194
A matrix.
Definition: matrix.hh:105
Definition: operators.hh:119
Vector< 3, Precision > & get_translation()
Returns the translation part of the transformation as a Vector.
Definition: sim3.h:64
Matrix< Rows, 4, typename Internal::MultiplyType< PM, P >::type > operator*(const Matrix< Rows, C, PM, A > &lhs, const SIM3< P > &rhs)
Left-multiply by a Matrix.
Definition: sim3.h:415
TooN::Matrix< 3, 3, P > cross_product_matrix(const Vector< Size, P, B > &vec)
creates an returns a cross product matrix M from a 3 vector v, such that for all vectors w...
Definition: helpers.h:444
SIM3 & operator*=(const SIM3 &rhs)
Right-multiply by another SIM3 (concatenate the two transformations)
Definition: sim3.h:93
Vector< 4, typename Internal::MultiplyType< P, PV >::type > operator*(const Vector< S, PV, A > &lhs, const SIM3< P > &rhs)
Left-multiply by a Vector.
Definition: sim3.h:347
Class to represent a three-dimensional rotation matrix.
Definition: so3.h:37
const Vector< 3, Precision > & get_translation() const
Definition: sim3.h:66
Precision & get_scale()
Returns the scale factor.
Definition: sim3.h:69
const Precision & get_scale() const
Definition: sim3.h:71
SIM3< typename Internal::MultiplyType< Precision, P >::type > operator*(const SIM3< P > &rhs) const
Right-multiply by another SIM3 (concatenate the two transformations)
Definition: sim3.h:108
static Vector< 4, Precision > generator_field(int i, const Vector< 4, Precision, Base > &pos)
Returns the i-th generator times pos.
Definition: sim3.h:138
Vector< 7, 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: sim3.h:208
Vector< 4, typename Internal::MultiplyType< P, PV >::type > operator*(const SIM3< P > &lhs, const Vector< S, PV, A > &rhs)
Right-multiply by a Vector.
Definition: sim3.h:306
Vector< 3, typename Internal::MultiplyType< P, PV >::type > operator*(const SIM3< P > &lhs, const Vector< 3, PV, A > &rhs)
Right-multiply by a Vector.
Definition: sim3.h:313
Represent a three-dimensional similarity transformation (a rotation, a scale factor and a translation...
Definition: sim3.h:48
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
SIM3 & operator=(const TooN::Operator< TooN::Internal::Identity< TooN::Internal::One >> &)
Reset back to the identity transform.
Definition: sim3.h:101
Vector< N, Precision > gaussian_elimination(Matrix< N, N, Precision > A, Vector< N, Precision > b)
Return the solution for , given and .
Definition: gaussian_elimination.h:43
SO3< Precision > & get_rotation()
Returns the rotation part of the transformation as a SO3.
Definition: se3.h:62
std::istream & operator>>(std::istream &is, SIM3< Precision > &rhs)
Reads an SIM3 from a stream.
Definition: sim3.h:267
Matrix< 4, Cols, typename Internal::MultiplyType< P, PM >::type > operator*(const SIM3< P > &lhs, const Matrix< R, Cols, PM, A > &rhs)
Right-multiply by a Matrix.
Definition: sim3.h:381
SIM3()
Default constructor. Initialises the the rotation to zero (the identity), the scale to one and the tr...
Definition: sim3.h:51