Go to the documentation of this file.
4 #ifndef EIGEN_USE_NEW_STDVECTOR
5 #define EIGEN_USE_NEW_STDVECTOR
6 #endif // EIGEN_USE_NEW_STDVECTOR
9 #include <Eigen/Geometry>
11 #include <Eigen/StdVector>
21 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
33 Eigen::Matrix<double,3,3>
Hpp;
36 Eigen::Matrix<double,3,6>
Hpc;
39 Eigen::Matrix<double,6,6>
Hcc;
42 Eigen::Matrix<double,3,1>
Bp;
45 Eigen::Matrix<double,6,1>
JcTE;
52 typedef std::map<const int, Proj, std::less<int>, Eigen::aligned_allocator<Proj> >
ProjMap;
61 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
66 Proj(
int ci, Eigen::Vector3d &q,
bool stereo =
true);
71 Proj(
int ci, Eigen::Vector2d &q);
124 Eigen::Matrix<double,6,3>
Tpc;
Eigen::Matrix< double, 3, 3 > covarmat
Covariance matrix for cost calculation.
Eigen::Vector3d plane_normal
Normal for point-plane projections.
void setJacobiansMono_(const Node &nd, const Point &pt, JacobProds *jpp)
Set monocular jacobians/hessians.
Eigen::Matrix< double, 3, 6 > Hpc
Point-to-camera Hessian (JpT*Jc)
Eigen::Vector3d plane_local_normal
Original normal in plane_node_index coordinate's frame.
Eigen::Vector4d Point
Point holds 3D points using in world coordinates. Currently we just represent these as 4-vectors,...
ProjMap projections
A map of all the projections of the point with camera index as key, based off an STL map.
void setCovariance(const Eigen::Matrix3d &covar)
Set the covariance matrix to use for cost calculation. Without the covariance matrix,...
Eigen::Matrix< double, 3, 3 > Hpp
Point-to-point Hessian (JpT*Jp).
void setJacobiansStereo_(const Node &nd, const Point &pt, JacobProds *jpp)
Set stereo jacobians/hessians.
void clearCovariance()
Clear the covariance matrix and no longer use it.
static constexpr double qScale
double calcErr(const Node &nd, const Point &pt, double huber=0.0)
Calculates re-projection error and stores it in err.
Eigen::Vector3d err
Reprojection error.
Proj()
Default constructor. Initializes to default values, kp = <0 0 0> and ndi = <0>. Also sets the project...
int plane_node_index
Point-plane node index in SBA.
Eigen::Matrix< double, 6, 6 > Hcc
Camera-to-camera Hessian (JcT*Jc)
Eigen::Matrix< double, 6, 3 > Tpc
Eigen::Matrix< double, 3, 1 > Bp
The B matrix with respect to points (JpT*Err)
void setJacobians(const Node &nd, const Point &pt, JacobProds *jpp)
Sets the jacobians and hessians for the projection to use for SBA.
bool useCovar
Use a covariance matrix?
EIGEN_MAKE_ALIGNED_OPERATOR_NEW JacobProds()
double getErrNorm()
Get the correct norm of the error, depending on whether the projection is monocular or stereo.
int plane_point_index
Point-plane match point index in SBA.
bool stereo
Whether the projection is Stereo (True) or Monocular (False).
Eigen::Vector3d plane_point
Point for point-plane projections.
std::map< const int, Proj, std::less< int >, Eigen::aligned_allocator< Proj > > ProjMap
Eigen::Matrix< double, 6, 1 > JcTE
Another matrix with respect to cameras (JcT*Err)
int ndi
Node index, the camera node for this projection.
Point point
An Eigen 4-vector containing the <x, y, z, w> coordinates of the point associated with the track.
double calcErrMono_(const Node &nd, const Point &pt, double huber)
Calculate error function for stereo.
bool pointPlane
Whether this is a point-plane match (true) or a point-point match (false).
bool isValid
valid or not (could be out of bounds)
JacobProds * jp
Jacobian products.
double getErrSquaredNorm()
Get the correct squared norm of the error, depending on whether the projection is monocular or stereo...
Track()
Default constructor for Track.
double calcErrStereo_(const Node &nd, const Point &pt, double huber)
Calculate error function for stereo.
Eigen::Vector3d kp
Keypoint, u,v,u-d vector.
NODE holds graph nodes corresponding to frames, for use in sparse bundle adjustment....
Proj holds a projection measurement of a point onto a frame. They are a repository for the link betwe...