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)
|
JacobProds * | jp |
| 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.
|
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.