Merge pull request #1354 from borglab/wrap/preintegrated-ahrs
commit
691dc98762
|
|
@ -216,7 +216,13 @@ virtual class CombinedImuFactor: gtsam::NonlinearFactor {
|
|||
#include <gtsam/navigation/AHRSFactor.h>
|
||||
class PreintegratedAhrsMeasurements {
|
||||
// Standard Constructor
|
||||
PreintegratedAhrsMeasurements(Vector bias, Matrix measuredOmegaCovariance);
|
||||
PreintegratedAhrsMeasurements(const gtsam::PreintegrationParams* params,
|
||||
const Vector& biasHat);
|
||||
PreintegratedAhrsMeasurements(const gtsam::PreintegrationParams* p,
|
||||
const Vector& bias_hat, double deltaTij,
|
||||
const gtsam::Rot3& deltaRij,
|
||||
const Matrix& delRdelBiasOmega,
|
||||
const Matrix& preint_meas_cov);
|
||||
PreintegratedAhrsMeasurements(const gtsam::PreintegratedAhrsMeasurements& rhs);
|
||||
|
||||
// Testable
|
||||
|
|
|
|||
Loading…
Reference in New Issue