sba::Proj Class Reference

Proj holds a projection measurement of a point onto a frame. They are a repository for the link between the frame and the point, with auxillary info such as Jacobians. More...

#include <proj.h>

List of all members.

Public Member Functions

double calcErr (const Node &nd, const Point &pt, double huber=0.0)
 Calculates re-projection error and stores it in err.
void clearCovariance ()
 Clear the covariance matrix and no longer use it.
double getErrNorm ()
 Get the correct norm of the error, depending on whether the projection is monocular or stereo.
double getErrSquaredNorm ()
 Get the correct squared norm of the error, depending on whether the projection is monocular or stereo.
 Proj ()
 Default constructor. Initializes to default values, kp = <0 0 0> and ndi = <0>. Also sets the projection to be invalid.
 Proj (int ci, Eigen::Vector2d &q)
 Monocular constructor. To construct a stereo projection, use other constructor. NOTE: sets the projection to be valid.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Proj (int ci, Eigen::Vector3d &q, bool stereo=true)
 General & stereo constructor. To construct a monocular projection, either use stereo = false or the other constructor. NOTE: sets the projection to be valid.
void setCovariance (const Eigen::Matrix3d &covar)
 Set the covariance matrix to use for cost calculation. Without the covariance matrix, cost is calculated by: cost = ||err|| With a covariance matrix, the cost is calculated by: cost = (err)T*covar*(err).
void setJacobians (const Node &nd, const Point &pt, JacobProds *jpp)
 Sets the jacobians and hessians for the projection to use for SBA.

Public Attributes

Eigen::Matrix< double, 3, 3 > covarmat
 Covariance matrix for cost calculation.
Eigen::Vector3d err
 Reprojection error.
bool isValid
 valid or not (could be out of bounds)
JacobProdsjp
 Jacobian products.
Eigen::Vector3d kp
 Keypoint, u,v,u-d vector.
int ndi
 Node index, the camera node for this projection.
Eigen::Vector3d plane_local_normal
 Original normal in plane_node_index coordinate's frame.
int plane_node_index
 Point-plane node index in SBA.
Eigen::Vector3d plane_normal
 Normal for point-plane projections.
Eigen::Vector3d plane_point
 Point for point-plane projections.
int plane_point_index
 Point-plane match point index in SBA.
bool pointPlane
 Whether this is a point-plane match (true) or a point-point match (false).
bool stereo
 Whether the projection is Stereo (True) or Monocular (False).
Eigen::Matrix< double, 6, 3 > Tpc
bool useCovar
 Use a covariance matrix?

Static Public Attributes

static const double qScale = 1.0

Protected Member Functions

double calcErrMono_ (const Node &nd, const Point &pt, double huber)
 Calculate error function for stereo.
double calcErrStereo_ (const Node &nd, const Point &pt, double huber)
 Calculate error function for stereo.
void setJacobiansMono_ (const Node &nd, const Point &pt, JacobProds *jpp)
 Set monocular jacobians/hessians.
void setJacobiansStereo_ (const Node &nd, const Point &pt, JacobProds *jpp)
 Set stereo jacobians/hessians.

Detailed Description

Proj holds a projection measurement of a point onto a frame. They are a repository for the link between the frame and the point, with auxillary info such as Jacobians.

Definition at line 55 of file proj.h.


Constructor & Destructor Documentation

sba::Proj::Proj ( int  ci,
Eigen::Vector3d &  q,
bool  stereo = true 
)

General & stereo constructor. To construct a monocular projection, either use stereo = false or the other constructor. NOTE: sets the projection to be valid.

Definition at line 5 of file proj.cpp.

sba::Proj::Proj ( int  ci,
Eigen::Vector2d &  q 
)

Monocular constructor. To construct a stereo projection, use other constructor. NOTE: sets the projection to be valid.

Definition at line 9 of file proj.cpp.

sba::Proj::Proj (  ) 

Default constructor. Initializes to default values, kp = <0 0 0> and ndi = <0>. Also sets the projection to be invalid.

Definition at line 13 of file proj.cpp.


Member Function Documentation

double sba::Proj::calcErr ( const Node nd,
const Point pt,
double  huber = 0.0 
)

Calculates re-projection error and stores it in err.

Definition at line 25 of file proj.cpp.

double sba::Proj::calcErrMono_ ( const Node nd,
const Point pt,
double  huber 
) [protected]

Calculate error function for stereo.

Definition at line 143 of file proj.cpp.

double sba::Proj::calcErrStereo_ ( const Node nd,
const Point pt,
double  huber 
) [protected]

Calculate error function for stereo.

Definition at line 288 of file proj.cpp.

void sba::Proj::clearCovariance (  ) 

Clear the covariance matrix and no longer use it.

Definition at line 55 of file proj.cpp.

double sba::Proj::getErrNorm (  ) 

Get the correct norm of the error, depending on whether the projection is monocular or stereo.

Definition at line 33 of file proj.cpp.

double sba::Proj::getErrSquaredNorm (  ) 

Get the correct squared norm of the error, depending on whether the projection is monocular or stereo.

Definition at line 41 of file proj.cpp.

void sba::Proj::setCovariance ( const Eigen::Matrix3d &  covar  ) 

Set the covariance matrix to use for cost calculation. Without the covariance matrix, cost is calculated by: cost = ||err|| With a covariance matrix, the cost is calculated by: cost = (err)T*covar*(err).

Definition at line 49 of file proj.cpp.

void sba::Proj::setJacobians ( const Node nd,
const Point pt,
JacobProds jpp 
)

Sets the jacobians and hessians for the projection to use for SBA.

Monocular:

dpc/dq = dR'/dq [pw-t], in homogeneous form, with q a quaternion param dpc/dx = -R' * [1 0 0]', in homogeneous form, with x a translation param d(px/pz)/du = [ pz dpx/du - px dpz/du ] / pz^2, works for all variables

Stereo: pc = R'[pw-t] => left cam pc = R'[pw-t] + [b 0 0]' => right cam px only

dpc/dq = dR'/dq [pw-t], in homogeneous form, with q a quaternion param dpc/dx = -R' * [1 0 0]', in homogeneous form, with x a translation param d(px/pz)/du = [ pz dpx/du - px dpz/du ] / pz^2, works for all variables only change for right cam is px += b

Definition at line 17 of file proj.cpp.

void sba::Proj::setJacobiansMono_ ( const Node nd,
const Point pt,
JacobProds jpp 
) [protected]

Set monocular jacobians/hessians.

jacobian with respect to frame; uses dR'/dq from Node calculation

jacobian with respect to point

Definition at line 60 of file proj.cpp.

void sba::Proj::setJacobiansStereo_ ( const Node nd,
const Point pt,
JacobProds jpp 
) [protected]

Set stereo jacobians/hessians.

jacobian with respect to point

jacobian with respect to frame; uses dR'/dq from Node calculation

Definition at line 190 of file proj.cpp.


Member Data Documentation

Eigen::Matrix<double,3,3> sba::Proj::covarmat

Covariance matrix for cost calculation.

Definition at line 135 of file proj.h.

Eigen::Vector3d sba::Proj::err

Reprojection error.

Definition at line 82 of file proj.h.

valid or not (could be out of bounds)

Definition at line 125 of file proj.h.

Jacobian products.

Definition at line 118 of file proj.h.

Eigen::Vector3d sba::Proj::kp

Keypoint, u,v,u-d vector.

Definition at line 79 of file proj.h.

Node index, the camera node for this projection.

Definition at line 76 of file proj.h.

Original normal in plane_node_index coordinate's frame.

Definition at line 153 of file proj.h.

Point-plane node index in SBA.

Definition at line 150 of file proj.h.

Eigen::Vector3d sba::Proj::plane_normal

Normal for point-plane projections.

Definition at line 141 of file proj.h.

Eigen::Vector3d sba::Proj::plane_point

Point for point-plane projections.

Definition at line 144 of file proj.h.

Point-plane match point index in SBA.

Definition at line 147 of file proj.h.

Whether this is a point-plane match (true) or a point-point match (false).

Definition at line 138 of file proj.h.

const double sba::Proj::qScale = 1.0 [static]

scaling factor for quaternion derivatives relative to translational ones; not sure if this is needed, it's close to 1.0

Definition at line 129 of file proj.h.

Whether the projection is Stereo (True) or Monocular (False).

Definition at line 85 of file proj.h.

Eigen::Matrix<double,6,3> sba::Proj::Tpc

Point-to-camera matrix (HpcT*Hpp^-1) Need to save this

Definition at line 122 of file proj.h.

Use a covariance matrix?

Definition at line 132 of file proj.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