C++ example of an Equivariant filter #2103
Conversation
dellaert
left a comment
There was a problem hiding this comment.
OK, so, many comments :-)
One main organizational comment that I think will make the transition to a templated version easier:
- Put Group, State in ABC.h, no cpp file, everything inlined. Use template size_T and std:array as I suggested earlier
- In ABC_EQF.*, only put filter stuff. Can still be specific and include ABC.h, but try to extract as much ABC-specific things you can into ABC.h
- Everything else (data loading is biggest part) put in Demo file.
examples/ABC_EQF.cpp
Outdated
| * @param m Number of sensors | ||
| * Uses SelfAdjointSolver, completeOrthoganalDecomposition().pseudoInverse() | ||
| */ | ||
| EqF::EqF(const Matrix& Sigma, int n, int m) |
There was a problem hiding this comment.
To me, the argument n causes a lot of issues! In the ABC.h code I shared with you I sketched how to use a size_t template argument, ijn which case the dimensions of G and State are known at compile time. I think that's much preferred for an example=, rather than introducing variable dimenions (and hence dynamically allocated matrices) everywhere.
…n METIS CMakeLists.txt & removed variables that were not used
…nge Input class to struct, remove changes to target
32bcc3a to
e5f4978
Compare
…nctions to be inline with the state class
dellaert
left a comment
There was a problem hiding this comment.
Awesome, great progresss!
I would still simplify much more. Get rid of “create” where possible, don’t check covariance matrices, and move all things that are ABC specific (except filter) to a separate file ABC.h.
And I would template on size_t, which will simplify the code even more. Remember this is an example, so we do not need to support reading data files with varying number of calibrations.
examples/ABC_EQF.h
Outdated
| Matrix3 W() const { /// Return w as a skew symmetric matrix | ||
| return Rot3::Hat(w); | ||
| } | ||
| static Input create(const Vector3& w, const Matrix& Sigma) { /// Initialize w and Sigma |
There was a problem hiding this comment.
Still seems overkill, just use brace init, don’t check covariance
examples/ABC_EQF.h
Outdated
| Unit3 d; /// Known direction in global frame | ||
| Matrix3 Sigma; /// Covariance matrix of the measurement | ||
| int cal_idx = -1; /// Calibration index (-1 for calibrated sensor) | ||
| static Measurement create(const Unit3& y_vec, const Unit3& d_vec, /// Initialize measurement |
There was a problem hiding this comment.
Same: kill and use brace init. Covariance checking is overkill in an example (and is not very relevant when we switch to noise models)
examples/ABC_EQF.h
Outdated
|
|
||
| /// State class representing the state of the Biased Attitude System | ||
|
|
||
| class State { |
There was a problem hiding this comment.
Move to ABC.h and template on size_t
examples/ABC_EQF.h
Outdated
| * Symmetry group (SO(3) |x so(3)) x SO(3) x ... x SO(3) | ||
| * Each element of the B list is associated with a calibration state | ||
| */ | ||
| class G { |
There was a problem hiding this comment.
Move to ABC.h and template on size_t
examples/ABC_EQF.h
Outdated
| class EqF { | ||
| private: | ||
| int dof; // Degrees of freedom | ||
| int n_cal; // Number of calibration states |
There was a problem hiding this comment.
Template EqF on size_t as well.
…ordinate to exponential, separate filter and demo specific functions, rename stateAction to operator *, fix brace initialization
|
|
||
| /// Check if a vector is a unit vector | ||
|
|
||
| bool checkNorm(const Vector3& x, double tol = 1e-3); |
|
|
||
| /// Check if vector contains NaN values | ||
|
|
||
| bool hasNaN(const Vector3& vec); |
There was a problem hiding this comment.
maybe kill this too if you don;t use it
|
|
||
| /// Create a block diagonal matrix from two matrices | ||
|
|
||
| Matrix blockDiag(const Matrix& A, const Matrix& B); |
| * @return A single consolidated matrix with A in the top left and B in the | ||
| * bottom right | ||
| */ | ||
| Matrix blockDiag(const Matrix& A, const Matrix& B) { |
There was a problem hiding this comment.
decide whether this is ABC-specific, or Eqf specific. If latter, move it.
| * @param n Number of times to be repeated | ||
| * @return Block diag matrix with A repeated 'n' times | ||
| */ | ||
| Matrix repBlock(const Matrix& A, int n) { |
|
Next PR should have:
|
An implementation of the Equivariant Filter (EqF) for attitude estimation with both gyroscope bias and sensor extrinsic calibration, based on the paper: "Overcoming Bias: Equivariant Filter Design for Biased Attitude Estimation with Online Calibration" by Fornasier et al.
Uses the same dataset from the paper but implemented through built-in GTSAM functions to reproduce the results.
Authored by Darshan Rajasekaran & Jennifer Oum