simple_math.h
Go to the documentation of this file.
00001 /* This file is part of the Pangolin Project.
00002  * http://github.com/stevenlovegrove/Pangolin
00003  *
00004  * Copyright (c) 2011 Steven Lovegrove
00005  *
00006  * Permission is hereby granted, free of charge, to any person
00007  * obtaining a copy of this software and associated documentation
00008  * files (the "Software"), to deal in the Software without
00009  * restriction, including without limitation the rights to use,
00010  * copy, modify, merge, publish, distribute, sublicense, and/or sell
00011  * copies of the Software, and to permit persons to whom the
00012  * Software is furnished to do so, subject to the following
00013  * conditions:
00014  *
00015  * The above copyright notice and this permission notice shall be
00016  * included in all copies or substantial portions of the Software.
00017  *
00018  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
00019  * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES
00020  * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
00021  * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
00022  * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
00023  * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
00024  * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
00025  * OTHER DEALINGS IN THE SOFTWARE.
00026  */
00027 
00028 #ifndef PANGOLIN_SIMPLE_MATH_H
00029 #define PANGOLIN_SIMPLE_MATH_H
00030 
00031 #include <iostream>
00032 #include <string.h>
00033 #include <algorithm>
00034 #include <stdarg.h>
00035 #include <cmath>
00036 
00037 namespace pangolin
00038 {
00039 
00040 static const double Identity3d[] = {1,0,0, 0,1,0, 0,0,1};
00041 static const double Zero3d[]     = {0,0,0, 0,0,0, 0,0,0};
00042 static const double Identity4d[] = {1,0,0,0, 0,1,0,0, 0,0,1,0, 0,0,0,1};
00043 static const double Zero4d[]     = {0,0,0,0, 0,0,0,0, 0,0,0,0, 0,0,0,0};
00044 
00045 static const float Identity3f[] = {1,0,0, 0,1,0, 0,0,1};
00046 static const float Zero3f[]     = {0,0,0, 0,0,0, 0,0,0};
00047 static const float Identity4f[] = {1,0,0,0, 0,1,0,0, 0,0,1,0, 0,0,0,1};
00048 static const float Zero4f[]     = {0,0,0,0, 0,0,0,0, 0,0,0,0, 0,0,0,0};
00049 
00050 template<int R, int C, typename P>
00051 void MatPrint(const P m[R*C])
00052 {
00053     for( int r=0; r < R; ++r)
00054     {
00055         for( int c=0; c < C; ++c )
00056             std::cout << m[R*c+r] << " ";
00057         std::cout << std::endl;
00058     }
00059     std::cout << std::endl;
00060 }
00061 
00062 template<int R, int C, typename P>
00063 void MatPrint(const P m[R*C], std::string name)
00064 {
00065     std::cout << name << " = [" << std::endl;
00066     for( int r=0; r < R; ++r)
00067     {
00068         for( int c=0; c < C; ++c )
00069             std::cout << m[R*c+r] << " ";
00070         std::cout << std::endl;
00071     }
00072     std::cout << std::endl << "]" << std::endl;
00073 }
00074 
00075 // Set array using varadic arguments
00076 template<int R, int C, typename P>
00077 void MatSet(P m[R*C], ...)
00078 {
00079     va_list ap;
00080     va_start(ap,m);
00081     for( int i=0; i< R*C; ++i )
00082     {
00083         *m = (P)va_arg(ap,double);
00084         ++m;
00085     }
00086 }
00087 
00088 // m = zeroes(N)
00089 template<int R, int C, typename P>
00090 void SetZero(P m[R*C] )
00091 {
00092     std::fill_n(m,R*C,0);
00093 }
00094 
00095 // m = identity(N)
00096 template<int N, typename P>
00097 void SetIdentity(P m[N*N] )
00098 {
00099     std::fill_n(m,N*N,0);
00100     for( int i=0; i< N; ++i )
00101         m[N*i+i] = 1;
00102 }
00103 
00104 // mo = m1 * m2
00105 template<int R, int M, int C, typename P>
00106 void MatMul(P mo[R*C], const P m1[R*M], const P m2[M*C] )
00107 {
00108     for( int r=0; r < R; ++r)
00109         for( int c=0; c < C; ++c )
00110         {
00111             mo[R*c+r] = 0;
00112             for( int m=0; m < M; ++ m) mo[R*c+r] += m1[R*m+r] * m2[M*c+m];
00113         }
00114 }
00115 
00116 // mo = m1 * m2 * s
00117 template<int R, int M, int C, typename P>
00118 void MatMul(P mo[R*C], const P m1[R*M], const P m2[M*C], P s )
00119 {
00120     for( int r=0; r < R; ++r)
00121         for( int c=0; c < C; ++c )
00122         {
00123             mo[R*c+r] = 0;
00124             for( int m=0; m < M; ++ m) mo[R*c+r] += m1[R*m+r] * m2[M*c+m] * s;
00125         }
00126 }
00127 
00128 // mo = m1 * transpose(m2)
00129 template<int R, int M, int C, typename P>
00130 void MatMulTranspose(P mo[R*C], const P m1[R*M], const P m2[C*M] )
00131 {
00132     for( int r=0; r < R; ++r)
00133         for( int c=0; c < C; ++c )
00134         {
00135             mo[R*c+r] = 0;
00136             for( int m=0; m < M; ++ m) mo[R*c+r] += m1[R*m+r] * m2[C*m+c];
00137         }
00138 }
00139 
00140 // m = m1 + m2
00141 template<int R, int C, typename P>
00142 void MatAdd(P m[R*C], const P m1[R*C], const P m2[R*C])
00143 {
00144     for( int i=0; i< R*C; ++i )
00145         m[i] = m1[i] + m2[i];
00146 }
00147 
00148 // m = m1 - m2
00149 template<int R, int C, typename P>
00150 void MatSub(P m[R*C], const P m1[R*C], const P m2[R*C])
00151 {
00152     for( int i=0; i< R*C; ++i )
00153         m[i] = m1[i] - m2[i];
00154 }
00155 
00156 // m = m1 * scalar
00157 template<int R, int C, typename P>
00158 void MatMul(P m[R*C], const P m1[R*C], P scalar)
00159 {
00160     for( int i=0; i< R*C; ++i )
00161         m[i] = m1[i] * scalar;
00162 }
00163 
00164 // m = m1 + m2
00165 template<int R, int C, typename P>
00166 void MatMul(P m[R*C], P scalar)
00167 {
00168     for( int i=0; i< R*C; ++i )
00169         m[i] *= scalar;
00170 }
00171 
00172 template<int N, typename P>
00173 void MatTranspose(P out[N*N], const P in[N*N] )
00174 {
00175     for( int c=0; c<N; ++c )
00176         for( int r=0; r<N; ++r )
00177             out[N*c+r] = in[N*r+c];
00178 }
00179 
00180 template<int N, typename P>
00181 void MatTranspose(P m[N*N] )
00182 {
00183     for( int c=0; c<N; ++c )
00184         for( int r=0; r<c; ++r )
00185             std::swap<P>(m[N*c+r],m[N*r+c]);
00186 }
00187 
00188 // s = skewSymetrixMatrix(v)
00189 template<typename P>
00190 void MatSkew(P s[3*3], const P v[3] )
00191 {
00192     s[0] = 0;
00193     s[1] = v[2];
00194     s[2] = -v[1];
00195     s[3] = -v[2];
00196     s[4] = 0;
00197     s[5] = v[0];
00198     s[6] = v[1];
00199     s[7] = -v[0];
00200     s[8] = 0;
00201 }
00202 
00203 template<int N, typename P>
00204 void MatOrtho( P m[N*N] )
00205 {
00206     // http://www.euclideanspace.com/maths/algebra/matrix/orthogonal/index.htm
00207     P Itimes3[N*N];
00208     SetIdentity<N>(Itimes3);
00209     MatMul<N,N>(Itimes3,(P)3.0);
00210 
00211     P mmT[N*N];
00212     MatMulTranspose<N,N,N>(mmT,m,m);
00213 
00214     P _c[N*N];
00215     MatSub<N,N>(_c,Itimes3,mmT);
00216     P _m[N*N];
00217     MatMul<N,N,N>(_m,m,_c,(P)0.5);
00218     std::copy(_m,_m+(N*N),m);
00219 }
00220 
00221 template<typename P>
00222 void Rotation(P R[3*3], P x, P y, P z)
00223 {
00224     P sx = sin(x);
00225     P sy = sin(y);
00226     P sz = sin(z);
00227     P cx = cos(x);
00228     P cy = cos(y);
00229     P cz = cos(z);
00230 //  P cx = sqrt( (P)1.0 - sx * sx);
00231 //  P cy = sqrt( (P)1.0 - sy * sy);
00232 //  P cz = sqrt( (P)1.0 - sz * sz);
00233     R[0] = cy * cz;
00234     R[1] = sx * sy * cz + cx * sz;
00235     R[2] = -cx * sy * cz + sx * sz;
00236     R[3] = -cy * sz;
00237     R[4] = -sx * sy * sz + cx * cz;
00238     R[5] = cx * sy * sz + sx * cz;
00239     R[6] = sy;
00240     R[7] = -sx * cy;
00241     R[8] = cx * cy;
00242 }
00243 
00244 template<typename P>
00245 void LieSetIdentity(P T_ba[3*4] )
00246 {
00247     SetIdentity<3>(T_ba);
00248     std::fill_n(T_ba+(3*3),3,0);
00249 }
00250 
00251 template<typename P>
00252 void LieSetRotation(P T_ba[3*4], const P R_ba[3*3] )
00253 {
00254     std::copy(R_ba,R_ba+(3*3),T_ba);
00255 }
00256 
00257 template<typename P>
00258 void LieSetTranslation(P T_ba[3*4], const P a_b[3*3] )
00259 {
00260     std::copy(a_b, a_b+3, T_ba+(3*3));
00261 }
00262 
00263 template<typename P>
00264 void LieSetSE3(P T_ba[3*4], const P R_ba[3*3], const P a_b[3] )
00265 {
00266     LieSetRotation<P>(T_ba,R_ba);
00267     LieSetTranslation<P>(T_ba,a_b);
00268 }
00269 
00270 template<typename P>
00271 void LieGetRotation(P R_ba[3*3], const P T_ba[3*4] )
00272 {
00273     std::copy(T_ba,T_ba+(3*3),R_ba);
00274 }
00275 
00276 template<typename P>
00277 void LieApplySO3( P out[3], const P R_ba[3*3], const P in[3] )
00278 {
00279     MatMul<3,3,1,P>(out,R_ba,in);
00280 }
00281 
00282 template<typename P>
00283 void LieApplySE3vec( P x_b[3], const P T_ba[3*4], const P x_a[3] )
00284 {
00285     P rot[3];
00286     MatMul<3,3,1,P>(rot,T_ba,x_a);
00287     MatAdd<3,1,P>(x_b,rot,T_ba+(3*3));
00288 }
00289 
00290 template<typename P>
00291 void LieMulSO3( P R_ca[3*3], const P R_cb[3*3], const P R_ba[3*3] )
00292 {
00293     MatMul<3,3,3>(R_ca,R_cb,R_ba);
00294 }
00295 
00296 template<typename P>
00297 void LieMulSE3( P T_ca[3*4], const P T_cb[3*4], const P T_ba[3*4] )
00298 {
00299     LieMulSO3<>(T_ca,T_cb,T_ba);
00300     P R_cb_times_a_b[3];
00301     LieApplySO3<>(R_cb_times_a_b,T_cb,T_ba+(3*3));
00302     MatAdd<3,1>(T_ca+(3*3),R_cb_times_a_b,T_cb+(3*3));
00303 }
00304 
00305 template<typename P>
00306 void LiePutSE3in4x4(P out[4*4], const P in[3*4] )
00307 {
00308     SetIdentity<4>(out);
00309     std::copy(in,in+3, out);
00310     std::copy(in+3,in+6, out+4);
00311     std::copy(in+6,in+9, out+8);
00312     std::copy(in+9,in+12, out+12);
00313 }
00314 
00315 template<typename P>
00316 void LieSE3from4x4(P out[3*4], const P in[4*4] )
00317 {
00318     std::copy(in,in+4, out);
00319     std::copy(in+4,in+8, out+3);
00320     std::copy(in+8,in+12, out+6);
00321     std::copy(in+12,in+16, out+9);
00322 }
00323 
00324 template<typename P>
00325 void LieMul4x4bySE3( P T_ca[4*4], const P T_cb[3*4], const P T_ba[4*4] )
00326 {
00327     // TODO: fast
00328     P T_cb4[4*4];
00329     LiePutSE3in4x4<>(T_cb4,T_cb);
00330     P res[4*4];
00331     MatMul<4,4,4>(res,T_cb4,T_ba);
00332     std::copy(res,res+(4*4),T_ca);
00333 }
00334 
00335 template<typename P>
00336 void LieTransposeSO3( P R_ab[3*3], const P R_ba[3*3] )
00337 {
00338     MatTranspose<3,P>(R_ab,R_ba);
00339 }
00340 
00341 template<typename P>
00342 void LieInverseSE3( P T_ab[3*4], const P T_ba[3*4] )
00343 {
00344     LieTransposeSO3<P>(T_ab,T_ba);
00345     P minus_b_a[3];
00346     LieApplySO3(minus_b_a, T_ab, T_ba+(3*3));
00347     MatMul<3,1,P>(T_ab+(3*3),minus_b_a, -1);
00348 }
00349 
00350 // c = a x b
00351 template<typename P>
00352 void CrossProduct( P c[3], const P a[3], const P b[3] )
00353 {
00354     c[0] = a[1] * b[2] - a[2] * b[1];
00355     c[1] = a[2] * b[0] - a[0] * b[2];
00356     c[2] = a[0] * b[1] - a[1] * b[0];
00357 }
00358 
00359 template<int R, typename P>
00360 P Length( P v[R] )
00361 {
00362     P sum_sq = 0;
00363 
00364     for(size_t r = 0; r < R; ++r )
00365     {
00366         sum_sq += v[r] * v[r];
00367     }
00368 
00369     return sqrt(sum_sq);
00370 }
00371 
00372 
00373 template<int R, typename P>
00374 void Normalise( P v[R] )
00375 {
00376     const P length = Length<R,P>(v);
00377 
00378     for(size_t r = 0; r < R; ++r )
00379     {
00380         v[r] /= length;
00381     }
00382 }
00383 
00384 template<typename P>
00385 void EnforceUpT_wc(P T_wc[3*4], const P up_w[3])
00386 {
00387     // Copy R_wc
00388     P R_wc[3*3];
00389     std::copy(T_wc,T_wc+3*3,R_wc);
00390 
00391     // New R_wc should go into T_wc
00392     P* NR_wc = T_wc;
00393 
00394 //    // cx_w,cy_w,cz_w are camera axis in world coordinates
00395 //    // Calculate new camera coordinates (ncx_w,ncy_w,ncz_w)
00396 
00397     // ncx_w = up_w x cz_w
00398     CrossProduct(NR_wc + 0*3, up_w, R_wc + 2*3);
00399 
00400     // ncy_w = cz_w x ncx_w
00401     CrossProduct(NR_wc + 1*3, R_wc + 2*3, NR_wc + 0*3);
00402 
00403     // ncz_w = cz_w
00404     std::copy(R_wc + 2*3, R_wc + 3*3, NR_wc + 2*3);
00405 
00406     Normalise<3,P>(NR_wc + 0*3);
00407     Normalise<3,P>(NR_wc + 1*3);
00408     Normalise<3,P>(NR_wc + 2*3);
00409 }
00410 
00411 template<typename P>
00412 void EnforceUpT_cw(P T_cw_4x4[4*4], const P up_w[3])
00413 {
00414     // 3x4 from 4x4
00415     P T_cw[3*4];
00416     LieSE3from4x4<P>(T_cw,T_cw_4x4);
00417 
00418     // Invert T_cw
00419     P T_wc[3*4];
00420     LieInverseSE3<P>(T_wc, T_cw);
00421 
00422     // Enforce up for T_wc
00423     EnforceUpT_wc<P>(T_wc, up_w);
00424 
00425     // Invert
00426     LieInverseSE3<P>(T_cw, T_wc);
00427 
00428     // 4x4 from 3x4
00429     LiePutSE3in4x4<P>(T_cw_4x4,T_cw);
00430 }
00431 
00432 }
00433 
00434 #endif //PANGOLIN_SIMPLE_MATH_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pangolin_wrapper
Author(s): Todor Stoyanov
autogenerated on Wed Feb 13 2013 14:03:25