g2o
Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
g2o::SBACam Class Reference

#include <sbacam.h>

Inheritance diagram for g2o::SBACam:
Inheritance graph
[legend]
Collaboration diagram for g2o::SBACam:
Collaboration graph
[legend]

Public Member Functions

 SBACam ()
 
 SBACam (const Eigen::Quaterniond &r_, const Eigen::Vector3d &t_)
 
 SBACam (const SE3Quat &p)
 
void update (const Vector6d &update)
 
void setKcam (double fx, double fy, double cx, double cy, double tx)
 
void setTransform ()
 
void setProjection ()
 
void setDr ()
 
- Public Member Functions inherited from g2o::SE3Quat
 SE3Quat ()
 
 SE3Quat (const Matrix3D &R, const Vector3D &t)
 
 SE3Quat (const Eigen::Quaterniond &q, const Vector3D &t)
 
template<typename Derived >
 SE3Quat (const Eigen::MatrixBase< Derived > &v)
 
const Vector3Dtranslation () const
 
void setTranslation (const Vector3D &t_)
 
const Eigen::Quaterniond & rotation () const
 
void setRotation (const Eigen::Quaterniond &r_)
 
SE3Quat operator* (const SE3Quat &tr2) const
 
SE3Quatoperator*= (const SE3Quat &tr2)
 
Vector3D operator* (const Vector3D &v) const
 
SE3Quat inverse () const
 
double operator[] (int i) const
 
Vector7d toVector () const
 
void fromVector (const Vector7d &v)
 
Vector6d toMinimalVector () const
 
void fromMinimalVector (const Vector6d &v)
 
Vector6d log () const
 
Vector3D map (const Vector3D &xyz) const
 
Eigen::Matrix< double, 6, 6, Eigen::ColMajor > adj () const
 
Eigen::Matrix< double, 4, 4, Eigen::ColMajor > to_homogeneous_matrix () const
 
void normalizeRotation ()
 
 operator Isometry3D () const
 

Static Public Member Functions

static void transformW2F (Eigen::Matrix< double, 3, 4 > &m, const Eigen::Vector3d &trans, const Eigen::Quaterniond &qrot)
 
static void transformF2W (Eigen::Matrix< double, 3, 4 > &m, const Eigen::Vector3d &trans, const Eigen::Quaterniond &qrot)
 
- Static Public Member Functions inherited from g2o::SE3Quat
static SE3Quat exp (const Vector6d &update)
 

Public Attributes

Eigen::Matrix3d Kcam
 
double baseline
 
Eigen::Matrix< double, 3, 4 > w2n
 
Eigen::Matrix< double, 3, 4 > w2i
 
Eigen::Matrix3d dRdx
 
Eigen::Matrix3d dRdy
 
Eigen::Matrix3d dRdz
 
- Public Attributes inherited from g2o::SE3Quat
 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Additional Inherited Members

- Protected Attributes inherited from g2o::SE3Quat
Eigen::Quaterniond _r
 
Vector3D _t
 

Detailed Description

Definition at line 57 of file sbacam.h.

Constructor & Destructor Documentation

g2o::SBACam::SBACam ( )
inline

Definition at line 75 of file sbacam.h.

76  {
77  SE3Quat();
78  setKcam(1,1,0.5,0.5,0); // unit image projection
79  }
void setKcam(double fx, double fy, double cx, double cy, double tx)
Definition: sbacam.h:138
g2o::SBACam::SBACam ( const Eigen::Quaterniond &  r_,
const Eigen::Vector3d &  t_ 
)
inline

Definition at line 83 of file sbacam.h.

83  : SE3Quat(r_, t_)
84  {
85  setTransform();
86  setProjection();
87  setDr();
88  }
void setDr()
Definition: sbacam.h:159
void setTransform()
Definition: sbacam.h:152
void setProjection()
Definition: sbacam.h:156
g2o::SBACam::SBACam ( const SE3Quat p)
inline

Definition at line 90 of file sbacam.h.

90  : SE3Quat(p) {
91  setTransform();
92  setProjection();
93  setDr();
94  }
void setDr()
Definition: sbacam.h:159
void setTransform()
Definition: sbacam.h:152
void setProjection()
Definition: sbacam.h:156

Member Function Documentation

void g2o::SBACam::setDr ( )
inline

Definition at line 159 of file sbacam.h.

160  {
161  // inefficient, just for testing
162  // use simple multiplications and additions for production code in calculating dRdx,y,z
163  Eigen::Matrix3d dRidx, dRidy, dRidz;
164  dRidx << 0.0,0.0,0.0,
165  0.0,0.0,2.0,
166  0.0,-2.0,0.0;
167  dRidy << 0.0,0.0,-2.0,
168  0.0,0.0,0.0,
169  2.0,0.0,0.0;
170  dRidz << 0.0,2.0,0.0,
171  -2.0,0.0,0.0,
172  0.0,0.0,0.0;
173 
174  // for dS'*R', with dS the incremental change
175  dRdx = dRidx * w2n.block<3,3>(0,0);
176  dRdy = dRidy * w2n.block<3,3>(0,0);
177  dRdz = dRidz * w2n.block<3,3>(0,0);
178  }
Eigen::Matrix3d dRdx
Definition: sbacam.h:72
Eigen::Matrix3d dRdz
Definition: sbacam.h:72
Eigen::Matrix3d dRdy
Definition: sbacam.h:72
Eigen::Matrix< double, 3, 4 > w2n
Definition: sbacam.h:67
void g2o::SBACam::setKcam ( double  fx,
double  fy,
double  cx,
double  cy,
double  tx 
)
inline

Definition at line 138 of file sbacam.h.

Referenced by g2o::VertexCam::read().

139  {
140  Kcam.setZero();
141  Kcam(0,0) = fx;
142  Kcam(1,1) = fy;
143  Kcam(0,2) = cx;
144  Kcam(1,2) = cy;
145  Kcam(2,2) = 1.0;
146  baseline = tx;
147  setProjection();
148  setDr();
149  }
void setDr()
Definition: sbacam.h:159
double baseline
Definition: sbacam.h:64
Eigen::Matrix3d Kcam
Definition: sbacam.h:63
void setProjection()
Definition: sbacam.h:156
void g2o::SBACam::setProjection ( )
inline

Definition at line 156 of file sbacam.h.

156 { w2i = Kcam * w2n; }
Eigen::Matrix3d Kcam
Definition: sbacam.h:63
Eigen::Matrix< double, 3, 4 > w2i
Definition: sbacam.h:68
Eigen::Matrix< double, 3, 4 > w2n
Definition: sbacam.h:67
void g2o::SBACam::setTransform ( )
inline

Definition at line 152 of file sbacam.h.

152 { transformW2F(w2n,_t,_r); }
static void transformW2F(Eigen::Matrix< double, 3, 4 > &m, const Eigen::Vector3d &trans, const Eigen::Quaterniond &qrot)
Definition: sbacam.h:117
Eigen::Quaterniond _r
Definition: se3quat.h:46
Vector3D _t
Definition: se3quat.h:47
Eigen::Matrix< double, 3, 4 > w2n
Definition: sbacam.h:67
static void g2o::SBACam::transformF2W ( Eigen::Matrix< double, 3, 4 > &  m,
const Eigen::Vector3d &  trans,
const Eigen::Quaterniond &  qrot 
)
inlinestatic

Definition at line 129 of file sbacam.h.

132  {
133  m.block<3,3>(0,0) = qrot.toRotationMatrix();
134  m.col(3) = trans;
135  }
static void g2o::SBACam::transformW2F ( Eigen::Matrix< double, 3, 4 > &  m,
const Eigen::Vector3d &  trans,
const Eigen::Quaterniond &  qrot 
)
inlinestatic

Definition at line 117 of file sbacam.h.

120  {
121  m.block<3,3>(0,0) = qrot.toRotationMatrix().transpose();
122  m.col(3).setZero(); // make sure there's no translation
123  Eigen::Vector4d tt;
124  tt.head(3) = trans;
125  tt[3] = 1.0;
126  m.col(3) = -m*tt;
127  }
void g2o::SBACam::update ( const Vector6d update)
inline

Definition at line 98 of file sbacam.h.

99  {
100  // std::cout << "UPDATE " << update.transpose() << std::endl;
101  // position update
102  _t += update.head(3);
103  // small quaternion update
104  Eigen::Quaterniond qr;
105  qr.vec() = update.segment<3>(3);
106  qr.w() = sqrt(1.0 - qr.vec().squaredNorm()); // should always be positive
107  _r *= qr; // post-multiply
108  _r.normalize();
109  setTransform();
110  setProjection();
111  setDr();
112  // std::cout << t.transpose() << std::endl;
113  // std::cout << r.coeffs().transpose() << std::endl;
114  }
void setDr()
Definition: sbacam.h:159
void setTransform()
Definition: sbacam.h:152
void setProjection()
Definition: sbacam.h:156
void update(const Vector6d &update)
Definition: sbacam.h:98
Eigen::Quaterniond _r
Definition: se3quat.h:46
Vector3D _t
Definition: se3quat.h:47

Member Data Documentation

double g2o::SBACam::baseline
Eigen::Matrix3d g2o::SBACam::dRdx
Eigen::Matrix3d g2o::SBACam::dRdy
Eigen::Matrix3d g2o::SBACam::dRdz
Eigen::Matrix3d g2o::SBACam::Kcam
Eigen::Matrix<double,3,4> g2o::SBACam::w2i
Eigen::Matrix<double,3,4> g2o::SBACam::w2n

The documentation for this class was generated from the following file: