wrapping translation recovery doesnt build
parent
02cd45d4b8
commit
9b481cb790
|
@ -3033,6 +3033,17 @@ class ShonanAveraging3 {
|
|||
pair<gtsam::Values, double> run(const gtsam::Values& initial, size_t min_p, size_t max_p) const;
|
||||
};
|
||||
|
||||
#include <gtsam/sfm/TranslationRecovery.h>
|
||||
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
|
||||
//*************************************************************************
|
||||
|
|
|
@ -9,3 +9,4 @@ py::bind_vector<std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point
|
|||
py::bind_vector<std::vector<gtsam::Pose3> >(m_, "Pose3Vector");
|
||||
py::bind_vector<std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > > >(m_, "BetweenFactorPose3s");
|
||||
py::bind_vector<std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose2> > > >(m_, "BetweenFactorPose2s");
|
||||
py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Unit3> > >(m_, "BinaryMeasurementsUnit3");
|
||||
|
|
Loading…
Reference in New Issue