From 867acbef6cd508bfb58ce4fbb4e7bb6b57b72eb0 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 24 Nov 2014 20:14:56 +0100 Subject: [PATCH] Fixed building wrapper. --- gtsam.h | 8 ++++---- gtsam_unstable/dynamics/FullIMUFactor.h | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/gtsam.h b/gtsam.h index 9a44c7aa2..0ceda6db5 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2438,8 +2438,8 @@ virtual class ImuFactor : gtsam::NonlinearFactor { #include class AHRSFactorPreintegratedMeasurements { // Standard Constructor - AHRSFactorPreintegratedMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredOmegaCovariance); - AHRSFactorPreintegratedMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredOmegaCovariance); + AHRSFactorPreintegratedMeasurements(Vector bias, Matrix measuredOmegaCovariance); + AHRSFactorPreintegratedMeasurements(Vector bias, Matrix measuredOmegaCovariance); AHRSFactorPreintegratedMeasurements(const gtsam::AHRSFactorPreintegratedMeasurements& rhs); // Testable @@ -2468,8 +2468,8 @@ virtual class AHRSFactor : gtsam::NonlinearFactor { // Standard Interface gtsam::AHRSFactorPreintegratedMeasurements preintegratedMeasurements() const; Vector evaluateError(const gtsam::Rot3& rot_i, const gtsam::Rot3& rot_j, - const gtsam::imuBias::ConstantBias& bias) const; - gtsam::Rot3 predict(const gtsam::Rot3& rot_i, const gtsam::imuBias::ConstantBias& bias, + Vector bias) const; + gtsam::Rot3 predict(const gtsam::Rot3& rot_i, Vector bias, const gtsam::AHRSFactorPreintegratedMeasurements& preintegratedMeasurements, Vector omegaCoriolis) const; }; diff --git a/gtsam_unstable/dynamics/FullIMUFactor.h b/gtsam_unstable/dynamics/FullIMUFactor.h index 1c35fc9b8..1c2807e7a 100644 --- a/gtsam_unstable/dynamics/FullIMUFactor.h +++ b/gtsam_unstable/dynamics/FullIMUFactor.h @@ -75,7 +75,7 @@ public: // access const Vector3& gyro() const { return gyro_; } const Vector3& accel() const { return accel_; } - Vector6 z() const { return (Vector6() << accel_, gyro_); } + Vector6 z() const { return (Vector(6) << accel_, gyro_).finished(); } /** * Error evaluation with optional derivatives - calculates