Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Change from biasAccOmegaInt to biasAccOmegaInit #1709

Open
wants to merge 4 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion examples/CombinedImuFactorsExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ std::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
// PreintegrationCombinedMeasurements params:
p->biasAccCovariance = bias_acc_cov; // acc bias in continuous
p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous
p->biasAccOmegaInt = bias_acc_omega_init;
p->biasAccOmegaInit = bias_acc_omega_init;

return p;
}
Expand Down
2 changes: 1 addition & 1 deletion examples/ImuFactorsExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ std::shared_ptr<PreintegratedCombinedMeasurements::Params> imuParams() {
// PreintegrationCombinedMeasurements params:
p->biasAccCovariance = bias_acc_cov; // acc bias in continuous
p->biasOmegaCovariance = bias_omega_cov; // gyro bias in continuous
p->biasAccOmegaInt = bias_acc_omega_init;
p->biasAccOmegaInit = bias_acc_omega_init;

return p;
}
Expand Down
8 changes: 4 additions & 4 deletions gtsam/navigation/CombinedImuFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ void PreintegrationCombinedParams::print(const string& s) const {
<< endl;
cout << "biasOmegaCovariance:\n[\n" << biasOmegaCovariance << "\n]"
<< endl;
cout << "biasAccOmegaInt:\n[\n" << biasAccOmegaInt << "\n]"
cout << "biasAccOmegaInit:\n[\n" << biasAccOmegaInit << "\n]"
<< endl;
}

Expand All @@ -54,7 +54,7 @@ bool PreintegrationCombinedParams::equals(const PreintegratedRotationParams& oth
tol) &&
equal_with_abs_tol(biasOmegaCovariance, e->biasOmegaCovariance,
tol) &&
equal_with_abs_tol(biasAccOmegaInt, e->biasAccOmegaInt, tol);
equal_with_abs_tol(biasAccOmegaInit, e->biasAccOmegaInit, tol);
}

//------------------------------------------------------------------------------
Expand Down Expand Up @@ -84,7 +84,7 @@ void PreintegratedCombinedMeasurements::resetIntegration(
const gtsam::Matrix6& Q_init) {
// Base class method to reset the preintegrated measurements
PreintegrationType::resetIntegration();
p().biasAccOmegaInt = Q_init;
p().biasAccOmegaInit = Q_init;
preintMeasCov_.setZero();
}

Expand Down Expand Up @@ -147,7 +147,7 @@ void PreintegratedCombinedMeasurements::integrateMeasurement(
const Matrix3& aCov = p().accelerometerCovariance;
const Matrix3& wCov = p().gyroscopeCovariance;
const Matrix3& iCov = p().integrationCovariance;
const Matrix6& bInitCov = p().biasAccOmegaInt;
const Matrix6& bInitCov = p().biasAccOmegaInit;

// first order uncertainty propagation
// Optimized matrix mult: (1/dt) * G * measurementCovariance * G.transpose()
Expand Down
12 changes: 6 additions & 6 deletions gtsam/navigation/PreintegrationCombinedParams.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,22 +39,22 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams {
///< accelerometer bias random walk
Matrix3 biasOmegaCovariance; ///< continuous-time "Covariance" describing
///< gyroscope bias random walk
Matrix6 biasAccOmegaInt; ///< covariance of bias used as initial estimate.
Matrix6 biasAccOmegaInit; ///< covariance of bias used as initial estimate.

/// Default constructor makes uninitialized params struct.
/// Used for serialization.
PreintegrationCombinedParams()
: biasAccCovariance(I_3x3),
biasOmegaCovariance(I_3x3),
biasAccOmegaInt(I_6x6) {}
biasAccOmegaInit(I_6x6) {}

/// See two named constructors below for good values of n_gravity in body
/// frame
PreintegrationCombinedParams(const Vector3& n_gravity_)
: PreintegrationParams(n_gravity_),
biasAccCovariance(I_3x3),
biasOmegaCovariance(I_3x3),
biasAccOmegaInt(I_6x6) {}
biasAccOmegaInit(I_6x6) {}

// Default Params for a Z-down navigation frame, such as NED: gravity points
// along positive Z-axis
Expand All @@ -78,11 +78,11 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams {

void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance = cov; }
void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance = cov; }
void setBiasAccOmegaInit(const Matrix6& cov) { biasAccOmegaInt = cov; }
void setBiasAccOmegaInit(const Matrix6& cov) { biasAccOmegaInit = cov; }

const Matrix3& getBiasAccCovariance() const { return biasAccCovariance; }
const Matrix3& getBiasOmegaCovariance() const { return biasOmegaCovariance; }
const Matrix6& getBiasAccOmegaInit() const { return biasAccOmegaInt; }
const Matrix6& getBiasAccOmegaInit() const { return biasAccOmegaInit; }

private:
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
Expand All @@ -94,7 +94,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams {
ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationParams);
ar& BOOST_SERIALIZATION_NVP(biasAccCovariance);
ar& BOOST_SERIALIZATION_NVP(biasOmegaCovariance);
ar& BOOST_SERIALIZATION_NVP(biasAccOmegaInt);
ar& BOOST_SERIALIZATION_NVP(biasAccOmegaInit);
}
#endif

Expand Down
8 changes: 4 additions & 4 deletions gtsam/navigation/tests/testCombinedImuFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,14 +39,14 @@ namespace testing {
static std::shared_ptr<PreintegratedCombinedMeasurements::Params> Params(
const Matrix3& biasAccCovariance = Matrix3::Zero(),
const Matrix3& biasOmegaCovariance = Matrix3::Zero(),
const Matrix6& biasAccOmegaInt = Matrix6::Zero()) {
const Matrix6& biasAccOmegaInit = Matrix6::Zero()) {
auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(kGravity);
p->gyroscopeCovariance = kGyroSigma * kGyroSigma * I_3x3;
p->accelerometerCovariance = kAccelSigma * kAccelSigma * I_3x3;
p->integrationCovariance = 0.0001 * I_3x3;
p->biasAccCovariance = biasAccCovariance;
p->biasOmegaCovariance = biasOmegaCovariance;
p->biasAccOmegaInt = biasAccOmegaInt;
p->biasAccOmegaInit = biasAccOmegaInit;
return p;
}
} // namespace testing
Expand Down Expand Up @@ -349,12 +349,12 @@ TEST(CombinedImuFactor, ResetIntegration) {
// Test default method
pim.resetIntegration();
Matrix6 expected = 0.1 * I_6x6;
EXPECT(assert_equal(expected, pim.p().biasAccOmegaInt, 1e-9));
EXPECT(assert_equal(expected, pim.p().biasAccOmegaInit, 1e-9));

// Test method where Q_init is provided
Matrix6 expected_Q_init = I_6x6 * 0.001;
pim2.resetIntegration(expected_Q_init);
EXPECT(assert_equal(expected_Q_init, pim.p().biasAccOmegaInt, 1e-9));
EXPECT(assert_equal(expected_Q_init, pim.p().biasAccOmegaInit, 1e-9));
}

/* ************************************************************************* */
Expand Down
2 changes: 1 addition & 1 deletion gtsam_unstable/examples/ISAM2_SmartFactorStereo_IMU.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ struct IMUHelper {
p->biasAccCovariance = I_3x3 * pow(0.00002, 2.0); // acc bias in continuous
p->biasOmegaCovariance =
I_3x3 * pow(0.001, 2.0); // gyro bias in continuous
p->biasAccOmegaInt = Matrix::Identity(6, 6) * 1e-5;
p->biasAccOmegaInit = Matrix::Identity(6, 6) * 1e-5;

// body to IMU rotation
Rot3 iRb(0.036129, -0.998727, 0.035207,
Expand Down
4 changes: 2 additions & 2 deletions tests/testImuPreintegration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ TEST(TestImuPreintegration, LoadedSimulationData) {
double gyrNoiseSigma = 0.000208;
double gyrBiasRwSigma = 0.000004;
double integrationCovariance = 1e-8;
double biasAccOmegaInt = 1e-5;
double biasAccOmegaInit = 1e-5;

double gravity = 9.81;
double rate = 400.0; // Hz
Expand Down Expand Up @@ -76,7 +76,7 @@ TEST(TestImuPreintegration, LoadedSimulationData) {
imuPreintegratedParams->gyroscopeCovariance = I_3x3 * pow(gyrNoiseSigma, 2);
imuPreintegratedParams->biasOmegaCovariance = I_3x3 * pow(gyrBiasRwSigma, 2);
imuPreintegratedParams->integrationCovariance = I_3x3 * integrationCovariance;
imuPreintegratedParams->biasAccOmegaInt = I_6x6 * biasAccOmegaInt;
imuPreintegratedParams->biasAccOmegaInit = I_6x6 * biasAccOmegaInit;

// Initial state
Pose3 priorPose;
Expand Down