Fixed MATLAB wrapper

release/4.3a0
dellaert 2016-01-28 09:54:47 -08:00
parent 127cfdcfde
commit 8a45320ae2
2 changed files with 121 additions and 94 deletions

209
gtsam.h
View File

@ -2447,7 +2447,7 @@ namespace imuBias {
#include <gtsam/navigation/ImuBias.h> #include <gtsam/navigation/ImuBias.h>
class ConstantBias { class ConstantBias {
// Standard Constructor // Constructors
ConstantBias(); ConstantBias();
ConstantBias(Vector biasAcc, Vector biasGyro); ConstantBias(Vector biasAcc, Vector biasGyro);
@ -2479,99 +2479,120 @@ class ConstantBias {
}///\namespace imuBias }///\namespace imuBias
//#include <gtsam/navigation/ImuFactor.h> #include <gtsam/navigation/NavState.h>
//class PoseVelocityBias{ class NavState {
// PoseVelocityBias(const gtsam::Pose3& pose, Vector velocity, const gtsam::imuBias::ConstantBias& bias); // Constructors
// }; NavState();
//class PreintegratedImuMeasurements { NavState(const gtsam::Rot3& R, const gtsam::Point3& t, Vector v);
// // Standard Constructor NavState(const gtsam::Pose3& pose, Vector v);
// PreintegratedImuMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredAccCovariance,Matrix measuredOmegaCovariance, Matrix integrationErrorCovariance, bool use2ndOrderIntegration);
// PreintegratedImuMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredAccCovariance,Matrix measuredOmegaCovariance, Matrix integrationErrorCovariance); // Testable
// // PreintegratedImuMeasurements(const gtsam::PreintegratedImuMeasurements& rhs); void print(string s) const;
// bool equals(const gtsam::NavState& expected, double tol) const;
// // Testable
// void print(string s) const; // Access
// bool equals(const gtsam::PreintegratedImuMeasurements& expected, double tol); gtsam::Rot3 attitude() const;
// gtsam::Point3 position() const;
// double deltaTij() const; Vector velocity() const;
// gtsam::Rot3 deltaRij() const; gtsam::Pose3 pose() const;
// Vector deltaPij() const; };
// Vector deltaVij() const;
// Vector biasHatVector() const; #include <gtsam/navigation/PreintegrationParams.h>
// Matrix delPdelBiasAcc() const; class PreintegrationParams {
// Matrix delPdelBiasOmega() const; PreintegrationParams(Vector n_gravity);
// Matrix delVdelBiasAcc() const; // TODO(frank): add setters/getters or make this MATLAB wrapper feature
// Matrix delVdelBiasOmega() const; };
// Matrix delRdelBiasOmega() const;
// Matrix preintMeasCov() const; #include <gtsam/navigation/PreintegrationBase.h>
// virtual class PreintegrationBase {
// // Standard Interface // Constructors
// void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, double deltaT); PreintegrationBase(const gtsam::PreintegrationParams* params);
// gtsam::PoseVelocityBias predict(const gtsam::Pose3& pose_i, Vector vel_i, const gtsam::imuBias::ConstantBias& bias, PreintegrationBase(const gtsam::PreintegrationParams* params,
// Vector gravity, Vector omegaCoriolis) const; const gtsam::imuBias::ConstantBias& bias);
//};
// // Testable
//virtual class ImuFactor : gtsam::NonlinearFactor { void print(string s) const;
// ImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias, bool equals(const gtsam::PreintegrationBase& expected, double tol);
// const gtsam::PreintegratedImuMeasurements& preintegratedMeasurements, Vector gravity, Vector omegaCoriolis);
// ImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias, double deltaTij() const;
// const gtsam::PreintegratedImuMeasurements& preintegratedMeasurements, Vector gravity, Vector omegaCoriolis, gtsam::Rot3 deltaRij() const;
// const gtsam::Pose3& body_P_sensor); Vector deltaPij() const;
// // Standard Interface Vector deltaVij() const;
// gtsam::PreintegratedImuMeasurements preintegratedMeasurements() const; Vector biasHatVector() const;
//}; Matrix delPdelBiasAcc() const;
// Matrix delPdelBiasOmega() const;
//#include <gtsam/navigation/CombinedImuFactor.h> Matrix delVdelBiasAcc() const;
//class PreintegratedCombinedMeasurements { Matrix delVdelBiasOmega() const;
// // Standard Constructor Matrix delRdelBiasOmega() const;
// PreintegratedCombinedMeasurements(
// const gtsam::imuBias::ConstantBias& bias, // Standard Interface
// Matrix measuredAccCovariance, gtsam::NavState predict(const gtsam::NavState& state_i,
// Matrix measuredOmegaCovariance, const gtsam::imuBias::ConstantBias& bias) const;
// Matrix integrationErrorCovariance, };
// Matrix biasAccCovariance,
// Matrix biasOmegaCovariance, #include <gtsam/navigation/ImuFactor.h>
// Matrix biasAccOmegaInit); virtual class PreintegratedImuMeasurements: gtsam::PreintegrationBase {
// PreintegratedCombinedMeasurements( // Constructors
// const gtsam::imuBias::ConstantBias& bias, PreintegratedImuMeasurements(const gtsam::PreintegrationParams* params);
// Matrix measuredAccCovariance, PreintegratedImuMeasurements(const gtsam::PreintegrationParams* params,
// Matrix measuredOmegaCovariance, const gtsam::imuBias::ConstantBias& bias);
// Matrix integrationErrorCovariance,
// Matrix biasAccCovariance, // Testable
// Matrix biasOmegaCovariance, void print(string s) const;
// Matrix biasAccOmegaInit, bool equals(const gtsam::PreintegratedImuMeasurements& expected, double tol);
// bool use2ndOrderIntegration);
// // PreintegratedCombinedMeasurements(const gtsam::PreintegratedCombinedMeasurements& rhs); // Standard Interface
// void integrateMeasurement(Vector measuredAcc, Vector measuredOmega,
// // Testable double deltaT);
// void print(string s) const; void resetIntegration();
// bool equals(const gtsam::PreintegratedCombinedMeasurements& expected, double tol); Matrix preintMeasCov() const;
// };
// double deltaTij() const;
// gtsam::Rot3 deltaRij() const; virtual class ImuFactor: gtsam::NonlinearFactor {
// Vector deltaPij() const; ImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j,
// Vector deltaVij() const; size_t bias,
// Vector biasHatVector() const; const gtsam::PreintegratedImuMeasurements& preintegratedMeasurements);
// Matrix delPdelBiasAcc() const;
// Matrix delPdelBiasOmega() const; // Standard Interface
// Matrix delVdelBiasAcc() const; gtsam::PreintegratedImuMeasurements preintegratedMeasurements() const;
// Matrix delVdelBiasOmega() const; Vector evaluateError(const gtsam::Pose3& pose_i, Vector vel_i,
// Matrix delRdelBiasOmega() const; const gtsam::Pose3& pose_j, Vector vel_j,
// Matrix preintMeasCov() const; const gtsam::imuBias::ConstantBias& bias);
// };
// // Standard Interface
// void integrateMeasurement(Vector measuredAcc, Vector measuredOmega, double deltaT); #include <gtsam/navigation/CombinedImuFactor.h>
// gtsam::PoseVelocityBias predict(const gtsam::Pose3& pose_i, Vector vel_i, const gtsam::imuBias::ConstantBias& bias, virtual class PreintegratedCombinedMeasurements: gtsam::PreintegrationBase {
// Vector gravity, Vector omegaCoriolis) const; // Standard Constructor
//}; PreintegratedCombinedMeasurements(const gtsam::imuBias::ConstantBias& bias,
// Matrix measuredAccCovariance, Matrix measuredOmegaCovariance,
//virtual class CombinedImuFactor : gtsam::NonlinearFactor { Matrix integrationErrorCovariance, Matrix biasAccCovariance,
// CombinedImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j, size_t bias_i, size_t bias_j, Matrix biasOmegaCovariance, Matrix biasAccOmegaInit);
// const gtsam::PreintegratedCombinedMeasurements& CombinedPreintegratedMeasurements, Vector gravity, Vector omegaCoriolis);
// // Standard Interface // Testable
// gtsam::PreintegratedCombinedMeasurements preintegratedMeasurements() const; void print(string s) const;
//}; bool equals(const gtsam::PreintegratedCombinedMeasurements& expected,
// double tol);
// Standard Interface
void integrateMeasurement(Vector measuredAcc, Vector measuredOmega,
double deltaT);
void resetIntegration();
Matrix preintMeasCov() const;
};
virtual class CombinedImuFactor: gtsam::NonlinearFactor {
CombinedImuFactor(size_t pose_i, size_t vel_i, size_t pose_j, size_t vel_j,
size_t bias_i, size_t bias_j,
const gtsam::PreintegratedCombinedMeasurements& CombinedPreintegratedMeasurements);
// Standard Interface
gtsam::PreintegratedCombinedMeasurements preintegratedMeasurements() const;
Vector evaluateError(const gtsam::Pose3& pose_i, Vector vel_i,
const gtsam::Pose3& pose_j, Vector vel_j,
const gtsam::imuBias::ConstantBias& bias_i,
const gtsam::imuBias::ConstantBias& bias_j);
};
#include <gtsam/navigation/AHRSFactor.h> #include <gtsam/navigation/AHRSFactor.h>
class PreintegratedAhrsMeasurements { class PreintegratedAhrsMeasurements {
// Standard Constructor // Standard Constructor

View File

@ -280,6 +280,12 @@ public:
/// @} /// @}
/** Dummy clone for MATLAB */
virtual boost::shared_ptr<PreintegrationBase> clone() const {
return boost::shared_ptr<PreintegrationBase>();
}
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
/// @name Deprecated /// @name Deprecated
/// @{ /// @{