special_cases_pybind.cpp
Go to the documentation of this file.
1 
2 
3 #include <pybind11/eigen.h>
4 #include <pybind11/stl_bind.h>
5 #include <pybind11/pybind11.h>
6 #include <pybind11/operators.h>
7 #include "gtsam/nonlinear/utilities.h" // for RedirectCout.
8 
10 
11 #include "wrap/serialization.h"
12 #include <boost/serialization/export.hpp>
13 
14 
15 
16 
17 
18 using namespace std;
19 
20 namespace py = pybind11;
21 
22 PYBIND11_MODULE(special_cases_py, m_) {
23  m_.doc() = "pybind11 wrapper of special_cases_py";
24 
25  pybind11::module m_gtsam = m_.def_submodule("gtsam", "gtsam submodule");
26 
27  py::class_<gtsam::NonlinearFactorGraph, std::shared_ptr<gtsam::NonlinearFactorGraph>>(m_gtsam, "NonlinearFactorGraph")
28  .def("addPriorPinholeCameraCal3Bundler",[](gtsam::NonlinearFactorGraph* self, size_t key, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& prior, const std::shared_ptr<gtsam::noiseModel::Base> noiseModel){ self->addPrior<gtsam::PinholeCamera<gtsam::Cal3Bundler>>(key, prior, noiseModel);}, py::arg("key"), py::arg("prior"), py::arg("noiseModel"));
29 
30  py::class_<gtsam::SfmTrack, std::shared_ptr<gtsam::SfmTrack>>(m_gtsam, "SfmTrack")
31  .def_readwrite("measurements", &gtsam::SfmTrack::measurements);
32 
33  py::class_<gtsam::PinholeCamera<gtsam::Cal3Bundler>, std::shared_ptr<gtsam::PinholeCamera<gtsam::Cal3Bundler>>>(m_gtsam, "PinholeCameraCal3Bundler");
34 
35  py::class_<gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>, std::shared_ptr<gtsam::GeneralSFMFactor<gtsam::PinholeCamera<gtsam::Cal3Bundler>, gtsam::Point3>>>(m_gtsam, "GeneralSFMFactorCal3Bundler");
36 
37 
38 #include "python/specializations.h"
39 
40 }
41 
module_ module
Definition: pybind11.h:943
module_ def_submodule(const char *name, const char *doc=nullptr)
Definition: pybind11.h:903
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:87
Definition: Half.h:150
PYBIND11_MODULE(special_cases_py, m_)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const ArgReturnType arg() const
Vector3 Point3
Definition: Point3.h:35
std::vector< SfmMeasurement > measurements
The 2D image projections (id,(u,v))
Definition: dataset.h:226
Calibration used by Bundler.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:47