#include "g2o/core/sparse_optimizer.h"
#include "g2o/types/slam3d/edge_se3.h"
#include "scoped_timer.h"
Go to the source code of this file.
Typedefs | |
typedef std::set < g2o::HyperGraph::Edge * > | EdgeSet |
typedef std::set < g2o::HyperGraph::Edge * > ::iterator | EdgeSetIt |
typedef Eigen::Matrix< double, 6, 6 > | InfoMatType |
typedef Eigen::Matrix< double, 6, Eigen::Dynamic > | Matrix6Xd |
typedef Eigen::Matrix< double, 6, 1 > | Vector6d |
Functions | |
InfoMatType | computeEmpiricalInformationMatrix (const Matrix6Xd &measurements, const Matrix6Xd &errors, const Vector6d ¤tMeasurement, const Vector6d &stdDeviation) |
template<class EDGETYPE > | |
void | edgesToErrorMatrix (const EdgeSet &edges, Matrix6Xd &output) |
template<class EDGETYPE > | |
void | edgesToMeasurementMatrix (const EdgeSet &edges, Matrix6Xd &output) |
Convert Isometry to vector6d of which the last 3 parameters represent the. |
Definition at line 10 of file covariance_estimation.h.
Definition at line 11 of file covariance_estimation.h.
typedef Eigen::Matrix<double,6,6> InfoMatType |
Definition at line 7 of file covariance_estimation.h.
typedef Eigen::Matrix<double,6,Eigen::Dynamic> Matrix6Xd |
Definition at line 9 of file covariance_estimation.h.
typedef Eigen::Matrix<double,6,1> Vector6d |
Definition at line 8 of file covariance_estimation.h.
InfoMatType computeEmpiricalInformationMatrix | ( | const Matrix6Xd & | measurements, |
const Matrix6Xd & | errors, | ||
const Vector6d & | currentMeasurement, | ||
const Vector6d & | stdDeviation | ||
) |
FIXME: Why are the results worse than without inverse, which is wrong?
Definition at line 41 of file covariance_estimation.cpp.
void edgesToErrorMatrix | ( | const EdgeSet & | edges, |
Matrix6Xd & | output | ||
) |
Definition at line 52 of file covariance_estimation.h.
void edgesToMeasurementMatrix | ( | const EdgeSet & | edges, |
Matrix6Xd & | output | ||
) |
Convert Isometry to vector6d of which the last 3 parameters represent the.
Convert Isometry to vector6d of which the last 3 parameters represent the
Definition at line 32 of file covariance_estimation.h.