27 #ifndef G2O_BASE_MULTI_EDGE_H 28 #define G2O_BASE_MULTI_EDGE_H 34 #include <Eigen/StdVector> 38 #include "../../config.h" 42 using namespace Eigen;
50 template <
int D,
typename E>
69 typedef Eigen::Map<MatrixXd, MatrixXd::Flags & AlignedBit ? Aligned : Unaligned >
HessianBlockType;
81 virtual void linearizeOplus();
83 virtual void resize(
size_t size);
85 virtual bool allVerticesFixed()
const;
87 virtual void constructQuadraticForm() ;
89 virtual void mapHessianMemory(
double*
d,
int i,
int j,
bool rowMajor);
103 void computeQuadraticForm(
const InformationType& omega,
const ErrorVector& weightedError);
106 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
bool transposed
the block has to be transposed
std::vector< HessianHelper > _hessian
std::vector< JacobianType, aligned_allocator< JacobianType > > _jacobianOplus
jacobians of the edge (w.r.t. oplus)
MatrixXd::MapType JacobianType
BaseEdge< D, E >::Measurement Measurement
Matrix< double, D, 1 > ErrorVector
BaseEdge< D, E >::ErrorVector ErrorVector
base class to represent an edge connecting an arbitrary number of nodes
Eigen::Map< MatrixXd > matrix
the mapped memory
helper for mapping the Hessian memory of the upper triangular block
BaseEdge< D, E >::InformationType InformationType
Eigen::Map< MatrixXd, MatrixXd::Flags &AlignedBit?Aligned:Unaligned > HessianBlockType
provide memory workspace for computing the Jacobians
Matrix< double, D, D > InformationType