wrap MFAS
parent
9350dd71ae
commit
1ed651b1a2
|
@ -3105,6 +3105,27 @@ class ShonanAveraging3 {
|
||||||
pair<gtsam::Values, double> run(const gtsam::Values& initial, size_t min_p, size_t max_p) const;
|
pair<gtsam::Values, double> run(const gtsam::Values& initial, size_t min_p, size_t max_p) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam/sfm/MFAS.h>
|
||||||
|
|
||||||
|
class KeyPairDoubleMap {
|
||||||
|
KeyPairDoubleMap();
|
||||||
|
KeyPairDoubleMap(const gtsam::KeyPairDoubleMap& other);
|
||||||
|
|
||||||
|
size_t size() const;
|
||||||
|
bool empty() const;
|
||||||
|
void clear();
|
||||||
|
size_t at(pair<size_t, size_t>) const;
|
||||||
|
};
|
||||||
|
|
||||||
|
class MFAS {
|
||||||
|
MFAS(const KeyVector*& nodes,
|
||||||
|
const gtsam::BinaryMeasurementsUnit3& relativeTranslations,
|
||||||
|
const gtsam::Unit3& projectionDirection);
|
||||||
|
|
||||||
|
KeyPairDoubleMap computeOutlierWeights() const;
|
||||||
|
KeyVector computeOrdering() const;
|
||||||
|
};
|
||||||
|
|
||||||
#include <gtsam/sfm/TranslationRecovery.h>
|
#include <gtsam/sfm/TranslationRecovery.h>
|
||||||
class TranslationRecovery {
|
class TranslationRecovery {
|
||||||
TranslationRecovery(const gtsam::BinaryMeasurementsUnit3 &relativeTranslations,
|
TranslationRecovery(const gtsam::BinaryMeasurementsUnit3 &relativeTranslations,
|
||||||
|
|
|
@ -108,4 +108,6 @@ class MFAS {
|
||||||
std::map<KeyPair, double> computeOutlierWeights() const;
|
std::map<KeyPair, double> computeOutlierWeights() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
typedef std::map<std::pair<Key, Key>, double> KeyPairDoubleMap;
|
||||||
|
|
||||||
} // namespace gtsam
|
} // namespace gtsam
|
||||||
|
|
|
@ -37,7 +37,8 @@ set(ignore
|
||||||
gtsam::Point2Vector
|
gtsam::Point2Vector
|
||||||
gtsam::Pose3Vector
|
gtsam::Pose3Vector
|
||||||
gtsam::KeyVector
|
gtsam::KeyVector
|
||||||
gtsam::BinaryMeasurementsUnit3)
|
gtsam::BinaryMeasurementsUnit3
|
||||||
|
gtsam::KeyPairDoubleMap)
|
||||||
|
|
||||||
pybind_wrap(gtsam_py # target
|
pybind_wrap(gtsam_py # target
|
||||||
${PROJECT_SOURCE_DIR}/gtsam/gtsam.i # interface_header
|
${PROJECT_SOURCE_DIR}/gtsam/gtsam.i # interface_header
|
||||||
|
@ -80,7 +81,9 @@ set(ignore
|
||||||
gtsam::Pose3Vector
|
gtsam::Pose3Vector
|
||||||
gtsam::KeyVector
|
gtsam::KeyVector
|
||||||
gtsam::FixedLagSmootherKeyTimestampMapValue
|
gtsam::FixedLagSmootherKeyTimestampMapValue
|
||||||
gtsam::BinaryMeasurementsUnit3)
|
gtsam::BinaryMeasurementsUnit3
|
||||||
|
gtsam::KeyPairDoubleMap)
|
||||||
|
|
||||||
pybind_wrap(gtsam_unstable_py # target
|
pybind_wrap(gtsam_unstable_py # target
|
||||||
${PROJECT_SOURCE_DIR}/gtsam_unstable/gtsam_unstable.i # interface_header
|
${PROJECT_SOURCE_DIR}/gtsam_unstable/gtsam_unstable.i # interface_header
|
||||||
"gtsam_unstable.cpp" # generated_cpp
|
"gtsam_unstable.cpp" # generated_cpp
|
||||||
|
|
|
@ -12,3 +12,4 @@ py::bind_vector<std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose2>
|
||||||
py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Unit3> > >(m_, "BinaryMeasurementsUnit3");
|
py::bind_vector<std::vector<gtsam::BinaryMeasurement<gtsam::Unit3> > >(m_, "BinaryMeasurementsUnit3");
|
||||||
py::bind_map<gtsam::IndexPairSetMap>(m_, "IndexPairSetMap");
|
py::bind_map<gtsam::IndexPairSetMap>(m_, "IndexPairSetMap");
|
||||||
py::bind_vector<gtsam::IndexPairVector>(m_, "IndexPairVector");
|
py::bind_vector<gtsam::IndexPairVector>(m_, "IndexPairVector");
|
||||||
|
py::bind_map<gtsam::KeyPairDoubleMap>(m_, "KeyPairDoubleMap");
|
||||||
|
|
Loading…
Reference in New Issue