diff --git a/gtsam.h b/gtsam.h index 2cd30be42..80fbddec7 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2568,10 +2568,12 @@ virtual class BetweenFactor : gtsam::NoiseModelFactor { void serialize() const; }; - - #include -template +template virtual class NonlinearEquality : gtsam::NoiseModelFactor { // Constructor - forces exact evaluation NonlinearEquality(size_t j, const T& feasible); @@ -2582,7 +2584,6 @@ virtual class NonlinearEquality : gtsam::NoiseModelFactor { void serialize() const; }; - #include template virtual class RangeFactor : gtsam::NoiseModelFactor { @@ -2880,6 +2881,41 @@ virtual class FrobeniusWormholeFactor : gtsam::NoiseModelFactor { Vector evaluateError(const gtsam::SOn& Q1, const gtsam::SOn& Q2); }; +#include +template +class BinaryMeasurement { + BinaryMeasurement(size_t key1, size_t key2, const T& measured, + const gtsam::noiseModel::Base* model); + size_t key1() const; + size_t key2() const; + T measured() const; +}; + +typedef gtsam::BinaryMeasurement BinaryMeasurementUnit3; +typedef gtsam::BinaryMeasurement BinaryMeasurementRot3; + +// std::vector::shared_ptr> +class BinaryMeasurementUnit3s +{ + BinaryMeasurementUnit3s(); + size_t size() const; + gtsam::BinaryMeasurementUnit3* at(size_t i) const; + void push_back(const gtsam::BinaryMeasurementUnit3* measurement); +}; + +// std::vector::shared_ptr> +class BinaryMeasurementRot3s +{ + BinaryMeasurementRot3s(); + size_t size() const; + gtsam::BinaryMeasurementRot3* at(size_t i) const; + void push_back(const gtsam::BinaryMeasurementRot3* measurement); +}; + +#include +class TranslationRecovery { + TranslationRecovery() +} //************************************************************************* // Navigation //************************************************************************* diff --git a/gtsam/sfm/BinaryMeasurement.h b/gtsam/sfm/BinaryMeasurement.h index 99f0e6882..c5bb9c625 100644 --- a/gtsam/sfm/BinaryMeasurement.h +++ b/gtsam/sfm/BinaryMeasurement.h @@ -91,4 +91,7 @@ public: return measured_; } }; // \class BetweenMeasurement + + using BinaryMeasurementUnit3s = std::vector::shared_ptr>; + using BinaryMeasurementRot3s = std::vector::shared_ptr>; } \ No newline at end of file