add resetIntegrationAndSetBias to wrapper
parent
082604b44f
commit
b11b184f22
4
gtsam.h
4
gtsam.h
|
@ -2913,6 +2913,8 @@ class PreintegratedImuMeasurements {
|
||||||
void integrateMeasurement(Vector measuredAcc, Vector measuredOmega,
|
void integrateMeasurement(Vector measuredAcc, Vector measuredOmega,
|
||||||
double deltaT);
|
double deltaT);
|
||||||
void resetIntegration();
|
void resetIntegration();
|
||||||
|
void resetIntegrationAndSetBias(const gtsam::imuBias::ConstantBias& biasHat);
|
||||||
|
|
||||||
Matrix preintMeasCov() const;
|
Matrix preintMeasCov() const;
|
||||||
double deltaTij() const;
|
double deltaTij() const;
|
||||||
gtsam::Rot3 deltaRij() const;
|
gtsam::Rot3 deltaRij() const;
|
||||||
|
@ -2972,6 +2974,8 @@ class PreintegratedCombinedMeasurements {
|
||||||
void integrateMeasurement(Vector measuredAcc, Vector measuredOmega,
|
void integrateMeasurement(Vector measuredAcc, Vector measuredOmega,
|
||||||
double deltaT);
|
double deltaT);
|
||||||
void resetIntegration();
|
void resetIntegration();
|
||||||
|
void resetIntegrationAndSetBias(const gtsam::imuBias::ConstantBias& biasHat);
|
||||||
|
|
||||||
Matrix preintMeasCov() const;
|
Matrix preintMeasCov() const;
|
||||||
double deltaTij() const;
|
double deltaTij() const;
|
||||||
gtsam::Rot3 deltaRij() const;
|
gtsam::Rot3 deltaRij() const;
|
||||||
|
|
Loading…
Reference in New Issue