From 9b481cb790d25ff9a013f9ef40f89dc7814e5ba9 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Thu, 27 Aug 2020 22:18:53 -0700 Subject: [PATCH] wrapping translation recovery doesnt build --- gtsam/gtsam.i | 11 +++++++++++ python/gtsam/specializations.h | 1 + 2 files changed, 12 insertions(+) diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index b9ecf6f3b..a3d5c1a41 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -3033,6 +3033,17 @@ class ShonanAveraging3 { pair run(const gtsam::Values& initial, size_t min_p, size_t max_p) const; }; +#include +class TranslationRecovery { + TranslationRecovery(const BinaryMeasurementsUnit3& relativeTranslations, + const LevenbergMarquardtParams& lmParams); + TranslationRecovery( + const BinaryMeasurementsUnit3& + relativeTranslations); // default LevenbergMarquardtParams + gtsam::Values run(const double scale) const; + gtsam::Values run() const; // default scale = 1.0 +}; + //************************************************************************* // Navigation //************************************************************************* diff --git a/python/gtsam/specializations.h b/python/gtsam/specializations.h index 3b60e42cb..52fffab6b 100644 --- a/python/gtsam/specializations.h +++ b/python/gtsam/specializations.h @@ -9,3 +9,4 @@ py::bind_vector >(m_, "Pose3Vector"); py::bind_vector > > >(m_, "BetweenFactorPose3s"); py::bind_vector > > >(m_, "BetweenFactorPose2s"); +py::bind_vector > >(m_, "BinaryMeasurementsUnit3");