diff --git a/3rdparty/nanogui b/3rdparty/nanogui index 2bf2c17a63..eb8b089f56 160000 --- a/3rdparty/nanogui +++ b/3rdparty/nanogui @@ -1 +1 @@ -Subproject commit 2bf2c17a63cf9482e030e8b218dc0c1aee4c1b60 +Subproject commit eb8b089f56af06c0423b45213d25bf8201a1c2ba diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 5fbdc117a7..ae2f269f8a 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -2,7 +2,8 @@ # Version 2.10.2: UNRELEASED - BUG FIXES: - - Fix CSparse "C" linkage build error (OSX Clang) + - Fix CSparse "C" linkage build error (OSX Clang). PR [#1280](https://github.com/MRPT/mrpt/pull/1280) + - Fix missing Python wrapping of poses PDF (poses with uncertainty) composition (\oplus and \ominus) operators. (Closes [#1281](https://github.com/MRPT/mrpt/issues/1281)). PR [#1283](https://github.com/MRPT/mrpt/pull/1283) # Version 2.10.1: Released August 10th, 2023 - Build system: diff --git a/python-examples/ros-poses-convert.py b/python-examples/ros-poses-convert.py index 1ecbd7a237..e26075dbe9 100755 --- a/python-examples/ros-poses-convert.py +++ b/python-examples/ros-poses-convert.py @@ -66,3 +66,9 @@ print('mrpt PDF mr3 : ' + str(mr3)) print('mrpt PDF mr3b : ' + str(mr3b)) print('ros PDF r3b : ' + str(r3b)) + +a = mr3 +b = mr3 +c = a+b + +print('r3b (+) rb3 : ' + str(c)) diff --git a/python/generate-python-stubs.sh b/python/generate-python-stubs.sh index 07e4efd0b1..f05122644b 100755 --- a/python/generate-python-stubs.sh +++ b/python/generate-python-stubs.sh @@ -16,4 +16,4 @@ stubgen -p mrpt -p mrpt.pymrpt -o stubs-out # applying manual patches to stubs: echo "Applying manual patches to stubs..." -find . -name "patch-stubs*.diff" | xargs -I FIL bash -c "echo FIL && git apply FIL" +find . -name "patch-stubs*.diff" | xargs -I FIL bash -c "echo FIL && git apply FIL --ignore-whitespace" diff --git a/python/generate-python.sh b/python/generate-python.sh index 1759f09a22..c6e320f649 100755 --- a/python/generate-python.sh +++ b/python/generate-python.sh @@ -4,7 +4,7 @@ # Based on https://github.com/RosettaCommons/binder # # binder config: llvm-14 -# +# PYBIND11_VERSION=$(dpkg -s pybind11-dev | grep '^Version:' | cut -d " " -f2) @@ -94,5 +94,5 @@ find $WRAP_OUT_DIR -name "*.cpp" | xargs -I FIL \ # applying manual patches: echo "Applying manual patches to pybind11 code..." -find . -name "patch-0*.diff" | xargs -I FIL bash -c "echo FIL && git apply FIL" +find . -name "patch-0*.diff" | xargs -I FIL bash -c "echo \"Applying patch: FIL\" && git apply FIL --ignore-whitespace" diff --git a/python/patch-001.diff b/python/patch-001.diff index a34ff86e54..d6f68276e5 100644 --- a/python/patch-001.diff +++ b/python/patch-001.diff @@ -24,7 +24,7 @@ index cabe86ec7..302018560 100644 + void bind_std_stl_deque(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // std::deque file:bits/stl_deque.h line:766 + { // std::deque file:bits/stl_deque.h line:767 diff --git a/python/src/std/stl_deque_1.cpp b/python/src/std/stl_deque_1.cpp index d974577d3..a80326114 100644 --- a/python/src/std/stl_deque_1.cpp @@ -38,7 +38,7 @@ index d974577d3..a80326114 100644 + void bind_std_stl_deque_1(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // std::deque file:bits/stl_deque.h line:766 + { // std::deque file:bits/stl_deque.h line:767 diff --git a/python/src/std/stl_deque_2.cpp b/python/src/std/stl_deque_2.cpp index ca96e381d..54e7eaaf4 100644 --- a/python/src/std/stl_deque_2.cpp @@ -51,7 +51,7 @@ index ca96e381d..54e7eaaf4 100644 + void bind_std_stl_deque_2(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // std::deque file:bits/stl_deque.h line:766 + { // std::deque file:bits/stl_deque.h line:767 diff --git a/python/src/std/stl_map.cpp b/python/src/std/stl_map.cpp index db3f49fde..793bf72f3 100644 --- a/python/src/std/stl_map.cpp diff --git a/python/patch-007.diff b/python/patch-007.diff index a890a43d83..2501a44b3f 100644 --- a/python/patch-007.diff +++ b/python/patch-007.diff @@ -12,7 +12,7 @@ index 1638b4d29..4c5984034 100644 + }, pybind11::keep_alive<0, 1>()); + } - { // std::deque file:bits/stl_deque.h line:766 + { // std::deque file:bits/stl_deque.h line:767 pybind11::class_>, std::shared_ptr>>> cl(M("std"), "deque_mrpt_bayes_CProbabilityParticle_mrpt_math_TPose2D_mrpt_bayes_particle_storage_mode_VALUE_t", ""); @@ -90,5 +95,10 @@ void bind_std_stl_deque(std::function< pybind11::module &(std::string const &nam cl.def("pop_back", (void (std::deque>::*)()) &std::deque>::pop_back, "C++: std::deque>::pop_back() --> void"); @@ -39,7 +39,7 @@ index b16449336..69668158e 100644 + }, pybind11::keep_alive<0, 1>()); + } - { // std::deque file:bits/stl_deque.h line:766 + { // std::deque file:bits/stl_deque.h line:767 pybind11::class_>, std::shared_ptr>>> cl(M("std"), "deque_mrpt_bayes_CProbabilityParticle_mrpt_maps_CRBPFParticleData_mrpt_bayes_particle_storage_mode_POINTER_t", ""); @@ -91,5 +96,10 @@ void bind_std_stl_deque_1(std::function< pybind11::module &(std::string const &n cl.def("pop_back", (void (std::deque>::*)()) &std::deque>::pop_back, "C++: std::deque>::pop_back() --> void"); diff --git a/python/patch-009.diff b/python/patch-009.diff new file mode 100644 index 0000000000..05322b2c90 --- /dev/null +++ b/python/patch-009.diff @@ -0,0 +1,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_, PyCallBack_mrpt_poses_CPose3DPDFGrid, mrpt::poses::CPose3DPDF, mrpt::poses::CPose3DGridTemplate> 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_, 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; }); + } + } diff --git a/python/python.conf b/python/python.conf index 0ce34e94ce..ccba8abe7d 100644 --- a/python/python.conf +++ b/python/python.conf @@ -295,4 +295,6 @@ # -class std::map -class std::map --class std::monostate \ No newline at end of file +-class std::monostate +# ++function mrpt::poses::operator+(const mrpt::poses::CPose3DPDFGaussian&, const mrpt::poses::CPose3DPDFGaussian&) diff --git a/python/src/mrpt/config/CLoadableOptions.cpp b/python/src/mrpt/config/CLoadableOptions.cpp index 24034f6c6d..2d2736b5a9 100644 --- a/python/src/mrpt/config/CLoadableOptions.cpp +++ b/python/src/mrpt/config/CLoadableOptions.cpp @@ -24,7 +24,7 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::config::CLoadableOptions file:mrpt/config/CLoadableOptions.h line:26 +// mrpt::config::CLoadableOptions file:mrpt/config/CLoadableOptions.h line:24 struct PyCallBack_mrpt_config_CLoadableOptions : public mrpt::config::CLoadableOptions { using mrpt::config::CLoadableOptions::CLoadableOptions; @@ -58,8 +58,8 @@ struct PyCallBack_mrpt_config_CLoadableOptions : public mrpt::config::CLoadableO void bind_mrpt_config_CLoadableOptions(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::config::CLoadableOptions file:mrpt/config/CLoadableOptions.h line:26 - pybind11::class_, PyCallBack_mrpt_config_CLoadableOptions> cl(M("mrpt::config"), "CLoadableOptions", "This is a virtual base class for sets of options than can be loaded from\n and/or saved to configuration plain-text files.\n"); + { // mrpt::config::CLoadableOptions file:mrpt/config/CLoadableOptions.h line:24 + pybind11::class_, PyCallBack_mrpt_config_CLoadableOptions> cl(M("mrpt::config"), "CLoadableOptions", "This is a virtual base class for sets of options than can be loaded from\n and/or saved to configuration plain-text files.\n \n\n\n "); cl.def(pybind11::init()); cl.def( pybind11::init( [](){ return new PyCallBack_mrpt_config_CLoadableOptions(); } ) ); cl.def("loadFromConfigFile", (void (mrpt::config::CLoadableOptions::*)(const class mrpt::config::CConfigFileBase &, const std::string &)) &mrpt::config::CLoadableOptions::loadFromConfigFile, "This method load the options from a \".ini\"-like file or memory-stored\n string list.\n Only those parameters found in the given \"section\" and having\n the same name that the variable are loaded. Those not found in\n the file will stay with their previous values (usually the default\n values loaded at initialization). An example of an \".ini\" file:\n \n\n\n\n\n\n \n loadFromConfigFileName, saveToConfigFile\n\nC++: mrpt::config::CLoadableOptions::loadFromConfigFile(const class mrpt::config::CConfigFileBase &, const std::string &) --> void", pybind11::arg("source"), pybind11::arg("section")); diff --git a/python/src/mrpt/hwdrivers/CNTRIPClient.cpp b/python/src/mrpt/hwdrivers/CNTRIPClient.cpp index 2440654c69..238eb4ff34 100644 --- a/python/src/mrpt/hwdrivers/CNTRIPClient.cpp +++ b/python/src/mrpt/hwdrivers/CNTRIPClient.cpp @@ -355,7 +355,7 @@ void bind_mrpt_hwdrivers_CNTRIPClient(std::function< pybind11::module &(std::str } { // mrpt::hwdrivers::CNTRIPEmitter file:mrpt/hwdrivers/CNTRIPEmitter.h line:62 - pybind11::class_, PyCallBack_mrpt_hwdrivers_CNTRIPEmitter, mrpt::hwdrivers::CGenericSensor> cl(M("mrpt::hwdrivers"), "CNTRIPEmitter", "This \"virtual driver\" encapsulates a NTRIP client (see CNTRIPClient) but\n adds the functionality of dumping the received datastream to a given serial\n port.\n Used within rawlog-grabber, along CGPSInterface, this class allows one to build\n a powerful & simple RTK-capable GPS receiver system.\n\n Therefore, this sensor will never \"collect\" any observation via the\n CGenericSensor interface.\n\n See also the example configuration file for rawlog-grabber in\n \"share/mrpt/config_files/rawlog-grabber\".\n\n \n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n The next picture summarizes existing MRPT classes related to GPS / GNSS\n devices (CGPSInterface, CNTRIPEmitter, CGPS_NTRIP):\n\n \n\n \n\n \n CGPSInterface, CGPS_NTRIP, CNTRIPClient"); + pybind11::class_, PyCallBack_mrpt_hwdrivers_CNTRIPEmitter, mrpt::hwdrivers::CGenericSensor> cl(M("mrpt::hwdrivers"), "CNTRIPEmitter", "This \"virtual driver\" encapsulates a NTRIP client (see CNTRIPClient) but\n adds the functionality of dumping the received datastream to a given serial\n port.\n Used within rawlog-grabber, along CGPSInterface, this class allows one to\n build a powerful & simple RTK-capable GPS receiver system.\n\n Therefore, this sensor will never \"collect\" any observation via the\n CGenericSensor interface.\n\n See also the example configuration file for rawlog-grabber in\n \"share/mrpt/config_files/rawlog-grabber\".\n\n \n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n The next picture summarizes existing MRPT classes related to GPS / GNSS\n devices (CGPSInterface, CNTRIPEmitter, CGPS_NTRIP):\n\n \n\n \n\n \n CGPSInterface, CGPS_NTRIP, CNTRIPClient"); cl.def( pybind11::init( [](){ return new mrpt::hwdrivers::CNTRIPEmitter(); }, [](){ return new PyCallBack_mrpt_hwdrivers_CNTRIPEmitter(); } ) ); cl.def("GetRuntimeClass", (const struct mrpt::hwdrivers::TSensorClassId * (mrpt::hwdrivers::CNTRIPEmitter::*)() const) &mrpt::hwdrivers::CNTRIPEmitter::GetRuntimeClass, "C++: mrpt::hwdrivers::CNTRIPEmitter::GetRuntimeClass() const --> const struct mrpt::hwdrivers::TSensorClassId *", pybind11::return_value_policy::automatic); cl.def_static("CreateObject", (class mrpt::hwdrivers::CGenericSensor * (*)()) &mrpt::hwdrivers::CNTRIPEmitter::CreateObject, "C++: mrpt::hwdrivers::CNTRIPEmitter::CreateObject() --> class mrpt::hwdrivers::CGenericSensor *", pybind11::return_value_policy::automatic); diff --git a/python/src/mrpt/poses/CPose3DPDF.cpp b/python/src/mrpt/poses/CPose3DPDF.cpp index 73668b4fd3..472022c93b 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 6655851d93..3f249106bc 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_, PyCallBack_mrpt_poses_CPose3DPDFGrid, mrpt::poses::CPose3DPDF, mrpt::poses::CPose3DGridTemplate> 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 d0b98b04a5..c3d2a60017 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_, 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 c50d72dee3..4671c88a64 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; }); } } diff --git a/python/src/std/stl_deque.cpp b/python/src/std/stl_deque.cpp index 4c59840342..6e96f8eb27 100644 --- a/python/src/std/stl_deque.cpp +++ b/python/src/std/stl_deque.cpp @@ -23,7 +23,7 @@ PYBIND11_MAKE_OPAQUE(std::deque &M) { - { // std::deque file:bits/stl_deque.h line:766 + { // std::deque file:bits/stl_deque.h line:767 pybind11::class_>, std::shared_ptr>>> cl(M("std"), "deque_mrpt_bayes_CProbabilityParticle_mrpt_math_TPose3D_mrpt_bayes_particle_storage_mode_VALUE_t", ""); cl.def( pybind11::init( [](){ return new std::deque>(); } ) ); cl.def( pybind11::init > &>(), pybind11::arg("__a") ); @@ -62,7 +62,7 @@ void bind_std_stl_deque(std::function< pybind11::module &(std::string const &nam }, pybind11::keep_alive<0, 1>()); } - { // std::deque file:bits/stl_deque.h line:766 + { // std::deque file:bits/stl_deque.h line:767 pybind11::class_>, std::shared_ptr>>> cl(M("std"), "deque_mrpt_bayes_CProbabilityParticle_mrpt_math_TPose2D_mrpt_bayes_particle_storage_mode_VALUE_t", ""); cl.def( pybind11::init( [](){ return new std::deque>(); } ) ); cl.def( pybind11::init > &>(), pybind11::arg("__a") ); diff --git a/python/src/std/stl_deque_1.cpp b/python/src/std/stl_deque_1.cpp index 69668158ed..3fe005dcf4 100644 --- a/python/src/std/stl_deque_1.cpp +++ b/python/src/std/stl_deque_1.cpp @@ -31,7 +31,7 @@ PYBIND11_MAKE_OPAQUE(std::deque &M) { - { // std::deque file:bits/stl_deque.h line:766 + { // std::deque file:bits/stl_deque.h line:767 pybind11::class_, std::shared_ptr>> cl(M("std"), "deque_mrpt_math_TPose3D_t", ""); cl.def( pybind11::init( [](){ return new std::deque(); } ) ); cl.def( pybind11::init &>(), pybind11::arg("__a") ); @@ -70,7 +70,7 @@ void bind_std_stl_deque_1(std::function< pybind11::module &(std::string const &n }, pybind11::keep_alive<0, 1>()); } - { // std::deque file:bits/stl_deque.h line:766 + { // std::deque file:bits/stl_deque.h line:767 pybind11::class_>, std::shared_ptr>>> cl(M("std"), "deque_mrpt_bayes_CProbabilityParticle_mrpt_maps_CRBPFParticleData_mrpt_bayes_particle_storage_mode_POINTER_t", ""); cl.def( pybind11::init( [](){ return new std::deque>(); } ) ); cl.def( pybind11::init > &>(), pybind11::arg("__a") ); diff --git a/python/src/std/stl_deque_2.cpp b/python/src/std/stl_deque_2.cpp index 3ad4f52e77..744ff62ac6 100644 --- a/python/src/std/stl_deque_2.cpp +++ b/python/src/std/stl_deque_2.cpp @@ -20,7 +20,7 @@ PYBIND11_MAKE_OPAQUE(std::deque) void bind_std_stl_deque_2(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // std::deque file:bits/stl_deque.h line:766 + { // std::deque file:bits/stl_deque.h line:767 pybind11::class_, std::shared_ptr>> cl(M("std"), "deque_mrpt_system_CDirectoryExplorer_TFileInfo_t", ""); cl.def( pybind11::init( [](){ return new std::deque(); } ) ); cl.def( pybind11::init &>(), pybind11::arg("__a") ); diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi index 6d716eb800..001eab5d16 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi @@ -1134,12 +1134,14 @@ class CPose3DPDFGaussian(CPose3DPDF, mrpt.pymrpt.mrpt.Stringifyable): def saveToTextFile(self, file: str) -> bool: ... @overload def saveToTextFile(conststd) -> bool: ... + def __add__(self, arg0: CPose3DPDFGaussian) -> CPose3DPDFGaussian: ... @overload def __iadd__(self, Ap: CPose3D) -> None: ... @overload def __iadd__(self, Ap: CPose3DPDFGaussian) -> None: ... def __isub__(self, Ap: CPose3DPDFGaussian) -> None: ... def __neg__(self) -> CPose3DPDFGaussian: ... + def __sub__(self, arg0: CPose3DPDFGaussian) -> CPose3DPDFGaussian: ... class CPose3DPDFGaussianInf(CPose3DPDF): cov_inv: mrpt.pymrpt.mrpt.math.CMatrixFixed_double_6UL_6UL_t @@ -1216,12 +1218,14 @@ class CPose3DPDFGaussianInf(CPose3DPDF): def saveToTextFile(self, file: str) -> bool: ... @overload def saveToTextFile(conststd) -> bool: ... + def __add__(self, arg0: CPose3DPDFGaussianInf) -> CPose3DPDFGaussianInf: ... @overload def __iadd__(self, Ap: CPose3D) -> None: ... @overload def __iadd__(self, Ap: CPose3DPDFGaussianInf) -> None: ... def __isub__(self, Ap: CPose3DPDFGaussianInf) -> None: ... def __neg__(self) -> CPose3DPDFGaussianInf: ... + def __sub__(self, arg0: CPose3DPDFGaussianInf) -> CPose3DPDFGaussianInf: ... class CPose3DPDFGrid(CPose3DPDF, CPose3DGridTemplate_double_t): @overload @@ -1667,12 +1671,14 @@ class CPose3DQuatPDFGaussianInf(CPose3DQuatPDF): def saveToTextFile(self, file: str) -> bool: ... @overload def saveToTextFile(conststd) -> bool: ... + def __add__(self, arg0: CPose3DQuatPDFGaussianInf) -> CPose3DQuatPDFGaussianInf: ... @overload def __iadd__(self, Ap: CPose3DQuat) -> None: ... @overload def __iadd__(self, Ap: CPose3DQuatPDFGaussianInf) -> None: ... def __isub__(self, Ap: CPose3DQuatPDFGaussianInf) -> None: ... def __neg__(self) -> CPose3DQuatPDFGaussianInf: ... + def __sub__(self, arg0: CPose3DQuatPDFGaussianInf) -> CPose3DQuatPDFGaussianInf: ... class CPoseInterpolatorBase_2_t: @overload @@ -2134,11 +2140,13 @@ class CPosePDFGaussian(CPosePDF): def saveToTextFile(self, file: str) -> bool: ... @overload def saveToTextFile(conststd) -> bool: ... + def __add__(self, arg0: CPosePDFGaussian) -> CPosePDFGaussian: ... @overload def __iadd__(self, Ap: CPose2D) -> None: ... @overload def __iadd__(self, Ap: CPosePDFGaussian) -> None: ... def __isub__(self, ref: CPosePDFGaussian) -> None: ... + def __sub__(self, arg0: CPosePDFGaussian) -> CPosePDFGaussian: ... class CPosePDFGaussianInf(CPosePDF): cov_inv: mrpt.pymrpt.mrpt.math.CMatrixFixed_double_3UL_3UL_t @@ -2225,11 +2233,13 @@ class CPosePDFGaussianInf(CPosePDF): def saveToTextFile(self, file: str) -> bool: ... @overload def saveToTextFile(conststd) -> bool: ... + def __add__(self, arg0: CPosePDFGaussianInf) -> CPosePDFGaussianInf: ... @overload def __iadd__(self, Ap: CPose2D) -> None: ... @overload def __iadd__(self, Ap: CPosePDFGaussianInf) -> None: ... def __isub__(self, ref: CPosePDFGaussianInf) -> None: ... + def __sub__(self, arg0: CPosePDFGaussianInf) -> CPosePDFGaussianInf: ... class CPosePDFGrid(CPosePDF, CPose2DGridTemplate_double_t): @overload