fix matlab compile issue, by removing abstract class PreintegrationBase from wrapper declearation

release/4.3a0
Jing Dong 2016-06-02 21:04:52 -04:00
parent fb0a5489d7
commit b173057e33
1 changed files with 16 additions and 24 deletions

40
gtsam.h
View File

@ -2506,30 +2506,8 @@ virtual class PreintegrationParams : gtsam::PreintegratedRotationParams {
bool getUse2ndOrderCoriolis() const; bool getUse2ndOrderCoriolis() const;
}; };
#include <gtsam/navigation/PreintegrationBase.h>
virtual class PreintegrationBase {
// Constructors
PreintegrationBase(const gtsam::PreintegrationParams* params);
PreintegrationBase(const gtsam::PreintegrationParams* params,
const gtsam::imuBias::ConstantBias& bias);
// Testable
void print(string s) const;
bool equals(const gtsam::PreintegrationBase& expected, double tol);
double deltaTij() const;
gtsam::Rot3 deltaRij() const;
Vector deltaPij() const;
Vector deltaVij() const;
Vector biasHatVector() const;
// Standard Interface
gtsam::NavState predict(const gtsam::NavState& state_i,
const gtsam::imuBias::ConstantBias& bias) const;
};
#include <gtsam/navigation/ImuFactor.h> #include <gtsam/navigation/ImuFactor.h>
virtual class PreintegratedImuMeasurements: gtsam::PreintegrationBase { class PreintegratedImuMeasurements {
// Constructors // Constructors
PreintegratedImuMeasurements(const gtsam::PreintegrationParams* params); PreintegratedImuMeasurements(const gtsam::PreintegrationParams* params);
PreintegratedImuMeasurements(const gtsam::PreintegrationParams* params, PreintegratedImuMeasurements(const gtsam::PreintegrationParams* params,
@ -2544,6 +2522,13 @@ virtual class PreintegratedImuMeasurements: gtsam::PreintegrationBase {
double deltaT); double deltaT);
void resetIntegration(); void resetIntegration();
Matrix preintMeasCov() const; Matrix preintMeasCov() const;
double deltaTij() const;
gtsam::Rot3 deltaRij() const;
Vector deltaPij() const;
Vector deltaVij() const;
Vector biasHatVector() const;
gtsam::NavState predict(const gtsam::NavState& state_i,
const gtsam::imuBias::ConstantBias& bias) const;
}; };
virtual class ImuFactor: gtsam::NonlinearFactor { virtual class ImuFactor: gtsam::NonlinearFactor {
@ -2559,7 +2544,7 @@ virtual class ImuFactor: gtsam::NonlinearFactor {
}; };
#include <gtsam/navigation/CombinedImuFactor.h> #include <gtsam/navigation/CombinedImuFactor.h>
virtual class PreintegratedCombinedMeasurements: gtsam::PreintegrationBase { class PreintegratedCombinedMeasurements {
// Testable // Testable
void print(string s) const; void print(string s) const;
bool equals(const gtsam::PreintegratedCombinedMeasurements& expected, bool equals(const gtsam::PreintegratedCombinedMeasurements& expected,
@ -2570,6 +2555,13 @@ virtual class PreintegratedCombinedMeasurements: gtsam::PreintegrationBase {
double deltaT); double deltaT);
void resetIntegration(); void resetIntegration();
Matrix preintMeasCov() const; Matrix preintMeasCov() const;
double deltaTij() const;
gtsam::Rot3 deltaRij() const;
Vector deltaPij() const;
Vector deltaVij() const;
Vector biasHatVector() const;
gtsam::NavState predict(const gtsam::NavState& state_i,
const gtsam::imuBias::ConstantBias& bias) const;
}; };
virtual class CombinedImuFactor: gtsam::NonlinearFactor { virtual class CombinedImuFactor: gtsam::NonlinearFactor {