class_pybind.cpp
Go to the documentation of this file.
1 #include <pybind11/eigen.h>
2 #include <pybind11/stl_bind.h>
3 #include <pybind11/pybind11.h>
4 #include <pybind11/operators.h>
5 #include "gtsam/nonlinear/utilities.h" // for RedirectCout.
6 
7 #include "folder/path/to/Test.h"
8 
9 
10 
11 
12 using namespace std;
13 
14 namespace py = pybind11;
15 
16 PYBIND11_MODULE(class_py, m_) {
17  m_.doc() = "pybind11 wrapper of class_py";
18 
19 
20  py::class_<FunRange, std::shared_ptr<FunRange>>(m_, "FunRange")
21  .def(py::init<>())
22  .def("range",[](FunRange* self, double d){return self->range(d);}, py::arg("d"))
23  .def_static("create",[](){return FunRange::create();});
24 
25  py::class_<Fun<double>, std::shared_ptr<Fun<double>>>(m_, "FunDouble")
26  .def("templatedMethodString",[](Fun<double>* self, double d, string t){return self->templatedMethod<string>(d, t);}, py::arg("d"), py::arg("t"))
27  .def("multiTemplatedMethodStringSize_t",[](Fun<double>* self, double d, string t, size_t u){return self->multiTemplatedMethod<string,size_t>(d, t, u);}, py::arg("d"), py::arg("t"), py::arg("u"))
28  .def("sets",[](Fun<double>* self){return self->sets();})
29  .def_static("staticMethodWithThis",[](){return Fun<double>::staticMethodWithThis();})
30  .def_static("templatedStaticMethodInt",[](const int& m){return Fun<double>::templatedStaticMethod<int>(m);}, py::arg("m"));
31 
32  py::class_<Test, std::shared_ptr<Test>>(m_, "Test")
33  .def(py::init<>())
34  .def(py::init<double, const gtsam::Matrix&>(), py::arg("a"), py::arg("b"))
35  .def("return_pair",[](Test* self, const gtsam::Vector& v, const gtsam::Matrix& A){return self->return_pair(v, A);}, py::arg("v"), py::arg("A"))
36  .def("return_pair",[](Test* self, const gtsam::Vector& v){return self->return_pair(v);}, py::arg("v"))
37  .def("return_bool",[](Test* self, bool value){return self->return_bool(value);}, py::arg("value"))
38  .def("return_size_t",[](Test* self, size_t value){return self->return_size_t(value);}, py::arg("value"))
39  .def("return_int",[](Test* self, int value){return self->return_int(value);}, py::arg("value"))
40  .def("return_double",[](Test* self, double value){return self->return_double(value);}, py::arg("value"))
41  .def("return_string",[](Test* self, string value){return self->return_string(value);}, py::arg("value"))
42  .def("return_vector1",[](Test* self, const gtsam::Vector& value){return self->return_vector1(value);}, py::arg("value"))
43  .def("return_matrix1",[](Test* self, const gtsam::Matrix& value){return self->return_matrix1(value);}, py::arg("value"))
44  .def("return_vector2",[](Test* self, const gtsam::Vector& value){return self->return_vector2(value);}, py::arg("value"))
45  .def("return_matrix2",[](Test* self, const gtsam::Matrix& value){return self->return_matrix2(value);}, py::arg("value"))
46  .def("arg_EigenConstRef",[](Test* self, const gtsam::Matrix& value){ self->arg_EigenConstRef(value);}, py::arg("value"))
47  .def("return_field",[](Test* self, const Test& t){return self->return_field(t);}, py::arg("t"))
48  .def("return_TestPtr",[](Test* self, const std::shared_ptr<Test> value){return self->return_TestPtr(value);}, py::arg("value"))
49  .def("return_Test",[](Test* self, std::shared_ptr<Test> value){return self->return_Test(value);}, py::arg("value"))
50  .def("return_Point2Ptr",[](Test* self, bool value){return self->return_Point2Ptr(value);}, py::arg("value"))
51  .def("create_ptrs",[](Test* self){return self->create_ptrs();})
52  .def("create_MixedPtrs",[](Test* self){return self->create_MixedPtrs();})
53  .def("return_ptrs",[](Test* self, std::shared_ptr<Test> p1, std::shared_ptr<Test> p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2"))
54  .def("print",[](Test* self){ py::scoped_ostream_redirect output; self->print();})
55  .def("__repr__",
56  [](const Test& self){
57  gtsam::RedirectCout redirect;
58  self.print();
59  return redirect.str();
60  })
61  .def("lambda_",[](Test* self){ self->lambda();})
62  .def("set_container",[](Test* self, std::vector<testing::Test> container){ self->set_container(container);}, py::arg("container"))
63  .def("set_container",[](Test* self, std::vector<std::shared_ptr<testing::Test>> container){ self->set_container(container);}, py::arg("container"))
64  .def("set_container",[](Test* self, std::vector<testing::Test&> container){ self->set_container(container);}, py::arg("container"))
65  .def("get_container",[](Test* self){return self->get_container();})
66  .def("_repr_markdown_",[](Test* self, const gtsam::KeyFormatter& keyFormatter){return self->markdown(keyFormatter);}, py::arg("keyFormatter") = gtsam::DefaultKeyFormatter)
67  .def_readwrite("model_ptr", &Test::model_ptr)
68  .def_readwrite("value", &Test::value)
69  .def_readwrite("name", &Test::name);
70 
71  py::class_<PrimitiveRef<double>, std::shared_ptr<PrimitiveRef<double>>>(m_, "PrimitiveRefDouble")
72  .def(py::init<>())
73  .def_static("Brutal",[](const double& t){return PrimitiveRef<double>::Brutal(t);}, py::arg("t"));
74 
75  py::class_<MyVector<3>, std::shared_ptr<MyVector<3>>>(m_, "MyVector3")
76  .def(py::init<>());
77 
78  py::class_<MyVector<12>, std::shared_ptr<MyVector<12>>>(m_, "MyVector12")
79  .def(py::init<>());
80 
81  py::class_<MultipleTemplates<int, double>, std::shared_ptr<MultipleTemplates<int, double>>>(m_, "MultipleTemplatesIntDouble");
82 
83  py::class_<MultipleTemplates<int, float>, std::shared_ptr<MultipleTemplates<int, float>>>(m_, "MultipleTemplatesIntFloat");
84 
85  py::class_<ForwardKinematics, std::shared_ptr<ForwardKinematics>>(m_, "ForwardKinematics")
86  .def(py::init<const gtdynamics::Robot&, const string&, const string&, const gtsam::Values&, const gtsam::Pose3&>(), py::arg("robot"), py::arg("start_link_name"), py::arg("end_link_name"), py::arg("joint_angles"), py::arg("l2Tp") = gtsam::Pose3());
87 
88  py::class_<TemplatedConstructor, std::shared_ptr<TemplatedConstructor>>(m_, "TemplatedConstructor")
89  .def(py::init<>())
90  .def(py::init<const string&>(), py::arg("arg"))
91  .def(py::init<const int&>(), py::arg("arg"))
92  .def(py::init<const double&>(), py::arg("arg"));
93 
94  py::class_<FastSet, std::shared_ptr<FastSet>>(m_, "FastSet")
95  .def(py::init<>())
96  .def("__len__",[](FastSet* self){return std::distance(self->begin(), self->end());})
97  .def("__contains__",[](FastSet* self, size_t key){return std::find(self->begin(), self->end(), key) != self->end();}, py::arg("key"))
98  .def("__iter__",[](FastSet* self){return py::make_iterator(self->begin(), self->end());});
99 
100  py::class_<MyFactor<gtsam::Pose2, gtsam::Matrix>, std::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>>(m_, "MyFactorPosePoint2")
101  .def(py::init<size_t, size_t, double, const std::shared_ptr<gtsam::noiseModel::Base>>(), py::arg("key1"), py::arg("key2"), py::arg("measured"), py::arg("noiseModel"))
102  .def("print",[](MyFactor<gtsam::Pose2, gtsam::Matrix>* self, const string& s, const gtsam::KeyFormatter& keyFormatter){ py::scoped_ostream_redirect output; self->print(s, keyFormatter);}, py::arg("s") = "factor: ", py::arg("keyFormatter") = gtsam::DefaultKeyFormatter)
103  .def("__repr__",
104  [](const MyFactor<gtsam::Pose2, gtsam::Matrix>& self, const string& s, const gtsam::KeyFormatter& keyFormatter){
105  gtsam::RedirectCout redirect;
106  self.print(s, keyFormatter);
107  return redirect.str();
108  }, py::arg("s") = "factor: ", py::arg("keyFormatter") = gtsam::DefaultKeyFormatter);
109 
110  py::class_<SuperCoolFactor<gtsam::Pose3>, std::shared_ptr<SuperCoolFactor<gtsam::Pose3>>>(m_, "SuperCoolFactorPose3");
111 
112 #include "python/specializations.h"
113 
114 }
115 
utilities.h
Contains generic global functions designed particularly for the matlab interface.
create
ADT create(const Signature &signature)
Definition: testAlgebraicDecisionTree.cpp:129
s
RealScalar s
Definition: level1_cplx_impl.h:126
d
static const double d[K][N]
Definition: igam.h:11
gtsam::RedirectCout
Definition: base/utilities.h:16
PYBIND11_MODULE
PYBIND11_MODULE(class_py, m_)
Definition: class_pybind.cpp:16
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
name
static char name[]
Definition: rgamma.c:72
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
make_iterator
iterator make_iterator(Iterator first, Sentinel last, Extra &&...extra)
Makes a python iterator from a first and past-the-end C++ InputIterator.
Definition: pybind11.h:2409
gtsam::KeyFormatter
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
gtsam::Pose3
Definition: Pose3.h:37
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
arg
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE ArgReturnType arg() const
Definition: ArrayCwiseUnaryOps.h:66
E1::A
@ A
MyFactor
GeneralSFMFactor< SfmCamera, Point3 > MyFactor
Definition: SFMExample_bal.cpp:36
init
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Definition: pybind11.h:1912
p1
Vector3f p1
Definition: MatrixBase_all.cpp:2
key
const gtsam::Symbol key('X', 0)
pybind11.h
std
Definition: BFloat16.h:88
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
self
static const self_t self
Definition: operators.h:72
pybind11
Definition: wrap/pybind11/pybind11/__init__.py:1
gtsam::distance
Double_ distance(const OrientedPlane3_ &p)
Definition: slam/expressions.h:117
eigen.h
align_3::t
Point2 t(10, 10)
operators.h
stl_bind.h
test_callbacks.value
value
Definition: test_callbacks.py:158
gtsam::RedirectCout::str
std::string str() const
return the string
Definition: utilities.cpp:5


gtsam
Author(s):
autogenerated on Mon Jul 1 2024 03:00:55