sba::Node Class Reference

NODE holds graph nodes corresponding to frames, for use in sparse bundle adjustment. Each node has a 6DOF pose, encoded as a translation vector and rotation unit quaternion (Eigen classes). These represent the pose of the node in the world frame. More...

#include <node.h>

List of all members.

Public Member Functions

void normRot ()
 Normalize quaternion to unit. Problem with global derivatives near w=0, solved by a hack for now.
void normRotLocal ()
 Normalize quaternion to unit, without w=0 considerations.
void project2im (Eigen::Vector2d &pi, const Point &p) const
void projectMono (const Point &pt, Eigen::Vector3d &proj)
 Project a 3D point into the image frame as a monocular point.
void projectStereo (const Point &pt, Eigen::Vector3d &proj)
 Project a 3D point into the image frame as a stereo point.
void setDr (bool local=false)
 Set angle derivates.
void setDri ()
 Set local angle derivatives.
void setKcam (const fc::CamParams &cp)
 Sets the Kcam and baseline matrices from frame_common::CamParams.
void setProjection ()
void setTransform ()
 Sets the transform matrices of the node.

Static Public Member Functions

static void initDr ()
 Sets up constant matrices for derivatives.

Public Attributes

double baseline
 baseline for stereo
Eigen::Matrix< double, 3, 3 > dRdx
 Derivatives of the rotation matrix transpose wrt quaternion xyz, used for calculating Jacobian wrt pose of a projection.
Eigen::Matrix< double, 3, 3 > dRdy
Eigen::Matrix< double, 3, 3 > dRdz
bool isFixed
 For SBA, is this camera fixed or free?
Eigen::Matrix< double, 3, 3 > Kcam
 Projection to frame image coordinates. pre-multiply by the frame camera matrix.
Eigen::Quaternion< double > oldqrot
 Previous quaternion rotation, saved for downdating within LM.
Eigen::Matrix< double, 4, 1 > oldtrans
 Previous translation, saved for downdating within LM.
Eigen::Quaternion< double > qrot
 Rotation of the node expressed as a Quaternion.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Eigen::Matrix< double, 4, 1 > 
trans
 Translation in homogeneous coordinates, last element is 1.0.
Eigen::Matrix< double, 3, 4 > w2i
 The transform from world to image coordinates.
Eigen::Matrix< double, 3, 4 > w2n
 Resultant transform from world to node coordinates.

Static Public Attributes

static Eigen::Matrix3d dRidx
 Constant matrices for derivatives.
static Eigen::Matrix3d dRidy
static Eigen::Matrix3d dRidz

Detailed Description

NODE holds graph nodes corresponding to frames, for use in sparse bundle adjustment. Each node has a 6DOF pose, encoded as a translation vector and rotation unit quaternion (Eigen classes). These represent the pose of the node in the world frame.

The pose generates a 3x4 homogenous transform, taking a point in world coordinates into the node coordinates.

Additionally a 3x4 homogenous transform is composed from the pose transform and a projection transform to the frame image coordinates.

Projections from points to features are in a list. There should also be a reverse index from features to projections and points, so that matched features can tie in to points.

Definition at line 63 of file node.h.


Member Function Documentation

void sba::Node::initDr (  )  [static]

Sets up constant matrices for derivatives.

Definition at line 23 of file node.cpp.

void sba::Node::normRot (  ) 

Normalize quaternion to unit. Problem with global derivatives near w=0, solved by a hack for now.

Definition at line 37 of file node.cpp.

void sba::Node::normRotLocal (  ) 

Normalize quaternion to unit, without w=0 considerations.

Definition at line 122 of file node.cpp.

void sba::Node::project2im ( Eigen::Vector2d &  pi,
const Point p 
) const [inline]

Project a point into image coordinates.

Parameters:
pi The u, v projection of the point into image coordinates.
p The 3D point in world coordinates to be projected.

Definition at line 116 of file node.h.

void sba::Node::projectMono ( const Point pt,
Eigen::Vector3d &  proj 
)

Project a 3D point into the image frame as a monocular point.

Definition at line 134 of file node.cpp.

void sba::Node::projectStereo ( const Point pt,
Eigen::Vector3d &  proj 
)

Project a 3D point into the image frame as a stereo point.

Definition at line 142 of file node.cpp.

void sba::Node::setDr ( bool  local = false  ) 

Set angle derivates.

Definition at line 56 of file node.cpp.

void sba::Node::setDri (  ) 

Set local angle derivatives.

Definition at line 14 of file node.cpp.

void sba::Node::setKcam ( const fc::CamParams cp  )  [inline]

Sets the Kcam and baseline matrices from frame_common::CamParams.

Parameters:
cp The camera parameters from camera calibration.

Definition at line 98 of file node.h.

void sba::Node::setProjection (  )  [inline]

Set up world-to-image projection matrix (w2i), assumes camera parameters are filled.

Definition at line 121 of file node.h.

void sba::Node::setTransform (  ) 

Sets the transform matrices of the node.

Definition at line 8 of file node.cpp.


Member Data Documentation

baseline for stereo

Definition at line 93 of file node.h.

Eigen::Matrix<double,3,3> sba::Node::dRdx

Derivatives of the rotation matrix transpose wrt quaternion xyz, used for calculating Jacobian wrt pose of a projection.

Definition at line 126 of file node.h.

Eigen::Matrix<double,3,3> sba::Node::dRdy

Definition at line 126 of file node.h.

Eigen::Matrix<double,3,3> sba::Node::dRdz

Definition at line 126 of file node.h.

Eigen::Matrix3d sba::Node::dRidx [static]

Constant matrices for derivatives.

Definition at line 129 of file node.h.

Eigen::Matrix3d sba::Node::dRidy [static]

Definition at line 129 of file node.h.

Eigen::Matrix3d sba::Node::dRidz [static]

Definition at line 129 of file node.h.

For SBA, is this camera fixed or free?

Definition at line 141 of file node.h.

Eigen::Matrix<double,3,3> sba::Node::Kcam

Projection to frame image coordinates. pre-multiply by the frame camera matrix.

Definition at line 92 of file node.h.

Eigen::Quaternion<double> sba::Node::oldqrot

Previous quaternion rotation, saved for downdating within LM.

Definition at line 147 of file node.h.

Eigen::Matrix<double,4,1> sba::Node::oldtrans

Previous translation, saved for downdating within LM.

Definition at line 144 of file node.h.

Eigen::Quaternion<double> sba::Node::qrot

Rotation of the node expressed as a Quaternion.

Definition at line 70 of file node.h.

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix<double,4,1> sba::Node::trans

Translation in homogeneous coordinates, last element is 1.0.

Definition at line 69 of file node.h.

Eigen::Matrix<double,3,4> sba::Node::w2i

The transform from world to image coordinates.

Definition at line 111 of file node.h.

Eigen::Matrix<double,3,4> sba::Node::w2n

Resultant transform from world to node coordinates.

Definition at line 80 of file node.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Defines


sba
Author(s): Kurt Konolige, Helen Oleynikova
autogenerated on Fri Jan 11 09:12:12 2013