-
Notifications
You must be signed in to change notification settings - Fork 638
/
Copy pathpatch-009.diff
63 lines (58 loc) · 7.14 KB
/
patch-009.diff
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
diff --git a/python/src/mrpt/poses/CPose3DPDF.cpp b/python/src/mrpt/poses/CPose3DPDF.cpp
index 73668b4fd..472022c93 100644
--- a/python/src/mrpt/poses/CPose3DPDF.cpp
+++ b/python/src/mrpt/poses/CPose3DPDF.cpp
@@ -533,5 +533,8 @@ void bind_mrpt_poses_CPose3DPDF(std::function< pybind11::module &(std::string co
cl.def("assign", (class mrpt::poses::CPose3DPDFGaussian & (mrpt::poses::CPose3DPDFGaussian::*)(const class mrpt::poses::CPose3DPDFGaussian &)) &mrpt::poses::CPose3DPDFGaussian::operator=, "C++: mrpt::poses::CPose3DPDFGaussian::operator=(const class mrpt::poses::CPose3DPDFGaussian &) --> class mrpt::poses::CPose3DPDFGaussian &", pybind11::return_value_policy::automatic, pybind11::arg(""));
cl.def("__str__", [](mrpt::poses::CPose3DPDFGaussian const &o) -> std::string { std::ostringstream s; using namespace mrpt::poses; s << o; return s.str(); } );
+
+ cl.def("__add__", [](const mrpt::poses::CPose3DPDFGaussian&a, const mrpt::poses::CPose3DPDFGaussian& b) -> mrpt::poses::CPose3DPDFGaussian { return a+b; });
+ cl.def("__sub__", [](const mrpt::poses::CPose3DPDFGaussian&a, const mrpt::poses::CPose3DPDFGaussian& b) -> mrpt::poses::CPose3DPDFGaussian { return a-b; });
}
}
diff --git a/python/src/mrpt/poses/CPose3DPDFGaussianInf.cpp b/python/src/mrpt/poses/CPose3DPDFGaussianInf.cpp
index 6655851d9..3f249106b 100644
--- a/python/src/mrpt/poses/CPose3DPDFGaussianInf.cpp
+++ b/python/src/mrpt/poses/CPose3DPDFGaussianInf.cpp
@@ -504,6 +504,9 @@ void bind_mrpt_poses_CPose3DPDFGaussianInf(std::function< pybind11::module &(std
cl.def("assign", (class mrpt::poses::CPose3DPDFGaussianInf & (mrpt::poses::CPose3DPDFGaussianInf::*)(const class mrpt::poses::CPose3DPDFGaussianInf &)) &mrpt::poses::CPose3DPDFGaussianInf::operator=, "C++: mrpt::poses::CPose3DPDFGaussianInf::operator=(const class mrpt::poses::CPose3DPDFGaussianInf &) --> class mrpt::poses::CPose3DPDFGaussianInf &", pybind11::return_value_policy::automatic, pybind11::arg(""));
cl.def("__str__", [](mrpt::poses::CPose3DPDFGaussianInf const &o) -> std::string { std::ostringstream s; using namespace mrpt::poses; s << o; return s.str(); } );
+
+ cl.def("__add__", [](const mrpt::poses::CPose3DPDFGaussianInf&a, const mrpt::poses::CPose3DPDFGaussianInf& b) -> mrpt::poses::CPose3DPDFGaussianInf { return a+b; });
+ cl.def("__sub__", [](const mrpt::poses::CPose3DPDFGaussianInf&a, const mrpt::poses::CPose3DPDFGaussianInf& b) -> mrpt::poses::CPose3DPDFGaussianInf { return a-b; });
}
{ // mrpt::poses::CPose3DPDFGrid file:mrpt/poses/CPose3DPDFGrid.h line:25
pybind11::class_<mrpt::poses::CPose3DPDFGrid, std::shared_ptr<mrpt::poses::CPose3DPDFGrid>, PyCallBack_mrpt_poses_CPose3DPDFGrid, mrpt::poses::CPose3DPDF, mrpt::poses::CPose3DGridTemplate<double>> cl(M("mrpt::poses"), "CPose3DPDFGrid", "Declares a class that represents a Probability Distribution\n function (PDF) of a SE(3) pose (x,y,z, yaw, pitch, roll), in\n the form of a 6-dimensional grid of \"voxels\".\n\n \n CPose3D, CPose3DPDF, CPose3DGridTemplate\n \n\n\n ");
diff --git a/python/src/mrpt/poses/CPose3DQuatPDFGaussianInf.cpp b/python/src/mrpt/poses/CPose3DQuatPDFGaussianInf.cpp
index d0b98b04a..c3d2a6001 100644
--- a/python/src/mrpt/poses/CPose3DQuatPDFGaussianInf.cpp
+++ b/python/src/mrpt/poses/CPose3DQuatPDFGaussianInf.cpp
@@ -483,6 +483,9 @@ void bind_mrpt_poses_CPose3DQuatPDFGaussianInf(std::function< pybind11::module &
cl.def("assign", (class mrpt::poses::CPose3DQuatPDFGaussianInf & (mrpt::poses::CPose3DQuatPDFGaussianInf::*)(const class mrpt::poses::CPose3DQuatPDFGaussianInf &)) &mrpt::poses::CPose3DQuatPDFGaussianInf::operator=, "C++: mrpt::poses::CPose3DQuatPDFGaussianInf::operator=(const class mrpt::poses::CPose3DQuatPDFGaussianInf &) --> class mrpt::poses::CPose3DQuatPDFGaussianInf &", pybind11::return_value_policy::automatic, pybind11::arg(""));
cl.def("__str__", [](mrpt::poses::CPose3DQuatPDFGaussianInf const &o) -> std::string { std::ostringstream s; using namespace mrpt::poses; s << o; return s.str(); } );
+
+ cl.def("__add__", [](const mrpt::poses::CPose3DQuatPDFGaussianInf&a, const mrpt::poses::CPose3DQuatPDFGaussianInf& b) -> mrpt::poses::CPose3DQuatPDFGaussianInf { return a+b; });
+ cl.def("__sub__", [](const mrpt::poses::CPose3DQuatPDFGaussianInf&a, const mrpt::poses::CPose3DQuatPDFGaussianInf& b) -> mrpt::poses::CPose3DQuatPDFGaussianInf { return a-b; });
}
{ // mrpt::poses::CPosePDFGaussianInf file:mrpt/poses/CPosePDFGaussianInf.h line:33
pybind11::class_<mrpt::poses::CPosePDFGaussianInf, std::shared_ptr<mrpt::poses::CPosePDFGaussianInf>, PyCallBack_mrpt_poses_CPosePDFGaussianInf, mrpt::poses::CPosePDF> cl(M("mrpt::poses"), "CPosePDFGaussianInf", "A Probability Density function (PDF) of a 2D pose \n\n\n as a Gaussian with a mean and the inverse of the covariance.\n\n This class implements a PDF as a mono-modal Gaussian distribution in its\n information form, that is,\n keeping the inverse of the covariance matrix instead of the covariance\n matrix itself.\n\n This class is the dual of CPosePDFGaussian.\n\n \n CPose2D, CPosePDF, CPosePDFParticles\n \n\n\n ");
@@ -529,5 +532,8 @@ void bind_mrpt_poses_CPose3DQuatPDFGaussianInf(std::function< pybind11::module &
cl.def("assign", (class mrpt::poses::CPosePDFGaussianInf & (mrpt::poses::CPosePDFGaussianInf::*)(const class mrpt::poses::CPosePDFGaussianInf &)) &mrpt::poses::CPosePDFGaussianInf::operator=, "C++: mrpt::poses::CPosePDFGaussianInf::operator=(const class mrpt::poses::CPosePDFGaussianInf &) --> class mrpt::poses::CPosePDFGaussianInf &", pybind11::return_value_policy::automatic, pybind11::arg(""));
cl.def("__str__", [](mrpt::poses::CPosePDFGaussianInf const &o) -> std::string { std::ostringstream s; using namespace mrpt::poses; s << o; return s.str(); } );
+
+ cl.def("__add__", [](const mrpt::poses::CPosePDFGaussianInf&a, const mrpt::poses::CPosePDFGaussianInf& b) -> mrpt::poses::CPosePDFGaussianInf { return a+b; });
+ cl.def("__sub__", [](const mrpt::poses::CPosePDFGaussianInf&a, const mrpt::poses::CPosePDFGaussianInf& b) -> mrpt::poses::CPosePDFGaussianInf { return a-b; });
}
}
diff --git a/python/src/mrpt/poses/CPosePDFGaussian.cpp b/python/src/mrpt/poses/CPosePDFGaussian.cpp
index c50d72dee..4671c88a6 100644
--- a/python/src/mrpt/poses/CPosePDFGaussian.cpp
+++ b/python/src/mrpt/poses/CPosePDFGaussian.cpp
@@ -301,5 +301,8 @@ void bind_mrpt_poses_CPosePDFGaussian(std::function< pybind11::module &(std::str
cl.def("assign", (class mrpt::poses::CPosePDFGaussian & (mrpt::poses::CPosePDFGaussian::*)(const class mrpt::poses::CPosePDFGaussian &)) &mrpt::poses::CPosePDFGaussian::operator=, "C++: mrpt::poses::CPosePDFGaussian::operator=(const class mrpt::poses::CPosePDFGaussian &) --> class mrpt::poses::CPosePDFGaussian &", pybind11::return_value_policy::automatic, pybind11::arg(""));
cl.def("__str__", [](mrpt::poses::CPosePDFGaussian const &o) -> std::string { std::ostringstream s; using namespace mrpt::poses; s << o; return s.str(); } );
+
+ cl.def("__add__", [](const mrpt::poses::CPosePDFGaussian&a, const mrpt::poses::CPosePDFGaussian& b) -> mrpt::poses::CPosePDFGaussian { return a+b; });
+ cl.def("__sub__", [](const mrpt::poses::CPosePDFGaussian&a, const mrpt::poses::CPosePDFGaussian& b) -> mrpt::poses::CPosePDFGaussian { return a-b; });
}
}