10 #include "wrap/serialization.h" 11 #include <boost/serialization/export.hpp> 22 m_.doc() =
"pybind11 wrapper of inheritance_py";
25 py::class_<MyBase, std::shared_ptr<MyBase>>(m_,
"MyBase");
27 py::class_<MyTemplate<gtsam::Point2>, MyBase, std::shared_ptr<MyTemplate<gtsam::Point2>>>(m_,
"MyTemplatePoint2")
33 .def(
"accept_T",[](MyTemplate<gtsam::Point2>*
self,
const gtsam::Point2&
value){
self->accept_T(value);},
py::arg(
"value"))
34 .def(
"accept_Tptr",[](MyTemplate<gtsam::Point2>*
self, std::shared_ptr<gtsam::Point2> value){
self->accept_Tptr(value);},
py::arg(
"value"))
35 .def(
"return_Tptr",[](MyTemplate<gtsam::Point2>*
self, std::shared_ptr<gtsam::Point2> value){
return self->return_Tptr(value);},
py::arg(
"value"))
36 .def(
"return_T",[](MyTemplate<gtsam::Point2>*
self,
gtsam::Point2* value){
return self->return_T(value);},
py::arg(
"value"))
37 .def(
"create_ptrs",[](MyTemplate<gtsam::Point2>*
self){
return self->create_ptrs();})
38 .def(
"create_MixedPtrs",[](MyTemplate<gtsam::Point2>*
self){
return self->create_MixedPtrs();})
39 .def(
"return_ptrs",[](MyTemplate<gtsam::Point2>*
self, std::shared_ptr<gtsam::Point2>
p1, std::shared_ptr<gtsam::Point2>
p2){
return self->return_ptrs(p1, p2);},
py::arg(
"p1"),
py::arg(
"p2"))
40 .def_static(
"Level",[](
const gtsam::Point2&
K){
return MyTemplate<gtsam::Point2>::Level(K);},
py::arg(
"K"));
42 py::class_<MyTemplate<gtsam::Matrix>, MyBase, std::shared_ptr<MyTemplate<gtsam::Matrix>>>(m_,
"MyTemplateMatrix")
48 .def(
"accept_T",[](MyTemplate<gtsam::Matrix>*
self,
const gtsam::Matrix& value){
self->accept_T(value);},
py::arg(
"value"))
49 .def(
"accept_Tptr",[](MyTemplate<gtsam::Matrix>*
self,
const std::shared_ptr<gtsam::Matrix> value){
self->accept_Tptr(value);},
py::arg(
"value"))
50 .def(
"return_Tptr",[](MyTemplate<gtsam::Matrix>*
self,
const std::shared_ptr<gtsam::Matrix> value){
return self->return_Tptr(value);},
py::arg(
"value"))
51 .def(
"return_T",[](MyTemplate<gtsam::Matrix>*
self,
const gtsam::Matrix* value){
return self->return_T(value);},
py::arg(
"value"))
52 .def(
"create_ptrs",[](MyTemplate<gtsam::Matrix>*
self){
return self->create_ptrs();})
53 .def(
"create_MixedPtrs",[](MyTemplate<gtsam::Matrix>*
self){
return self->create_MixedPtrs();})
54 .def(
"return_ptrs",[](MyTemplate<gtsam::Matrix>*
self,
const std::shared_ptr<gtsam::Matrix> p1,
const std::shared_ptr<gtsam::Matrix> p2){
return self->return_ptrs(p1, p2);},
py::arg(
"p1"),
py::arg(
"p2"))
55 .def_static(
"Level",[](
const gtsam::Matrix& K){
return MyTemplate<gtsam::Matrix>::Level(K);},
py::arg(
"K"));
57 py::class_<ForwardKinematicsFactor, gtsam::BetweenFactor<gtsam::Pose3>, std::shared_ptr<ForwardKinematicsFactor>>(m_,
"ForwardKinematicsFactor");
60 #include "python/specializations.h"
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const ArgReturnType arg() const
PYBIND11_MODULE(inheritance_py, m_)