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>
Public Member Functions | |
void | normRot () |
Normalize quaternion to unit. Problem with global derivatives near w=0, solved by a hack for now. More... | |
void | normRotLocal () |
Normalize quaternion to unit, without w=0 considerations. More... | |
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. More... | |
void | projectStereo (const Point &pt, Eigen::Vector3d &proj) |
Project a 3D point into the image frame as a stereo point. More... | |
void | setDr (bool local=false) |
Set angle derivates. More... | |
void | setDri () |
Set local angle derivatives. More... | |
void | setKcam (const fc::CamParams &cp) |
Sets the Kcam and baseline matrices from frame_common::CamParams. More... | |
void | setProjection () |
void | setTransform () |
Sets the transform matrices of the node. More... | |
Static Public Member Functions | |
static void | initDr () |
Sets up constant matrices for derivatives. More... | |
Public Attributes | |
double | baseline |
baseline for stereo More... | |
Eigen::Matrix< double, 3, 3 > | dRdx |
Derivatives of the rotation matrix transpose wrt quaternion xyz, used for calculating Jacobian wrt pose of a projection. More... | |
Eigen::Matrix< double, 3, 3 > | dRdy |
Eigen::Matrix< double, 3, 3 > | dRdz |
bool | isFixed |
For SBA, is this camera fixed or free? More... | |
Eigen::Matrix< double, 3, 3 > | Kcam |
Projection to frame image coordinates. pre-multiply by the frame camera matrix. More... | |
Eigen::Quaternion< double > | oldqrot |
Previous quaternion rotation, saved for downdating within LM. More... | |
Eigen::Matrix< double, 4, 1 > | oldtrans |
Previous translation, saved for downdating within LM. More... | |
Eigen::Quaternion< double > | qrot |
Rotation of the node expressed as a Quaternion. More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix< double, 4, 1 > | trans |
Translation in homogeneous coordinates, last element is 1.0. More... | |
Eigen::Matrix< double, 3, 4 > | w2i |
The transform from world to image coordinates. More... | |
Eigen::Matrix< double, 3, 4 > | w2n |
Resultant transform from world to node coordinates. More... | |
Static Public Attributes | |
static Eigen::Matrix3d | dRidx |
Constant matrices for derivatives. More... | |
static Eigen::Matrix3d | dRidy |
static Eigen::Matrix3d | dRidz |
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.
|
static |
void sba::Node::normRot | ( | ) |
void sba::Node::normRotLocal | ( | ) |
|
inline |
void sba::Node::projectMono | ( | const Point & | pt, |
Eigen::Vector3d & | proj | ||
) |
void sba::Node::projectStereo | ( | const Point & | pt, |
Eigen::Vector3d & | proj | ||
) |
void sba::Node::setDr | ( | bool | local = false | ) |
|
inline |
Sets the Kcam and baseline matrices from frame_common::CamParams.
cp | The camera parameters from camera calibration. |
|
inline |
void sba::Node::setTransform | ( | ) |
Eigen::Matrix<double,3,3> sba::Node::dRdx |
|
static |
bool sba::Node::isFixed |
Eigen::Matrix<double,3,3> sba::Node::Kcam |
Eigen::Quaternion<double> sba::Node::oldqrot |
Eigen::Matrix<double,4,1> sba::Node::oldtrans |
Eigen::Quaternion<double> sba::Node::qrot |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Matrix<double,4,1> sba::Node::trans |
Eigen::Matrix<double,3,4> sba::Node::w2i |
Eigen::Matrix<double,3,4> sba::Node::w2n |