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

Stereo camera vertex, derived from SE3 class. Note that we use the actual pose of the vertex as its parameterization, rather than the transform from RW to camera coords. Uses static vars for camera params, so there is a single camera setup. More...

#include <types_icp.h>

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

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW VertexSCam ()
 
virtual bool read (std::istream &is)
 read the vertex from a stream, i.e., the internal state of the vertex More...
 
virtual bool write (std::ostream &os) const
 write the vertex to a stream More...
 
virtual void oplusImpl (const double *update)
 
void setTransform ()
 
void setProjection ()
 
void setDr ()
 
void setAll ()
 
void mapPoint (Vector3D &res, const Vector3D &pt3)
 
- Public Member Functions inherited from g2o::VertexSE3
 VertexSE3 ()
 
virtual void setToOriginImpl ()
 sets the node to the origin (used in the multilevel stuff) More...
 
virtual bool setEstimateDataImpl (const double *est)
 
virtual bool getEstimateData (double *est) const
 
virtual int estimateDimension () const
 
virtual bool setMinimalEstimateDataImpl (const double *est)
 
virtual bool getMinimalEstimateData (double *est) const
 
virtual int minimalEstimateDimension () const
 
SE3Quat G2O_ATTRIBUTE_DEPRECATED (estimateAsSE3Quat() const)
 wrapper function to use the old SE3 type More...
 
void G2O_ATTRIBUTE_DEPRECATED (setEstimateFromSE3Quat(const SE3Quat &se3))
 wrapper function to use the old SE3 type More...
 
- Public Member Functions inherited from g2o::BaseVertex< 6, Isometry3D >
 BaseVertex ()
 
virtual const double & hessian (int i, int j) const
 get the element from the hessian matrix More...
 
virtual double & hessian (int i, int j)
 
virtual double hessianDeterminant () const
 
virtual double * hessianData ()
 
virtual void mapHessianMemory (double *d)
 
virtual int copyB (double *b_) const
 
virtual const double & b (int i) const
 get the b vector element More...
 
virtual double & b (int i)
 
Eigen::Matrix< double, D, 1, Eigen::ColMajor > & b ()
 return right hand side b of the constructed linear system More...
 
const Eigen::Matrix< double, D, 1, Eigen::ColMajor > & b () const
 
virtual double * bData ()
 return a pointer to the b vector associated with this vertex More...
 
virtual void clearQuadraticForm ()
 
virtual double solveDirect (double lambda=0)
 
HessianBlockTypeA ()
 return the hessian block associated with the vertex More...
 
const HessianBlockTypeA () const
 
virtual void push ()
 backup the position of the vertex to a stack More...
 
virtual void pop ()
 restore the position of the vertex by retrieving the position from the stack More...
 
virtual void discardTop ()
 pop the last element from the stack, without restoring the current estimate More...
 
virtual int stackSize () const
 return the stack size More...
 
const EstimateTypeestimate () const
 return the current estimate of the vertex More...
 
void setEstimate (const EstimateType &et)
 set the estimate for the vertex also calls updateCache() More...
 
- Public Member Functions inherited from g2o::OptimizableGraph::Vertex
 Vertex ()
 
virtual Vertexclone () const
 returns a deep copy of the current vertex More...
 
virtual ~Vertex ()
 
void setToOrigin ()
 sets the node to the origin (used in the multilevel stuff) More...
 
bool setEstimateData (const double *estimate)
 
bool setEstimateData (const std::vector< double > &estimate)
 
virtual bool getEstimateData (std::vector< double > &estimate) const
 
bool setMinimalEstimateData (const double *estimate)
 
bool setMinimalEstimateData (const std::vector< double > &estimate)
 
virtual bool getMinimalEstimateData (std::vector< double > &estimate) const
 
void oplus (const double *v)
 
int hessianIndex () const
 temporary index of this node in the parameter vector obtained from linearization More...
 
int G2O_ATTRIBUTE_DEPRECATED (tempIndex() const)
 
void setHessianIndex (int ti)
 set the temporary index of the vertex in the parameter blocks More...
 
void G2O_ATTRIBUTE_DEPRECATED (setTempIndex(int ti))
 
bool fixed () const
 true => this node is fixed during the optimization More...
 
void setFixed (bool fixed)
 true => this node should be considered fixed during the optimization More...
 
bool marginalized () const
 true => this node is marginalized out during the optimization More...
 
void setMarginalized (bool marginalized)
 true => this node should be marginalized out during the optimization More...
 
int dimension () const
 dimension of the estimated state belonging to this node More...
 
virtual void setId (int id)
 sets the id of the node in the graph be sure that the graph keeps consistent after changing the id More...
 
void setColInHessian (int c)
 set the row of this vertex in the Hessian More...
 
int colInHessian () const
 get the row of this vertex in the Hessian More...
 
const OptimizableGraphgraph () const
 
OptimizableGraphgraph ()
 
void lockQuadraticForm ()
 
void unlockQuadraticForm ()
 
virtual void updateCache ()
 
CacheContainercacheContainer ()
 
- Public Member Functions inherited from g2o::HyperGraph::Vertex
 Vertex (int id=InvalidId)
 creates a vertex having an ID specified by the argument More...
 
int id () const
 returns the id More...
 
const EdgeSetedges () const
 returns the set of hyper-edges that are leaving/entering in this vertex More...
 
EdgeSetedges ()
 returns the set of hyper-edges that are leaving/entering in this vertex More...
 
virtual HyperGraphElementType elementType () const
 
- Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement
virtual ~HyperGraphElement ()
 
HyperGraphElementclone () const
 
- Public Member Functions inherited from g2o::HyperGraph::DataContainer
 DataContainer ()
 
virtual ~DataContainer ()
 
const DatauserData () const
 the user data associated with this vertex More...
 
DatauserData ()
 
void setUserData (Data *obs)
 
void addUserData (Data *obs)
 

Static Public Member Functions

static void transformW2F (Eigen::Matrix< double, 3, 4, Eigen::ColMajor > &m, const Vector3D &trans, const Eigen::Quaterniond &qrot)
 
static void transformF2W (Eigen::Matrix< double, 3, 4, Eigen::ColMajor > &m, const Vector3D &trans, const Eigen::Quaterniond &qrot)
 
static void setKcam (double fx, double fy, double cx, double cy, double tx)
 

Public Attributes

Eigen::Matrix< double, 3, 4, Eigen::ColMajor > w2n
 
Eigen::Matrix< double, 3, 4, Eigen::ColMajor > w2i
 
Matrix3D dRdx
 
Matrix3D dRdy
 
Matrix3D dRdz
 
- Public Attributes inherited from g2o::VertexSE3
 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Static Public Attributes

static Matrix3D Kcam
 
static double baseline
 
static Matrix3D dRidx
 
static Matrix3D dRidy
 
static Matrix3D dRidz
 
- Static Public Attributes inherited from g2o::VertexSE3
static const int orthogonalizeAfter = 1000
 
- Static Public Attributes inherited from g2o::BaseVertex< 6, Isometry3D >
static const int Dimension
 dimension of the estimate (minimal) in the manifold space More...
 

Additional Inherited Members

- Public Types inherited from g2o::BaseVertex< 6, Isometry3D >
typedef Isometry3D EstimateType
 
typedef std::stack< EstimateType, std::vector< EstimateType, Eigen::aligned_allocator< EstimateType > > > BackupStackType
 
typedef Eigen::Map< Eigen::Matrix< double, D, D, Eigen::ColMajor >, Eigen::Matrix< double, D, D, Eigen::ColMajor >::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > HessianBlockType
 
- Protected Attributes inherited from g2o::VertexSE3
int _numOplusCalls
 store how often opluse was called to trigger orthogonaliation of the rotation matrix More...
 
- Protected Attributes inherited from g2o::BaseVertex< 6, Isometry3D >
HessianBlockType _hessian
 
Eigen::Matrix< double, D, 1, Eigen::ColMajor > _b
 
EstimateType _estimate
 
BackupStackType _backup
 
- Protected Attributes inherited from g2o::OptimizableGraph::Vertex
OptimizableGraph_graph
 
Data_userData
 
int _hessianIndex
 
bool _fixed
 
bool _marginalized
 
int _dimension
 
int _colInHessian
 
OpenMPMutex _quadraticFormMutex
 
CacheContainer_cacheContainer
 
- Protected Attributes inherited from g2o::HyperGraph::Vertex
int _id
 
EdgeSet _edges
 
- Protected Attributes inherited from g2o::HyperGraph::DataContainer
Data_userData
 

Detailed Description

Stereo camera vertex, derived from SE3 class. Note that we use the actual pose of the vertex as its parameterization, rather than the transform from RW to camera coords. Uses static vars for camera params, so there is a single camera setup.

Definition at line 250 of file types_icp.h.

Constructor & Destructor Documentation

g2o::VertexSCam::VertexSCam ( )

Definition at line 232 of file types_icp.cpp.

232  :
233  VertexSE3()
234  {}

Member Function Documentation

void g2o::VertexSCam::mapPoint ( Vector3D res,
const Vector3D pt3 
)
inline

Definition at line 343 of file types_icp.h.

Referenced by g2o::Edge_XYZ_VSC::computeError().

344  {
345  Vector4D pt;
346  pt.head<3>() = pt3;
347  pt(3) = 1.0;
348  Vector3D p1 = w2i * pt;
349  Vector3D p2 = w2n * pt;
350  Vector3D pb(baseline,0,0);
351 
352  double invp1 = 1.0/p1(2);
353  res.head<2>() = p1.head<2>()*invp1;
354 
355  // right camera px
356  p2 = Kcam*(p2-pb);
357  res(2) = p2(0)/p2(2);
358  }
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
Eigen::Matrix< double, 4, 1, Eigen::ColMajor > Vector4D
Definition: eigen_types.h:47
Eigen::Matrix< double, 3, 4, Eigen::ColMajor > w2i
Definition: types_icp.h:274
static Matrix3D Kcam
Definition: types_icp.h:269
static double baseline
Definition: types_icp.h:270
Eigen::Matrix< double, 3, 4, Eigen::ColMajor > w2n
Definition: types_icp.h:273
virtual void g2o::VertexSCam::oplusImpl ( const double *  update)
inlinevirtual

update the position of this vertex. The update is in the form (x,y,z,qx,qy,qz) whereas (x,y,z) represents the translational update and (qx,qy,qz) corresponds to the respective elements. The missing element qw of the quaternion is recovred by || (qw,qx,qy,qz) || == 1 => qw = sqrt(1 - || (qx,qy,qz) ||

Reimplemented from g2o::VertexSE3.

Definition at line 262 of file types_icp.h.

References g2o::VertexSE3::oplusImpl().

263  {
264  VertexSE3::oplusImpl(update);
265  setAll();
266  }
virtual void oplusImpl(const double *update)
Definition: vertex_se3.h:105
bool g2o::VertexSCam::read ( std::istream &  is)
virtual

read the vertex from a stream, i.e., the internal state of the vertex

Reimplemented from g2o::VertexSE3.

Definition at line 331 of file types_icp.cpp.

332  { return false; }
void g2o::VertexSCam::setAll ( )
inline

Definition at line 335 of file types_icp.h.

Referenced by main().

336  {
337  setTransform();
338  setProjection();
339  setDr();
340  }
void setTransform()
Definition: types_icp.h:314
void setProjection()
Definition: types_icp.h:321
void g2o::VertexSCam::setDr ( )
inline

Definition at line 324 of file types_icp.h.

325  {
326  // inefficient, just for testing
327  // use simple multiplications and additions for production code in calculating dRdx,y,z
328  // for dS'*R', with dS the incremental change
329  dRdx = dRidx * w2n.block<3,3>(0,0);
330  dRdy = dRidy * w2n.block<3,3>(0,0);
331  dRdz = dRidz * w2n.block<3,3>(0,0);
332  }
Matrix3D dRdy
Definition: types_icp.h:278
static Matrix3D dRidx
Definition: types_icp.h:360
static Matrix3D dRidy
Definition: types_icp.h:361
static Matrix3D dRidz
Definition: types_icp.h:362
Eigen::Matrix< double, 3, 4, Eigen::ColMajor > w2n
Definition: types_icp.h:273
Matrix3D dRdz
Definition: types_icp.h:278
Matrix3D dRdx
Definition: types_icp.h:278
static void g2o::VertexSCam::setKcam ( double  fx,
double  fy,
double  cx,
double  cy,
double  tx 
)
inlinestatic

Definition at line 302 of file types_icp.h.

Referenced by main().

303  {
304  Kcam.setZero();
305  Kcam(0,0) = fx;
306  Kcam(1,1) = fy;
307  Kcam(0,2) = cx;
308  Kcam(1,2) = cy;
309  Kcam(2,2) = 1.0;
310  baseline = tx;
311  }
static Matrix3D Kcam
Definition: types_icp.h:269
static double baseline
Definition: types_icp.h:270
void g2o::VertexSCam::setProjection ( )
inline

Definition at line 321 of file types_icp.h.

321 { w2i = Kcam * w2n; }
Eigen::Matrix< double, 3, 4, Eigen::ColMajor > w2i
Definition: types_icp.h:274
static Matrix3D Kcam
Definition: types_icp.h:269
Eigen::Matrix< double, 3, 4, Eigen::ColMajor > w2n
Definition: types_icp.h:273
void g2o::VertexSCam::setTransform ( )
inline

Definition at line 314 of file types_icp.h.

314  {
315  w2n = estimate().inverse().matrix().block<3,4>(0, 0);
316  //transformW2F(w2n,estimate().translation(), estimate().rotation());
317  }
Eigen::Matrix< double, 3, 4, Eigen::ColMajor > w2n
Definition: types_icp.h:273
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
static void g2o::VertexSCam::transformF2W ( Eigen::Matrix< double, 3, 4, Eigen::ColMajor > &  m,
const Vector3D trans,
const Eigen::Quaterniond &  qrot 
)
inlinestatic

Definition at line 293 of file types_icp.h.

296  {
297  m.block<3,3>(0,0) = qrot.toRotationMatrix();
298  m.col(3) = trans;
299  }
static void g2o::VertexSCam::transformW2F ( Eigen::Matrix< double, 3, 4, Eigen::ColMajor > &  m,
const Vector3D trans,
const Eigen::Quaterniond &  qrot 
)
inlinestatic

Definition at line 281 of file types_icp.h.

284  {
285  m.block<3,3>(0,0) = qrot.toRotationMatrix().transpose();
286  m.col(3).setZero(); // make sure there's no translation
287  Vector4D tt;
288  tt.head(3) = trans;
289  tt[3] = 1.0;
290  m.col(3) = -m*tt;
291  }
Eigen::Matrix< double, 4, 1, Eigen::ColMajor > Vector4D
Definition: eigen_types.h:47
bool g2o::VertexSCam::write ( std::ostream &  os) const
virtual

write the vertex to a stream

Reimplemented from g2o::VertexSE3.

Definition at line 334 of file types_icp.cpp.

335  { return false; }

Member Data Documentation

double g2o::VertexSCam::baseline
static

Definition at line 270 of file types_icp.h.

Referenced by g2o::Edge_XYZ_VSC::Edge_XYZ_VSC().

Matrix3D g2o::VertexSCam::dRdx

Definition at line 278 of file types_icp.h.

Referenced by g2o::Edge_XYZ_VSC::Edge_XYZ_VSC().

Matrix3D g2o::VertexSCam::dRdy

Definition at line 278 of file types_icp.h.

Referenced by g2o::Edge_XYZ_VSC::Edge_XYZ_VSC().

Matrix3D g2o::VertexSCam::dRdz

Definition at line 278 of file types_icp.h.

Referenced by g2o::Edge_XYZ_VSC::Edge_XYZ_VSC().

Matrix3D g2o::VertexSCam::dRidx
static

Definition at line 360 of file types_icp.h.

Matrix3D g2o::VertexSCam::dRidy
static

Definition at line 361 of file types_icp.h.

Matrix3D g2o::VertexSCam::dRidz
static

Definition at line 362 of file types_icp.h.

Matrix3D g2o::VertexSCam::Kcam
static

Definition at line 269 of file types_icp.h.

Referenced by g2o::Edge_XYZ_VSC::Edge_XYZ_VSC().

Eigen::Matrix<double,3,4,Eigen::ColMajor> g2o::VertexSCam::w2i

Definition at line 274 of file types_icp.h.

Eigen::Matrix<double,3,4,Eigen::ColMajor> g2o::VertexSCam::w2n

Definition at line 273 of file types_icp.h.

Referenced by g2o::Edge_XYZ_VSC::Edge_XYZ_VSC().


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