Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef SIM_3
00018 #define SIM_3
00019
00020 #include "se3_ops.h"
00021 #include <Eigen/Geometry>
00022
00023 namespace g2o
00024 {
00025 using namespace Eigen;
00026
00027 typedef Matrix <double, 7, 1> Vector7d;
00028 typedef Matrix <double, 7, 7> Matrix7d;
00029
00030
00031 struct Sim3
00032 {
00033 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00034
00035 protected:
00036 Quaterniond r;
00037 Vector3d t;
00038 double s;
00039
00040
00041 public:
00042 Sim3()
00043 {
00044 r.setIdentity();
00045 t.fill(0.);
00046 s=1.;
00047 }
00048
00049 Sim3(const Quaterniond & r, const Vector3d & t, double s)
00050 : r(r),t(t),s(s)
00051 {
00052 }
00053
00054 Sim3(const Matrix3d & R, const Vector3d & t, double s)
00055 : r(Quaterniond(R)),t(t),s(s)
00056 {
00057 }
00058
00059
00060 Sim3(const Vector7d & update)
00061 {
00062
00063 Vector3d omega;
00064 for (int i=0; i<3; i++)
00065 omega[i]=update[i];
00066
00067 Vector3d upsilon;
00068 for (int i=0; i<3; i++)
00069 upsilon[i]=update[i+3];
00070
00071 double sigma = update[6];
00072 double theta = omega.norm();
00073 Matrix3d Omega = skew(omega);
00074 s = std::exp(sigma);
00075 Matrix3d Omega2 = Omega*Omega;
00076 Matrix3d I;
00077 I.setIdentity();
00078 Matrix3d R;
00079
00080 double eps = 0.00001;
00081 double A,B,C;
00082 if (fabs(sigma)<eps)
00083 {
00084 C = 1;
00085 if (theta<eps)
00086 {
00087 A = 1./2.;
00088 B = 1./6.;
00089 R = (I + Omega + Omega*Omega);
00090 }
00091 else
00092 {
00093 double theta2= theta*theta;
00094 A = (1-cos(theta))/(theta2);
00095 B = (theta-sin(theta))/(theta2*theta);
00096 R = I + sin(theta)/theta *Omega + (1-cos(theta))/(theta*theta)*Omega2;
00097 }
00098 }
00099 else
00100 {
00101 C=(s-1)/sigma;
00102 if (theta<eps)
00103 {
00104 double sigma2= sigma*sigma;
00105 A = ((sigma-1)*s+1)/sigma2;
00106 B= ((0.5*sigma2-sigma+1)*s)/(sigma2*sigma);
00107 R = (I + Omega + Omega2);
00108 }
00109 else
00110 {
00111 R = I + sin(theta)/theta *Omega + (1-cos(theta))/(theta*theta)*Omega2;
00112
00113
00114
00115 double a=s*sin(theta);
00116 double b=s*cos(theta);
00117 double theta2= theta*theta;
00118 double sigma2= sigma*sigma;
00119
00120 double c=theta2+sigma2;
00121 A = (a*sigma+ (1-b)*theta)/(theta*c);
00122 B = (C-((b-1)*sigma+a*theta)/(c))*1./(theta2);
00123
00124 }
00125 }
00126 r = Quaterniond(R);
00127
00128
00129
00130 Matrix3d W = A*Omega + B*Omega2 + C*I;
00131 t = W*upsilon;
00132 }
00133
00134 Vector3d map (const Vector3d& xyz) const {
00135 return s*(r*xyz) + t;
00136 }
00137
00138 Vector7d log() const
00139 {
00140 Vector7d res;
00141 double sigma = std::log(s);
00142
00143
00144
00145
00146 Vector3d omega;
00147 Vector3d upsilon;
00148
00149
00150 Matrix3d R = r.toRotationMatrix();
00151 double d = 0.5*(R(0,0)+R(1,1)+R(2,2)-1);
00152
00153 Matrix3d Omega;
00154
00155 double eps = 0.00001;
00156 Matrix3d I = Matrix3d::Identity();
00157
00158 double A,B,C;
00159 if (fabs(sigma)<eps)
00160 {
00161 C = 1;
00162 if (d>1-eps)
00163 {
00164 omega=0.5*deltaR(R);
00165 Omega = skew(omega);
00166 A = 1./2.;
00167 B = 1./6.;
00168 }
00169 else
00170 {
00171 double theta = acos(d);
00172 double theta2 = theta*theta;
00173 omega = theta/(2*sqrt(1-d*d))*deltaR(R);
00174 Omega = skew(omega);
00175 A = (1-cos(theta))/(theta2);
00176 B = (theta-sin(theta))/(theta2*theta);
00177 }
00178 }
00179 else
00180 {
00181 C=(s-1)/sigma;
00182 if (d>1-eps)
00183 {
00184
00185 double sigma2 = sigma*sigma;
00186 omega=0.5*deltaR(R);
00187 Omega = skew(omega);
00188 A = ((sigma-1)*s+1)/(sigma2);
00189 B = ((0.5*sigma2-sigma+1)*s)/(sigma2*sigma);
00190 }
00191 else
00192 {
00193 double theta = acos(d);
00194 omega = theta/(2*sqrt(1-d*d))*deltaR(R);
00195 Omega = skew(omega);
00196 double theta2 = theta*theta;
00197 double a=s*sin(theta);
00198 double b=s*cos(theta);
00199 double c=theta2 + sigma*sigma;
00200 A = (a*sigma+ (1-b)*theta)/(theta*c);
00201 B = (C-((b-1)*sigma+a*theta)/(c))*1./(theta2);
00202 }
00203 }
00204
00205 Matrix3d W = A*Omega + B*Omega*Omega + C*I;
00206
00207 upsilon = W.lu().solve(t);
00208
00209
00210 for (int i=0; i<3; i++)
00211 res[i] = omega[i];
00212
00213 for (int i=0; i<3; i++)
00214 res[i+3] = upsilon[i];
00215
00216 res[6] = sigma;
00217
00218 return res;
00219
00220 }
00221
00222
00223 Sim3 inverse() const
00224 {
00225 return Sim3(r.conjugate(), r.conjugate()*((-1./s)*t), 1./s);
00226 }
00227
00228
00229 double operator[](int i) const
00230 {
00231 assert(i<8);
00232 if (i<4){
00233
00234 return r.coeffs()[i];
00235 }
00236 if (i<7){
00237 return t[i-4];
00238 }
00239 return s;
00240 }
00241
00242 double& operator[](int i)
00243 {
00244 assert(i<8);
00245 if (i<4){
00246
00247 return r.coeffs()[i];
00248 }
00249 if (i<7)
00250 {
00251 return t[i-4];
00252 }
00253 return s;
00254 }
00255
00256 Sim3 operator *(const Sim3& other){
00257 Sim3 ret;
00258 ret.r = r*other.r;
00259 ret.t=s*(r*other.t)+t;
00260 ret.s=s*other.s;
00261 return ret;
00262 }
00263
00264 Sim3& operator *=(const Sim3& other){
00265 Sim3 ret=(*this)*other;
00266 *this=ret;
00267 return *this;
00268 }
00269
00270 inline const Vector3d& translation() const {return t;}
00271
00272 inline Vector3d& translation() {return t;}
00273
00274 inline const Quaterniond& rotation() const {return r;}
00275
00276 inline Quaterniond& rotation() {return r;}
00277
00278 inline const double& scale() const {return s;}
00279
00280 inline double& scale() {return s;}
00281
00282 };
00283
00284 inline std::ostream& operator <<(std::ostream& out_str,
00285 const Sim3& sim3)
00286 {
00287 out_str << sim3.rotation().coeffs() << std::endl;
00288 out_str << sim3.translation() << std::endl;
00289 out_str << sim3.scale() << std::endl;
00290
00291 return out_str;
00292 }
00293
00294 }
00295
00296
00297 #endif