15#include <unordered_set>
17#include "types/fptypes.hpp"
18#include "msceqf/options/msceqf_options.hpp"
19#include "msceqf/filter/updater/updater_helper.hpp"
20#include "msceqf/system/system.hpp"
21#include "vision/track.hpp"
58 [[nodiscard]]
bool linearTriangulation(
const MSCEqFState& X,
const Track& track,
const SE3& A_E, Vector3& A_f)
const;
73 void nonlinearTriangulation(
const MSCEqFState& X,
const Track& track,
const SE3& A_E, Vector3& A_f)
const;
85 void nonlinearTriangulationResidualJacobian(
86 const MSCEqFState& X,
const Track& track,
const SE3& A_E,
const Vector3& A_f, VectorX& res, MatrixX& J)
const;
96 void UpdateMSCEqF(
MSCEqFState& X,
const MatrixX& C,
const VectorX& delta,
const MatrixX& R)
const;
103 ProjectionHelperUniquePtr ph_;
105 std::map<uint, fp> chi2_table_;
109 std::vector<uint> update_ids_;
this class represent the state of the MSCEqF. This includes the state of the lifted system (element o...
Definition state.hpp:30
The SystemState class represent the state of the system posed on the Homogenous space.
Definition system.hpp:29
Updater class. This class implements the Multi State Constraint update step of the MSCEqF filter.
Definition updater.hpp:30
void mscUpdate(MSCEqFState &X, const Tracks &tracks, std::unordered_set< uint > &ids)
Perform a Multi State Constraint update.
(Cache friendly) Track struct. Define a feature (labeled via a feature id) detected/tracked at differ...
Definition track.hpp:30
Definition msceqf_options.hpp:122