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>
|
double | calcErr (const Node &nd, const Point &pt, double huber=0.0) |
| Calculates re-projection error and stores it in err. More...
|
|
void | clearCovariance () |
| Clear the covariance matrix and no longer use it. More...
|
|
double | getErrNorm () |
| Get the correct norm of the error, depending on whether the projection is monocular or stereo. More...
|
|
double | getErrSquaredNorm () |
| Get the correct squared norm of the error, depending on whether the projection is monocular or stereo. More...
|
|
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. More...
|
|
| Proj (int ci, Eigen::Vector2d &q) |
| Monocular constructor. To construct a stereo projection, use other constructor. NOTE: sets the projection to be valid. More...
|
|
| Proj () |
| Default constructor. Initializes to default values, kp = <0 0 0> and ndi = <0>. Also sets the projection to be invalid. More...
|
|
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) More...
|
|
void | setJacobians (const Node &nd, const Point &pt, JacobProds *jpp) |
| Sets the jacobians and hessians for the projection to use for SBA. More...
|
|
|
static constexpr double | qScale = 1.0 |
|
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 57 of file proj.h.
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.
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.
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.
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.
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.
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.
Eigen::Matrix<double,3,3> sba::Proj::covarmat |
Covariance matrix for cost calculation.
Definition at line 137 of file proj.h.
Eigen::Vector3d sba::Proj::err |
Reprojection error.
Definition at line 84 of file proj.h.
valid or not (could be out of bounds)
Definition at line 127 of file proj.h.
Jacobian products.
Definition at line 120 of file proj.h.
Eigen::Vector3d sba::Proj::kp |
Keypoint, u,v,u-d vector.
Definition at line 81 of file proj.h.
Node index, the camera node for this projection.
Definition at line 78 of file proj.h.
Eigen::Vector3d sba::Proj::plane_local_normal |
int sba::Proj::plane_node_index |
Point-plane node index in SBA.
Definition at line 152 of file proj.h.
Eigen::Vector3d sba::Proj::plane_normal |
Normal for point-plane projections.
Definition at line 143 of file proj.h.
Eigen::Vector3d sba::Proj::plane_point |
Point for point-plane projections.
Definition at line 146 of file proj.h.
int sba::Proj::plane_point_index |
Point-plane match point index in SBA.
Definition at line 149 of file proj.h.
bool sba::Proj::pointPlane |
Whether this is a point-plane match (true) or a point-point match (false).
Definition at line 140 of file proj.h.
constexpr 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 131 of file proj.h.
Whether the projection is Stereo (True) or Monocular (False).
Definition at line 87 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 124 of file proj.h.
Use a covariance matrix?
Definition at line 134 of file proj.h.
The documentation for this class was generated from the following files: