Fixed building wrapper.

release/4.3a0
dellaert 2014-11-24 20:14:56 +01:00
parent cacb180a1c
commit 867acbef6c
2 changed files with 5 additions and 5 deletions

View File

@ -2438,8 +2438,8 @@ virtual class ImuFactor : gtsam::NonlinearFactor {
#include <gtsam/navigation/AHRSFactor.h>
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;
};

View File

@ -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