enable pickling for a bunch of objects
parent
007022df6f
commit
247d996a79
|
|
@ -34,6 +34,9 @@ virtual class Gaussian : gtsam::noiseModel::Base {
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
|
|
||||||
|
// enable pickling in python
|
||||||
|
void pickle() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
virtual class Diagonal : gtsam::noiseModel::Gaussian {
|
virtual class Diagonal : gtsam::noiseModel::Gaussian {
|
||||||
|
|
@ -49,6 +52,9 @@ virtual class Diagonal : gtsam::noiseModel::Gaussian {
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
|
|
||||||
|
// enable pickling in python
|
||||||
|
void pickle() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
virtual class Constrained : gtsam::noiseModel::Diagonal {
|
virtual class Constrained : gtsam::noiseModel::Diagonal {
|
||||||
|
|
@ -66,6 +72,9 @@ virtual class Constrained : gtsam::noiseModel::Diagonal {
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
|
|
||||||
|
// enable pickling in python
|
||||||
|
void pickle() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
virtual class Isotropic : gtsam::noiseModel::Diagonal {
|
virtual class Isotropic : gtsam::noiseModel::Diagonal {
|
||||||
|
|
@ -78,6 +87,9 @@ virtual class Isotropic : gtsam::noiseModel::Diagonal {
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
|
|
||||||
|
// enable pickling in python
|
||||||
|
void pickle() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
virtual class Unit : gtsam::noiseModel::Isotropic {
|
virtual class Unit : gtsam::noiseModel::Isotropic {
|
||||||
|
|
@ -85,6 +97,9 @@ virtual class Unit : gtsam::noiseModel::Isotropic {
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
|
|
||||||
|
// enable pickling in python
|
||||||
|
void pickle() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
namespace mEstimator {
|
namespace mEstimator {
|
||||||
|
|
|
||||||
|
|
@ -41,6 +41,12 @@ class ConstantBias {
|
||||||
Vector gyroscope() const;
|
Vector gyroscope() const;
|
||||||
Vector correctAccelerometer(Vector measurement) const;
|
Vector correctAccelerometer(Vector measurement) const;
|
||||||
Vector correctGyroscope(Vector measurement) const;
|
Vector correctGyroscope(Vector measurement) const;
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serialize() const;
|
||||||
|
|
||||||
|
// enable pickling in python
|
||||||
|
void pickle() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
}///\namespace imuBias
|
}///\namespace imuBias
|
||||||
|
|
@ -64,6 +70,12 @@ class NavState {
|
||||||
|
|
||||||
gtsam::NavState retract(const Vector& x) const;
|
gtsam::NavState retract(const Vector& x) const;
|
||||||
Vector localCoordinates(const gtsam::NavState& g) const;
|
Vector localCoordinates(const gtsam::NavState& g) const;
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serialize() const;
|
||||||
|
|
||||||
|
// enable pickling in python
|
||||||
|
void pickle() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/navigation/PreintegratedRotation.h>
|
#include <gtsam/navigation/PreintegratedRotation.h>
|
||||||
|
|
@ -106,6 +118,12 @@ virtual class PreintegrationParams : gtsam::PreintegratedRotationParams {
|
||||||
Matrix getAccelerometerCovariance() const;
|
Matrix getAccelerometerCovariance() const;
|
||||||
Matrix getIntegrationCovariance() const;
|
Matrix getIntegrationCovariance() const;
|
||||||
bool getUse2ndOrderCoriolis() const;
|
bool getUse2ndOrderCoriolis() const;
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serialize() const;
|
||||||
|
|
||||||
|
// enable pickling in python
|
||||||
|
void pickle() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/navigation/ImuFactor.h>
|
#include <gtsam/navigation/ImuFactor.h>
|
||||||
|
|
@ -135,6 +153,12 @@ class PreintegratedImuMeasurements {
|
||||||
Vector biasHatVector() const;
|
Vector biasHatVector() const;
|
||||||
gtsam::NavState predict(const gtsam::NavState& state_i,
|
gtsam::NavState predict(const gtsam::NavState& state_i,
|
||||||
const gtsam::imuBias::ConstantBias& bias) const;
|
const gtsam::imuBias::ConstantBias& bias) const;
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serialize() const;
|
||||||
|
|
||||||
|
// enable pickling in python
|
||||||
|
void pickle() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
virtual class ImuFactor: gtsam::NonlinearFactor {
|
virtual class ImuFactor: gtsam::NonlinearFactor {
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue