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

Added non-default const. for AHRS pre-int. and params #93

Merged
merged 5 commits into from
Jul 31, 2019
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
22 changes: 22 additions & 0 deletions gtsam/navigation/AHRSFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,28 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation
resetIntegration();
}

/**
* Non-Default constructor, initialize with measurements
* @param p: Parameters for AHRS pre-integration
* @param bias_hat: Current estimate of acceleration and rotation rate biases
* @param deltaTij: Delta time in pre-integration
* @param deltaRij: Delta rotation in pre-integration
* @param delRdelBiasOmega: Jacobian of rotation wrt. to gyro bias
* @param preint_meas_cov: Pre-integration covariance
*/
PreintegratedAhrsMeasurements(
const boost::shared_ptr<Params>& p,
const Vector3& bias_hat,
double deltaTij,
const Rot3& deltaRij,
const Matrix3& delRdelBiasOmega,
const Matrix3& preint_meas_cov) :
biasHat_(bias_hat),
PreintegratedRotation(p, deltaTij, deltaRij, delRdelBiasOmega),
preintMeasCov_(preint_meas_cov) {
p_->gyroscopeCovariance = p->getGyroscopeCovariance();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why ?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Redundant indeed, base class already copies params as p_(p)

}

const Params& p() const { return *boost::static_pointer_cast<const Params>(p_);}
const Vector3& biasHat() const { return biasHat_; }
const Matrix3& preintMeasCov() const { return preintMeasCov_; }
Expand Down
7 changes: 7 additions & 0 deletions gtsam/navigation/PreintegratedRotation.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,13 @@ struct GTSAM_EXPORT PreintegratedRotationParams {

PreintegratedRotationParams() : gyroscopeCovariance(I_3x3) {}

PreintegratedRotationParams(Matrix3 gyroscope_covariance,
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

const Matrix3&

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done

boost::optional<Vector3> omega_coriolis)
: gyroscopeCovariance(gyroscope_covariance) {
if (omega_coriolis)
omegaCoriolis.reset(omega_coriolis.get());
}

virtual ~PreintegratedRotationParams() {}

virtual void print(const std::string& s) const;
Expand Down
29 changes: 29 additions & 0 deletions gtsam/navigation/tests/testAHRSFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,35 @@ TEST( AHRSFactor, PreintegratedMeasurements ) {
DOUBLES_EQUAL(expectedDeltaT2, actual2.deltaTij(), 1e-6);
}

//******************************************************************************
TEST( AHRSFactor, PreintegratedAhrsMeasurementsConstructor ) {
// Linearization point
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

obsolete comment?

Copy link
Contributor

@ToniRV ToniRV Jul 30, 2019

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Removed, got copied from above test I think.

Matrix3 gyroscopeCovariance = Matrix3::Ones()*0.4;
Vector3 omegaCoriolis(0.1, 0.5, 0.9);
PreintegratedRotationParams params(gyroscopeCovariance, omegaCoriolis);
Vector3 bias(1.0,2.0,3.0); ///< Current estimate of angular rate bias
Rot3 deltaRij(Rot3::RzRyRx(M_PI / 12.0, M_PI / 6.0, M_PI / 4.0));
double deltaTij = 0.02;
Matrix3 delRdelBiasOmega = Matrix3::Ones()*0.5;
Matrix3 preintMeasCov = Matrix3::Ones()*0.2;
gtsam::PreintegratedAhrsMeasurements test_pim(
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

using gtsam and std in test files.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

test_pim -> actualPim, or just pim

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

changed to actualPim

boost::make_shared<gtsam::PreintegratedRotationParams>(params),
bias,
deltaTij,
deltaRij,
delRdelBiasOmega,
preintMeasCov);
EXPECT(assert_equal(gyroscopeCovariance,
test_pim.p().getGyroscopeCovariance(), 1e-6));
EXPECT(assert_equal(omegaCoriolis,
test_pim.p().getOmegaCoriolis().get(), 1e-6));
EXPECT(assert_equal(bias, test_pim.biasHat(), 1e-6));
DOUBLES_EQUAL(deltaTij, test_pim.deltaTij(), 1e-6);
EXPECT(assert_equal(deltaRij, Rot3(test_pim.deltaRij()), 1e-6));
EXPECT(assert_equal(delRdelBiasOmega, test_pim.delRdelBiasOmega(), 1e-6));
EXPECT(assert_equal(preintMeasCov, test_pim.preintMeasCov(), 1e-6));
}

/* ************************************************************************* */
TEST(AHRSFactor, Error) {
// Linearization point
Expand Down