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);
    90      double calcErr(
const Node &nd, 
const Point &pt, 
double huber = 0.0);
    94       double getErrSquaredNorm();
   124       Eigen::Matrix<double,6,3> 
Tpc;
   131       const static double qScale = 1.0;
   162       void setCovariance(
const Eigen::Matrix3d &covar);
   165       void clearCovariance();
   176       double calcErrMono_(
const Node &nd, 
const Point &pt, 
double huber);
   179       double calcErrStereo_(
const Node &nd, 
const Point &pt, 
double huber);
 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. 
std::map< const int, Proj, std::less< int >, Eigen::aligned_allocator< Proj > > ProjMap
Point point
An Eigen 4-vector containing the <x, y, z, w> coordinates of the point associated with the track...
Eigen::Matrix< double, 6, 6 > Hcc
Camera-to-camera Hessian (JcT*Jc) 
bool useCovar
Use a covariance matrix? 
Eigen::Matrix< double, 3, 3 > Hpp
Point-to-point Hessian (JpT*Jp). 
Eigen::Vector3d err
Reprojection error. 
Eigen::Matrix< double, 3, 1 > Bp
The B matrix with respect to points (JpT*Err) 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW JacobProds()
int plane_point_index
Point-plane match point index in SBA. 
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. 
int plane_node_index
Point-plane node index in SBA. 
Eigen::Matrix< double, 6, 3 > Tpc
Eigen::Matrix< double, 6, 1 > JcTE
Another matrix with respect to cameras (JcT*Err) 
bool stereo
Whether the projection is Stereo (True) or Monocular (False). 
ProjMap projections
A map of all the projections of the point with camera index as key, based off an STL map...
Proj holds a projection measurement of a point onto a frame. They are a repository for the link betwe...
int ndi
Node index, the camera node for this projection. 
Eigen::Vector3d plane_point
Point for point-plane projections. 
bool isValid
valid or not (could be out of bounds) 
Eigen::Vector3d kp
Keypoint, u,v,u-d vector. 
JacobProds * jp
Jacobian products. 
bool pointPlane
Whether this is a point-plane match (true) or a point-point match (false). 
Eigen::Vector4d Point
Point holds 3D points using in world coordinates. Currently we just represent these as 4-vectors...
Eigen::Matrix< double, 3, 3 > covarmat
Covariance matrix for cost calculation. 
Eigen::Vector3d plane_normal
Normal for point-plane projections.