#include #include #include #include #include "gtsam/nonlinear/utilities.h" // for RedirectCout. #include "gtsam/geometry/Cal3Bundler.h" #include "wrap/serialization.h" #include using namespace std; namespace py = pybind11; PYBIND11_MODULE(special_cases_py, m_) { m_.doc() = "pybind11 wrapper of special_cases_py"; pybind11::module m_gtsam = m_.def_submodule("gtsam", "gtsam submodule"); py::class_>(m_gtsam, "NonlinearFactorGraph") .def("addPriorPinholeCameraCal3Bundler",[](gtsam::NonlinearFactorGraph* self, size_t key, const gtsam::PinholeCamera& prior, const std::shared_ptr noiseModel){ self->addPrior>(key, prior, noiseModel);}, py::arg("key"), py::arg("prior"), py::arg("noiseModel")); py::class_>(m_gtsam, "SfmTrack") .def_readwrite("measurements", >sam::SfmTrack::measurements); py::class_, std::shared_ptr>>(m_gtsam, "PinholeCameraCal3Bundler"); py::class_, gtsam::Point3>, std::shared_ptr, gtsam::Point3>>> generalsfmfactorcal3bundler(m_gtsam, "GeneralSFMFactorCal3Bundler"); generalsfmfactorcal3bundler .def_readwrite("verbosity", >sam::GeneralSFMFactor, gtsam::Point3>::verbosity); py::enum_, gtsam::Point3>::Verbosity>(generalsfmfactorcal3bundler, "Verbosity", py::arithmetic()) .value("SILENT", gtsam::GeneralSFMFactor, gtsam::Point3>::Verbosity::SILENT) .value("SUMMARY", gtsam::GeneralSFMFactor, gtsam::Point3>::Verbosity::SUMMARY) .value("VALUES", gtsam::GeneralSFMFactor, gtsam::Point3>::Verbosity::VALUES); #include "python/specializations.h" }