From a57e0f3f5ce178a93a0c8d0a75683d3196e2937f Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Thu, 10 Aug 2023 09:15:56 +0200 Subject: [PATCH 01/31] version bump --- appveyor.yml | 2 +- doc/source/doxygen-docs/changelog.md | 3 +++ package.xml | 2 +- version_prefix.txt | 2 +- 4 files changed, 6 insertions(+), 3 deletions(-) diff --git a/appveyor.yml b/appveyor.yml index 14d6df7eb0..6ce5b36598 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -1,5 +1,5 @@ # version format -version: 2.10.1-{branch}-build{build} +version: 2.10.2-{branch}-build{build} os: Visual Studio 2019 diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 5a5240700e..697d66f255 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -1,5 +1,8 @@ \page changelog Change Log +# Version 2.10.2: UNRELEASED +(No changes yet) + # Version 2.10.1: Released August 10th, 2023 - Build system: - Add cmake flag to disable LTO in pymrpt module. diff --git a/package.xml b/package.xml index ea2dd0cbea..8a605117d2 100644 --- a/package.xml +++ b/package.xml @@ -7,7 +7,7 @@ mrpt2 - 2.10.1 + 2.10.2 Mobile Robot Programming Toolkit (MRPT) version 2.x Jose-Luis Blanco-Claraco diff --git a/version_prefix.txt b/version_prefix.txt index 3ca07415ec..6ce7473c51 100644 --- a/version_prefix.txt +++ b/version_prefix.txt @@ -1,4 +1,4 @@ -2.10.1 +2.10.2 # IMPORTANT: This file is parsed by CMake, don't add any comment to # the first line. # This file is used in both Windows and Linux scripts to automatically From afda967b07745c16d8c4a2a649a2709b0f8183e4 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Thu, 10 Aug 2023 09:43:06 +0200 Subject: [PATCH 02/31] Fix C linkage build error in CSparse --- doc/source/doxygen-docs/changelog.md | 3 ++- libs/math/include/mrpt/math/CSparseMatrix.h | 10 +++------- 2 files changed, 5 insertions(+), 8 deletions(-) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 697d66f255..5fbdc117a7 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -1,7 +1,8 @@ \page changelog Change Log # Version 2.10.2: UNRELEASED -(No changes yet) +- BUG FIXES: + - Fix CSparse "C" linkage build error (OSX Clang) # Version 2.10.1: Released August 10th, 2023 - Build system: diff --git a/libs/math/include/mrpt/math/CSparseMatrix.h b/libs/math/include/mrpt/math/CSparseMatrix.h index 43609454e6..4d6467e369 100644 --- a/libs/math/include/mrpt/math/CSparseMatrix.h +++ b/libs/math/include/mrpt/math/CSparseMatrix.h @@ -19,18 +19,14 @@ #include // Include CSparse lib headers, either from the system or embedded: -extern "C" -{ #if MRPT_HAS_SUITESPARSE -#define NCOMPLEX // In MRPT we don't need complex numbers, so avoid the -// annoying warning: 'cs_ci_house' has C-linkage specified, -// but returns UDT 'std::complex' which is -// incompatible with C #include "cs.h" #else +extern "C" +{ #include -#endif } +#endif namespace mrpt::math { From 78a12f4da8d471494832f38e76ba0e85bda3a5d6 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Fri, 11 Aug 2023 10:48:05 +0200 Subject: [PATCH 03/31] Progress fixing missing wrapped python operators --- python-examples/ros-poses-convert.py | 4 ++++ python/python.conf | 4 +++- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/python-examples/ros-poses-convert.py b/python-examples/ros-poses-convert.py index 1ecbd7a237..5a61484ec5 100755 --- a/python-examples/ros-poses-convert.py +++ b/python-examples/ros-poses-convert.py @@ -66,3 +66,7 @@ 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 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&) From f7c21dbaf8b4114c1cd7a3e6f16349da8ad5b735 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 16 Aug 2023 01:24:05 +0200 Subject: [PATCH 04/31] Update python generation scripts for latest gcc --- python/generate-python-stubs.sh | 2 +- python/generate-python.sh | 4 ++-- python/patch-001.diff | 6 +++--- python/patch-007.diff | 4 ++-- python/src/mrpt/config/CLoadableOptions.cpp | 6 +++--- python/src/mrpt/hwdrivers/CNTRIPClient.cpp | 2 +- python/src/std/stl_deque.cpp | 4 ++-- python/src/std/stl_deque_1.cpp | 4 ++-- python/src/std/stl_deque_2.cpp | 2 +- 9 files changed, 17 insertions(+), 17 deletions(-) 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/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/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") ); From 5e0917c48363b143ad597d2d5a12bcb2c834f08c Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 16 Aug 2023 01:57:18 +0200 Subject: [PATCH 05/31] Wrap add/substract operators for poses PDFs --- python/patch-009.diff | 63 +++++++++++++++++++ python/src/mrpt/poses/CPose3DPDF.cpp | 3 + .../src/mrpt/poses/CPose3DPDFGaussianInf.cpp | 3 + .../mrpt/poses/CPose3DQuatPDFGaussianInf.cpp | 6 ++ python/src/mrpt/poses/CPosePDFGaussian.cpp | 3 + 5 files changed, 78 insertions(+) create mode 100644 python/patch-009.diff 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/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; }); } } From e231f91d1f98f3098f52c508762dbd8715cfb8ce Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 16 Aug 2023 01:59:23 +0200 Subject: [PATCH 06/31] Nanogui: bump minimum required cmake version to 3.5 --- 3rdparty/nanogui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 From 32de463e60966cf813fb5d2247e9b3e593b5776a Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 16 Aug 2023 02:04:14 +0200 Subject: [PATCH 07/31] Update python stubs --- python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi | 10 ++++++++++ 1 file changed, 10 insertions(+) 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 From 95c01d49a2704010ce4a506e1928678f73502820 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 16 Aug 2023 02:08:48 +0200 Subject: [PATCH 08/31] Minimal demo of PDF pose composition --- python-examples/ros-poses-convert.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/python-examples/ros-poses-convert.py b/python-examples/ros-poses-convert.py index 5a61484ec5..e26075dbe9 100755 --- a/python-examples/ros-poses-convert.py +++ b/python-examples/ros-poses-convert.py @@ -70,3 +70,5 @@ a = mr3 b = mr3 c = a+b + +print('r3b (+) rb3 : ' + str(c)) From faa430a1cb4352c644cc418d561f888aa02c0e16 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 16 Aug 2023 02:12:16 +0200 Subject: [PATCH 09/31] changelog --- doc/source/doxygen-docs/changelog.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) 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: From fb162809f1ccc8ebd95db5b09f29b472eab7becd Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 16 Aug 2023 02:46:28 +0200 Subject: [PATCH 10/31] Fix make clean for latex docs --- doc/graphslam-engine-guide/Makefile | 1 + 1 file changed, 1 insertion(+) diff --git a/doc/graphslam-engine-guide/Makefile b/doc/graphslam-engine-guide/Makefile index 9bc6438caf..54758c5fa7 100644 --- a/doc/graphslam-engine-guide/Makefile +++ b/doc/graphslam-engine-guide/Makefile @@ -24,4 +24,5 @@ graphslam-engine-guide.ps.gz: graphslam-engine-guide.pdf clean: latexmk -CA + rm *.bbl *.nlo From fcaa51714f2bb297b4d719f9f93b246bfecf8b5b Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Thu, 17 Aug 2023 17:38:51 +0200 Subject: [PATCH 11/31] rawlog-edit: remap timestamps now can filter by label --- 3rdparty/nanogui | 2 +- doc/source/doxygen-docs/changelog.md | 2 + libs/apps/src/RawlogEditApp.cpp | 11 +++- .../apps/src/rawlog-edit_remap_timestamps.cpp | 62 ++++++++++++++++--- 4 files changed, 68 insertions(+), 9 deletions(-) diff --git a/3rdparty/nanogui b/3rdparty/nanogui index eb8b089f56..2bf2c17a63 160000 --- a/3rdparty/nanogui +++ b/3rdparty/nanogui @@ -1 +1 @@ -Subproject commit eb8b089f56af06c0423b45213d25bf8201a1c2ba +Subproject commit 2bf2c17a63cf9482e030e8b218dc0c1aee4c1b60 diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index ae2f269f8a..329338e1f5 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -1,6 +1,8 @@ \page changelog Change Log # Version 2.10.2: UNRELEASED +- Changes in apps: + - rawlog-edit: Add `--select-label` optional filter to command `--remap-timestamps`. - BUG FIXES: - 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) diff --git a/libs/apps/src/RawlogEditApp.cpp b/libs/apps/src/RawlogEditApp.cpp index bda1a9fab8..d49debe6fa 100644 --- a/libs/apps/src/RawlogEditApp.cpp +++ b/libs/apps/src/RawlogEditApp.cpp @@ -170,6 +170,13 @@ TCLAP::SwitchArg arg_overwrite( "w", "overwrite", "Force overwrite target file without prompting.", cmd, false); +TCLAP::ValueArg arg_select_label( + "", "select-label", + "Select one sensor label on which to apply the operation.\n" + "Several labels can be provided separated by commas.\n" + "Only for those ops that mention --select-label as optional.", + false, "", "label[,label...]", cmd); + TCLAP::SwitchArg arg_quiet("q", "quiet", "Terse output", cmd, false); void RawlogEditApp::run(int argc, const char** argv) @@ -232,8 +239,10 @@ void RawlogEditApp::run(int argc, const char** argv) "'a*t+b'." "The parameters 'a' and 'b' must be given separated with a " "semicolon.\n" + "Optional: --select-label LABEL1[,LABEL2] to limit the operation to " + "those sensors only.\n" "Requires: -o (or --output)", - false, "", "a;b", cmd)); + false, "", "\"a;b\"", cmd)); ops_functors["remap-timestamps"] = &op_remap_timestamps; arg_ops.push_back(std::make_unique( diff --git a/libs/apps/src/rawlog-edit_remap_timestamps.cpp b/libs/apps/src/rawlog-edit_remap_timestamps.cpp index 36ab4a66b1..8f9abca9c5 100644 --- a/libs/apps/src/rawlog-edit_remap_timestamps.cpp +++ b/libs/apps/src/rawlog-edit_remap_timestamps.cpp @@ -32,30 +32,67 @@ DECLARE_OP_FUNCTION(op_remap_timestamps) protected: TOutputRawlogCreator outrawlog; const double m_a, m_b; + const std::set m_labels; //!< empty: all sensors + size_t m_changes = 0; public: CRawlogProcessor_RemapTimestamps( CFileGZInputStream& in_rawlog, TCLAP::CmdLine& cmdline, - bool Verbose, double a, double b) + bool Verbose, double a, double b, + const std::set& labels) : CRawlogProcessorOnEachObservation(in_rawlog, cmdline, Verbose), m_a(a), - m_b(b) + m_b(b), + m_labels(labels) { - VERBOSE_COUT << "Applying timestamps remap a*t+b with: a=" << m_a - << " b=" << m_b << endl; + VERBOSE_COUT + << mrpt::format( + "Applying timestamps remap a*t+b with: a=%f b=%f", m_a, + m_b) + << std::endl; + + std::string sLog = "Applying to sensor labels: "; + if (m_labels.empty()) { sLog += " (all)\n"; } + else + { + for (const auto& l : m_labels) + { + sLog += "'"; + sLog += l; + sLog += "', "; + } + sLog += "\n"; + } + VERBOSE_COUT << sLog; + } + + ~CRawlogProcessor_RemapTimestamps() + { + VERBOSE_COUT << "Changed objects: " << m_changes << "\n"; + } + + bool checkSensorLabel(const CObservation::Ptr& obs) + { + if (m_labels.empty()) return true; + return m_labels.count(obs->sensorLabel) != 0; } bool processOneObservation(CObservation::Ptr& obs) override { + // does it apply? + if (!checkSensorLabel(obs)) return true; + // T_NEW = a * T_OLD + b const double t = mrpt::system::timestampToDouble(obs->timestamp); const double t_new = m_a * t + m_b; obs->timestamp = mrpt::system::time_tToTimestamp(t_new); + + m_changes++; return true; } - // This method can be reimplemented to save the modified object to an - // output stream. + // This method can be reimplemented to save the modified object to + // an output stream. void OnPostProcess( mrpt::obs::CActionCollection::Ptr& actions, mrpt::obs::CSensoryFrame::Ptr& SF, @@ -85,9 +122,20 @@ DECLARE_OP_FUNCTION(op_remap_timestamps) const double a = atof(sAB_tokens[0].c_str()); const double b = atof(sAB_tokens[1].c_str()); + string filter_labels; + getArgValue(cmdline, "select-label", filter_labels); + + std::vector lbs; + mrpt::system::tokenize(filter_labels, ";", lbs); + + std::set applyLabels; + for (const auto& l : lbs) + applyLabels.insert(l); + // Process // --------------------------------- - CRawlogProcessor_RemapTimestamps proc(in_rawlog, cmdline, verbose, a, b); + CRawlogProcessor_RemapTimestamps proc( + in_rawlog, cmdline, verbose, a, b, applyLabels); proc.doProcessRawlog(); // Dump statistics: From 34077ec74a90b593b587f2057d3280ea520a3609 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Thu, 17 Aug 2023 17:39:54 +0200 Subject: [PATCH 12/31] Fix separator --- libs/apps/src/rawlog-edit_remap_timestamps.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libs/apps/src/rawlog-edit_remap_timestamps.cpp b/libs/apps/src/rawlog-edit_remap_timestamps.cpp index 8f9abca9c5..e6a6b4e1fd 100644 --- a/libs/apps/src/rawlog-edit_remap_timestamps.cpp +++ b/libs/apps/src/rawlog-edit_remap_timestamps.cpp @@ -126,7 +126,7 @@ DECLARE_OP_FUNCTION(op_remap_timestamps) getArgValue(cmdline, "select-label", filter_labels); std::vector lbs; - mrpt::system::tokenize(filter_labels, ";", lbs); + mrpt::system::tokenize(filter_labels, ",", lbs); std::set applyLabels; for (const auto& l : lbs) From 87e3c6c5056434ed0065932523f7d4a6c05a90ba Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Sat, 26 Aug 2023 01:24:00 +0200 Subject: [PATCH 13/31] sync: nanogui requires more recent cmake version --- 3rdparty/nanogui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 From 99ccdab0ae7acd70a8a15e36f94ed324381698ff Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Sat, 26 Aug 2023 01:45:09 +0200 Subject: [PATCH 14/31] Remove leftover trace --- doc/source/doxygen-docs/changelog.md | 2 ++ libs/ros1bridge/src/map.cpp | 1 - libs/ros2bridge/src/map.cpp | 1 - 3 files changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 329338e1f5..0ba13b8ed4 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -3,6 +3,8 @@ # Version 2.10.2: UNRELEASED - Changes in apps: - rawlog-edit: Add `--select-label` optional filter to command `--remap-timestamps`. +- Changes in libraries: + - mrpt-ros1bridge and mrpt-ros2bridge: Remove leftover printf debugging trace printing ``Ok`` to console. - BUG FIXES: - 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) diff --git a/libs/ros1bridge/src/map.cpp b/libs/ros1bridge/src/map.cpp index 7a5b7123e3..4cbabbf02f 100644 --- a/libs/ros1bridge/src/map.cpp +++ b/libs/ros1bridge/src/map.cpp @@ -188,7 +188,6 @@ bool MapHdl::loadMap( if (_debug) printf("Loading '.simplemap' file..."); CFileGZInputStream f(_map_file); mrpt::serialization::archiveFrom(f) >> simpleMap; - printf("Ok\n"); ASSERTMSG_( simpleMap.size() > 0, diff --git a/libs/ros2bridge/src/map.cpp b/libs/ros2bridge/src/map.cpp index 81b931e49b..a52005efe7 100644 --- a/libs/ros2bridge/src/map.cpp +++ b/libs/ros2bridge/src/map.cpp @@ -188,7 +188,6 @@ bool MapHdl::loadMap( if (_debug) printf("Loading '.simplemap' file..."); CFileGZInputStream f(_map_file); mrpt::serialization::archiveFrom(f) >> simpleMap; - printf("Ok\n"); ASSERTMSG_( simpleMap.size() > 0, From 7ad256c5b5d513df44410cb4843de6289177fffb Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 28 Aug 2023 00:13:36 +0200 Subject: [PATCH 15/31] pip freeze for doc generation --- doc/requirements.txt | 37 ++++++++++++++++++++++++++++++++----- 1 file changed, 32 insertions(+), 5 deletions(-) diff --git a/doc/requirements.txt b/doc/requirements.txt index 57406373db..fcf73a604f 100644 --- a/doc/requirements.txt +++ b/doc/requirements.txt @@ -1,5 +1,32 @@ -sphinx_rtd_theme -sphinx_design -sphinxcontrib-bibtex -mistune<2.0.0 -m2r2 +alabaster==0.7.13 +Babel==2.12.1 +certifi==2023.7.22 +charset-normalizer==3.2.0 +docutils==0.17.1 +idna==3.4 +imagesize==1.4.1 +Jinja2==3.1.2 +latexcodec==2.0.1 +m2r2==0.3.2 +MarkupSafe==2.1.3 +mistune==0.8.4 +packaging==23.1 +pybtex==0.24.0 +pybtex-docutils==1.0.3 +Pygments==2.16.1 +PyYAML==6.0.1 +requests==2.31.0 +six==1.16.0 +snowballstemmer==2.2.0 +Sphinx==5.3.0 +sphinx-rtd-theme==1.3.0 +sphinx_design==0.5.0 +sphinxcontrib-applehelp==1.0.7 +sphinxcontrib-bibtex==2.6.1 +sphinxcontrib-devhelp==1.0.5 +sphinxcontrib-htmlhelp==2.0.4 +sphinxcontrib-jquery==4.1 +sphinxcontrib-jsmath==1.0.1 +sphinxcontrib-qthelp==1.0.6 +sphinxcontrib-serializinghtml==1.1.9 +urllib3==2.0.4 From d67230dd7bcde60b2a67564835e866d8095bb834 Mon Sep 17 00:00:00 2001 From: Michal Sojka Date: Sun, 3 Sep 2023 09:49:56 +0200 Subject: [PATCH 16/31] ros: Add missing dependencies Without these, the package cannot be built on NixOS. --- doc/source/doxygen-docs/changelog.md | 2 ++ package.xml | 3 +++ 2 files changed, 5 insertions(+) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 0ba13b8ed4..9d96abd330 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -8,6 +8,8 @@ - BUG FIXES: - 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) +- Build system: + - ROS: fix missing deps in package.xml needed for build via Nix. # Version 2.10.1: Released August 10th, 2023 - Build system: diff --git a/package.xml b/package.xml index 8a605117d2..844cf5fe7c 100644 --- a/package.xml +++ b/package.xml @@ -26,6 +26,7 @@ libxrandr libxxf86vm nav_msgs + opengl sensor_msgs std_msgs stereo_msgs @@ -40,12 +41,14 @@ assimp-dev ffmpeg libfreenect-dev + libfyaml-dev libjpeg libjsoncpp-dev libopenni2-dev libpcap libudev-dev libusb-1.0-dev + pkg-config pybind11-dev python3-pip tinyxml2 From ee3f2fb6638e568d03d4ee651637ac130abf96f7 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Tue, 5 Sep 2023 00:41:01 +0200 Subject: [PATCH 17/31] Add contributors badge --- README.md | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 8b0a9669d6..4d39e56ec0 100644 --- a/README.md +++ b/README.md @@ -27,7 +27,7 @@ and [much more](https://docs.mrpt.org/reference/latest/applications.html). ## 2. Resources * Download the latest unstable code with: `git clone https://github.com/MRPT/mrpt.git --recursive` - * Ask questions at: [this Google group](https://www.mrpt.org/forum/) or at [stackoverflow](https://stackoverflow.com/search?q=mrpt) (please, use the tag `mrpt`!) + * Ask questions at [stackoverflow](https://stackoverflow.com/search?q=mrpt) (use the tag `mrpt`) * [Main project website](https://www.mrpt.org/), including [sources and Windows installer downloads](https://www.mrpt.org/download-mrpt/) * [C++ API reference](https://docs.mrpt.org/reference/) * [ROS packages](https://docs.mrpt.org/reference/latest/wrappers.html#mrpt-ros-packages) @@ -92,6 +92,13 @@ sudo apt install ros-$ROS_DISTRO-mrpt2 ## 4. License MRPT is released under the [new BSD license](http://www.mrpt.org/License/). + +**Contributors** + + + + + ## 5. Versions in repositories ![Repology](https://repology.org/badge/vertical-allrepos/mrpt.svg) From 8882f2b9a2dba53a4d80aa225f990acb4fa5a7e6 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 11 Sep 2023 11:59:36 +0200 Subject: [PATCH 18/31] Use 2 hex digits per version part --- CMakeLists.txt | 2 +- .../src/mainwindow.cpp | 6 +-- apps/mrpt-performance/perf-main.cpp | 6 +-- cmakemodules/UtilsMacros.cmake | 49 ++++++------------- cmakemodules/script_create_version_h.cmake | 31 ++---------- doc/source/doxygen-docs/changelog.md | 2 + .../src/CCascadeClassifierDetection.cpp | 10 ++-- .../mrpt/3rdparty/do_opencv_includes.h | 6 +-- libs/img/src/CImage.cpp | 2 +- libs/vision/src/CFeatureExtraction_AKAZE.cpp | 8 +-- libs/vision/src/CFeatureExtraction_FAST.cpp | 2 +- libs/vision/src/CFeatureExtraction_ORB.cpp | 4 +- libs/vision/src/CFeatureExtraction_SIFT.cpp | 12 ++--- libs/vision/src/CFeatureExtraction_SURF.cpp | 6 +-- .../src/CFeatureExtraction_logPolarImg.cpp | 4 +- .../src/CFeatureExtraction_polarImg.cpp | 4 +- libs/vision/src/pnp/pnp_unittest.cpp | 2 +- parse-files/version.h.in | 2 +- 18 files changed, 58 insertions(+), 100 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 0f11be5de4..6bcfbe1511 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -8,7 +8,7 @@ # For compiling instructions for all compilers and platforms, see # https://docs.mrpt.org/reference/latest/compiling.html # -# 2007-2021, Jose Luis Blanco +# 2007-2023, Jose Luis Blanco # ---------------------------------------------------------------------------- # ------------------------- diff --git a/apps/benchmarking-image-features/src/mainwindow.cpp b/apps/benchmarking-image-features/src/mainwindow.cpp index 30a467c114..d654ffd92a 100644 --- a/apps/benchmarking-image-features/src/mainwindow.cpp +++ b/apps/benchmarking-image-features/src/mainwindow.cpp @@ -187,7 +187,7 @@ void MainWindow::on_button_generate_clicked() xData.at(i) = i; yData.at(i) = distances(i, 0); } -#if MRPT_OPENCV_VERSION_NUM >= 0x330 +#if MRPT_OPENCV_VERSION_NUM >= 0x030300 plot = plot::Plot2d::create(xData, yData); #else plot = plot::createPlot2d(xData, yData); @@ -384,7 +384,7 @@ void MainWindow::on_button_generate_clicked() min_y = -1; } -#if MRPT_OPENCV_VERSION_NUM >= 0x330 +#if MRPT_OPENCV_VERSION_NUM >= 0x030300 plot = plot::Plot2d::create(xData, yData); #else plot = plot::createPlot2d(xData, yData); @@ -439,7 +439,7 @@ void MainWindow::on_button_generate_clicked() else yData.at(i) = v2_surf.at(i); } -#if MRPT_OPENCV_VERSION_NUM >= 0x330 +#if MRPT_OPENCV_VERSION_NUM >= 0x030300 plot = plot::Plot2d::create(xData, yData); #else plot = plot::createPlot2d(xData, yData); diff --git a/apps/mrpt-performance/perf-main.cpp b/apps/mrpt-performance/perf-main.cpp index 913a4a8f5f..95549e1672 100644 --- a/apps/mrpt-performance/perf-main.cpp +++ b/apps/mrpt-performance/perf-main.cpp @@ -269,9 +269,9 @@ int main(int argc, char** argv) const string fil_name = PERF_DATA_DIR + mrpt::format("/perf-results-%i.%i.%i%s-%s-%ibit.dat", - int((MRPT_VERSION >> 8) & 0x0F), - int((MRPT_VERSION >> 4) & 0x0F), - int((MRPT_VERSION >> 0) & 0x0F), version_postfix, + int((MRPT_VERSION >> 16) & 0xFF), + int((MRPT_VERSION >> 8) & 0xFF), + int((MRPT_VERSION >> 0) & 0xFF), version_postfix, compiler_name, int(MRPT_WORD_SIZE)); cout << "Saving perf-data to: " << fil_name << endl; CFileOutputStream f(fil_name); diff --git a/cmakemodules/UtilsMacros.cmake b/cmakemodules/UtilsMacros.cmake index 247f03ae87..d94747b1e1 100644 --- a/cmakemodules/UtilsMacros.cmake +++ b/cmakemodules/UtilsMacros.cmake @@ -57,42 +57,21 @@ macro(pkgconfig_parse _FLAGS _OUT_PREFIX) endforeach(str) endmacro(pkgconfig_parse ) -# Convert a decimal value [0,15] to hexadecimal -# From: http://stackoverflow.com/questions/26182289/convert-from-decimal-to-hexadecimal-in-cmake -macro(DECCHAR2HEX VAR VAL) - if (${VAL} LESS 10) - set(${VAR} ${VAL}) - elseif(${VAL} EQUAL 10) - set(${VAR} "A") - elseif(${VAL} EQUAL 11) - set(${VAR} "B") - elseif(${VAL} EQUAL 12) - set(${VAR} "C") - elseif(${VAL} EQUAL 13) - set(${VAR} "D") - elseif(${VAL} EQUAL 14) - set(${VAR} "E") - elseif(${VAL} EQUAL 15) - set(${VAR} "F") - else(${VAL} LESS 10) - message(FATAL_ERROR "Invalid format for hexidecimal character") - endif(${VAL} LESS 10) -endmacro(DECCHAR2HEX) - -# Converts a version like "1.2.3" into a string "0x123" +# Converts a version like "1.2.3" into a string "0x10203", +# or "3.4.19" into "0x30413". # Usage: VERSION_TO_HEXADECIMAL(TARGET_VAR "1.2.3") -macro(VERSION_TO_HEXADECIMAL OUT_VAR IN_VERSION) - string(REGEX MATCHALL "[0-9]+" VERSION_PARTS "${IN_VERSION}") - list(GET VERSION_PARTS 0 VERSION_NUMBER_MAJOR) - list(GET VERSION_PARTS 1 VERSION_NUMBER_MINOR) - list(GET VERSION_PARTS 2 VERSION_NUMBER_PATCH) - # Convert each part to hex: - DECCHAR2HEX(VERSION_NUMBER_MAJOR_HEX ${VERSION_NUMBER_MAJOR}) - DECCHAR2HEX(VERSION_NUMBER_MINOR_HEX ${VERSION_NUMBER_MINOR}) - DECCHAR2HEX(VERSION_NUMBER_PATCH_HEX ${VERSION_NUMBER_PATCH}) - # Concat version string: - set(${OUT_VAR} "0x${VERSION_NUMBER_MAJOR_HEX}${VERSION_NUMBER_MINOR_HEX}${VERSION_NUMBER_PATCH_HEX}") -endmacro(VERSION_TO_HEXADECIMAL) +macro(VERSION_TO_HEXADECIMAL OUT_VAR IN_VERSION) + string(REGEX MATCHALL "[0-9]+" VERSION_PARTS "${IN_VERSION}") + list(GET VERSION_PARTS 0 VERSION_NUMBER_MAJOR) + list(GET VERSION_PARTS 1 VERSION_NUMBER_MINOR) + list(GET VERSION_PARTS 2 VERSION_NUMBER_PATCH) + + # Convert each part to hex: + math(EXPR ${OUT_VAR} + "(${VERSION_NUMBER_MAJOR} << 16) + \ + (${VERSION_NUMBER_MINOR} << 8) + \ + (${VERSION_NUMBER_PATCH})" OUTPUT_FORMAT HEXADECIMAL ) +endmacro() # GOOD & BAD are single strings, INPUT is a list wrapped in string diff --git a/cmakemodules/script_create_version_h.cmake b/cmakemodules/script_create_version_h.cmake index fc2d332625..8006d02d17 100644 --- a/cmakemodules/script_create_version_h.cmake +++ b/cmakemodules/script_create_version_h.cmake @@ -5,31 +5,8 @@ # ---------------------------------------------------------------------------- set(CMAKE_MRPT_COMPLETE_NAME "MRPT ${CMAKE_MRPT_VERSION_NUMBER_MAJOR}.${CMAKE_MRPT_VERSION_NUMBER_MINOR}.${CMAKE_MRPT_VERSION_NUMBER_PATCH}") -# There is no built-in support for dec to hex in cmake, sigh... -function(digit_to_hex DIGIT RET) - if (NOT ${DIGIT} GREATER 9) - set(${RET} ${DIGIT} PARENT_SCOPE) - elseif (${DIGIT} MATCHES "10") - set(${RET} "A" PARENT_SCOPE) - elseif (${DIGIT} MATCHES "11") - set(${RET} "B" PARENT_SCOPE) - elseif (${DIGIT} MATCHES "12") - set(${RET} "C" PARENT_SCOPE) - elseif (${DIGIT} MATCHES "13") - set(${RET} "D" PARENT_SCOPE) - elseif (${DIGIT} MATCHES "14") - set(${RET} "E" PARENT_SCOPE) - elseif (${DIGIT} MATCHES "15") - set(${RET} "F" PARENT_SCOPE) - endif() -endfunction() - -digit_to_hex(${CMAKE_MRPT_VERSION_NUMBER_MAJOR} CMAKE_MRPT_VERSION_NUMBER_MAJOR_HEX) -digit_to_hex(${CMAKE_MRPT_VERSION_NUMBER_MINOR} CMAKE_MRPT_VERSION_NUMBER_MINOR_HEX) -digit_to_hex(${CMAKE_MRPT_VERSION_NUMBER_PATCH} CMAKE_MRPT_VERSION_NUMBER_PATCH_HEX) - -# Build a three digits version code, eg. 0.5.1 -> 051, 1.2.0 -> 120 -set(CMAKE_MRPT_VERSION_CODE "0x${CMAKE_MRPT_VERSION_NUMBER_MAJOR_HEX}${CMAKE_MRPT_VERSION_NUMBER_MINOR_HEX}${CMAKE_MRPT_VERSION_NUMBER_PATCH_HEX}") +# Build a six digits hex version code, eg. 1.2.0 -> 0x010200 +VERSION_TO_HEXADECIMAL(CMAKE_MRPT_VERSION_CODE ${CMAKE_MRPT_COMPLETE_NAME}) # SOURCE_DATE_EPOCH: See Specs in https://reproducible-builds.org/specs/source-date-epoch/ # Take its value from: @@ -80,6 +57,6 @@ if (WIN32) ${MRPT_BINARY_DIR}/version.rc @ONLY) set(MRPT_VERSION_RC_FILE "${MRPT_BINARY_DIR}/version.rc") -else(WIN32) +else() set(MRPT_VERSION_RC_FILE "") -endif (WIN32) +endif() diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 0ba13b8ed4..820e710c24 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -1,6 +1,8 @@ \page changelog Change Log # Version 2.10.2: UNRELEASED +- Build system: + - MRPT and OpenCV versions were until now exposed as macros with 3 hexadecimal digits (e.g. `2.4.0`->`0x240`), with a clear limitation of versions greater than 15. Now, both symbols `MRPT_VERSION` and `MRPT_OPENCV_VERSION_NUM` use TWO hexadecimal digits per version part, like: `2.10.2` -> `0x010A02`, which is much more general and safe for the future. For backwards compatibility, just make sure your user code only uses `MRPT_VERSION>=xxx` or `MRPT_VERSION>xxx` comparisons, instead of less-than comparisons (Fixes [issue #1285](https://github.com/MRPT/mrpt/issues/1285)). - Changes in apps: - rawlog-edit: Add `--select-label` optional filter to command `--remap-timestamps`. - Changes in libraries: diff --git a/libs/detectors/src/CCascadeClassifierDetection.cpp b/libs/detectors/src/CCascadeClassifierDetection.cpp index eb5f672694..3e8372996f 100644 --- a/libs/detectors/src/CCascadeClassifierDetection.cpp +++ b/libs/detectors/src/CCascadeClassifierDetection.cpp @@ -24,7 +24,7 @@ using namespace mrpt::obs; using namespace mrpt::img; using namespace std; -#if MRPT_HAS_OPENCV && MRPT_OPENCV_VERSION_NUM >= 0x200 +#if MRPT_HAS_OPENCV using namespace cv; #endif @@ -38,7 +38,7 @@ using namespace cv; CCascadeClassifierDetection::CCascadeClassifierDetection() { // Check if MRPT is using OpenCV -#if !MRPT_HAS_OPENCV || MRPT_OPENCV_VERSION_NUM < 0x200 +#if !MRPT_HAS_OPENCV THROW_EXCEPTION( "CCascadeClassifierDetection class requires MRPT built against OpenCV " ">=2.0"); @@ -51,7 +51,7 @@ CCascadeClassifierDetection::CCascadeClassifierDetection() CCascadeClassifierDetection::~CCascadeClassifierDetection() { -#if MRPT_HAS_OPENCV && MRPT_OPENCV_VERSION_NUM >= 0x200 +#if MRPT_HAS_OPENCV delete CASCADE; #endif } @@ -63,7 +63,7 @@ CCascadeClassifierDetection::~CCascadeClassifierDetection() void CCascadeClassifierDetection::init( const mrpt::config::CConfigFileBase& config) { -#if MRPT_HAS_OPENCV && MRPT_OPENCV_VERSION_NUM >= 0x200 +#if MRPT_HAS_OPENCV // load configuration values m_options.cascadeFileName = config.read_string("CascadeClassifier", "cascadeFilename", ""); @@ -91,7 +91,7 @@ void CCascadeClassifierDetection::init( void CCascadeClassifierDetection::detectObjects_Impl( const CObservation& obs, vector_detectable_object& detected) { -#if MRPT_HAS_OPENCV && MRPT_OPENCV_VERSION_NUM >= 0x200 +#if MRPT_HAS_OPENCV // Obtain image from generic observation const mrpt::img::CImage* img = nullptr; diff --git a/libs/img/include/mrpt/3rdparty/do_opencv_includes.h b/libs/img/include/mrpt/3rdparty/do_opencv_includes.h index 4eb26dcdad..6138a067ee 100644 --- a/libs/img/include/mrpt/3rdparty/do_opencv_includes.h +++ b/libs/img/include/mrpt/3rdparty/do_opencv_includes.h @@ -18,14 +18,14 @@ // OPENCV HEADERS #define CV_NO_CVV_IMAGE // Avoid CImage name crash -#if MRPT_OPENCV_VERSION_NUM < 0x240 +#if MRPT_OPENCV_VERSION_NUM < 0x020400 #error "MRPT requires OpenCV 2.4.0 or newer" #endif #include // C++ API: -#if MRPT_OPENCV_VERSION_NUM >= 0x300 +#if MRPT_OPENCV_VERSION_NUM >= 0x030000 // C++ API - opencv >=3 #include #include @@ -72,7 +72,7 @@ #endif // Backwards compatible macro: -#if MRPT_OPENCV_VERSION_NUM < 0x344 +#if MRPT_OPENCV_VERSION_NUM < 0x030404 #define cvIplImage(X) (X) #endif diff --git a/libs/img/src/CImage.cpp b/libs/img/src/CImage.cpp index 440a6632de..d6d94cae83 100644 --- a/libs/img/src/CImage.cpp +++ b/libs/img/src/CImage.cpp @@ -2223,7 +2223,7 @@ void CImage::getAsIplImage(IplImage* dest) const #if MRPT_HAS_OPENCV makeSureImageIsLoaded(); -#if MRPT_OPENCV_VERSION_NUM < 0x300 +#if MRPT_OPENCV_VERSION_NUM < 0x030000 ASSERT_(dest != nullptr); *dest = cvIplImage(m_impl->img); #else diff --git a/libs/vision/src/CFeatureExtraction_AKAZE.cpp b/libs/vision/src/CFeatureExtraction_AKAZE.cpp index 46793f2aba..6d25435922 100644 --- a/libs/vision/src/CFeatureExtraction_AKAZE.cpp +++ b/libs/vision/src/CFeatureExtraction_AKAZE.cpp @@ -37,7 +37,7 @@ void CFeatureExtraction::extractFeaturesAKAZE( mrpt::system::CTimeLoggerEntry tle(profiler, "extractFeaturesAKAZE"); #if MRPT_HAS_OPENCV -#if MRPT_OPENCV_VERSION_NUM < 0x300 +#if MRPT_OPENCV_VERSION_NUM < 0x030000 THROW_EXCEPTION("This function requires OpenCV > 3.0.0"); #else @@ -46,11 +46,11 @@ void CFeatureExtraction::extractFeaturesAKAZE( // Make sure we operate on a gray-scale version of the image: const CImage inImg_gray(inImg, FAST_REF_OR_CONVERT_TO_GRAY); -#if MRPT_OPENCV_VERSION_NUM >= 0x300 +#if MRPT_OPENCV_VERSION_NUM >= 0x030000 Mat theImg = inImg_gray.asCvMat(SHALLOW_COPY); Ptr akaze = AKAZE::create( -#if MRPT_OPENCV_VERSION_NUM >= 0x400 +#if MRPT_OPENCV_VERSION_NUM >= 0x040000 static_cast( options.AKAZEOptions.descriptor_type), #else @@ -60,7 +60,7 @@ void CFeatureExtraction::extractFeaturesAKAZE( options.AKAZEOptions.descriptor_channels, options.AKAZEOptions.threshold, options.AKAZEOptions.nOctaves, options.AKAZEOptions.nOctaveLayers, -#if MRPT_OPENCV_VERSION_NUM >= 0x400 +#if MRPT_OPENCV_VERSION_NUM >= 0x040000 static_cast(options.AKAZEOptions.diffusivity) #else options.AKAZEOptions.diffusivity diff --git a/libs/vision/src/CFeatureExtraction_FAST.cpp b/libs/vision/src/CFeatureExtraction_FAST.cpp index 7ef357f6ce..5957de9cce 100644 --- a/libs/vision/src/CFeatureExtraction_FAST.cpp +++ b/libs/vision/src/CFeatureExtraction_FAST.cpp @@ -39,7 +39,7 @@ void CFeatureExtraction::extractFeaturesFAST( const CImage inImg_gray(inImg, FAST_REF_OR_CONVERT_TO_GRAY); const Mat theImg = inImg_gray.asCvMat(SHALLOW_COPY); -#if MRPT_OPENCV_VERSION_NUM < 0x300 +#if MRPT_OPENCV_VERSION_NUM < 0x030000 FastFeatureDetector fastDetector( options.FASTOptions.threshold, options.FASTOptions.nonmax_suppression); fastDetector.detect(theImg, cv_feats); diff --git a/libs/vision/src/CFeatureExtraction_ORB.cpp b/libs/vision/src/CFeatureExtraction_ORB.cpp index e81c048984..77efcd4383 100644 --- a/libs/vision/src/CFeatureExtraction_ORB.cpp +++ b/libs/vision/src/CFeatureExtraction_ORB.cpp @@ -55,7 +55,7 @@ void CFeatureExtraction::extractFeaturesORB( // The detector and descriptor profiler.enter("extractFeaturesORB.openCV_detectAndCompute"); -#if MRPT_OPENCV_VERSION_NUM < 0x300 +#if MRPT_OPENCV_VERSION_NUM < 0x030000 Ptr orb = Algorithm::create("Feature2D.ORB"); orb->operator()(cvImg, Mat(), cv_feats, cv_descs, use_precomputed_feats); #else @@ -250,7 +250,7 @@ void CFeatureExtraction::internal_computeORBDescriptors( const Mat& cvImg = inImg_gray.asCvMatRef(); Mat cv_descs; -#if MRPT_OPENCV_VERSION_NUM < 0x300 +#if MRPT_OPENCV_VERSION_NUM < 0x030000 Ptr orb = Algorithm::create("Feature2D.ORB"); orb->operator()( cvImg, cv::noArray(), cv_feats, cv_descs, diff --git a/libs/vision/src/CFeatureExtraction_SIFT.cpp b/libs/vision/src/CFeatureExtraction_SIFT.cpp index b7bcbaedac..103277f59c 100644 --- a/libs/vision/src/CFeatureExtraction_SIFT.cpp +++ b/libs/vision/src/CFeatureExtraction_SIFT.cpp @@ -18,7 +18,7 @@ #include #endif #ifdef HAVE_OPENCV_FEATURES2D -#if MRPT_OPENCV_VERSION_NUM >= 0x300 +#if MRPT_OPENCV_VERSION_NUM >= 0x030000 #include #else #include @@ -71,9 +71,9 @@ void CFeatureExtraction::extractFeaturesSIFT( // in opencv 4.4 SIFT got into the main repo #if defined(HAVE_OPENCV_NONFREE) || defined(HAVE_OPENCV_XFEATURES2D) || \ - (MRPT_OPENCV_VERSION_NUM >= 0x440) + (MRPT_OPENCV_VERSION_NUM >= 0x040400) -#if MRPT_OPENCV_VERSION_NUM < 0x300 +#if MRPT_OPENCV_VERSION_NUM < 0x030000 SiftFeatureDetector SIFTDetector( options.SIFTOptions.threshold, options.SIFTOptions.edgeThreshold); @@ -84,11 +84,11 @@ void CFeatureExtraction::extractFeaturesSIFT( Mat desc; SIFTDescriptor.compute(theImg, cv_feats, desc); #else - // MRPT_OPENCV_VERSION_NUM >= 0x300 + // MRPT_OPENCV_VERSION_NUM >= 0x030000 using namespace cv; vector cv_feats; -#if MRPT_OPENCV_VERSION_NUM >= 0x440 +#if MRPT_OPENCV_VERSION_NUM >= 0x040400 using sift_t = cv::SIFT; #else using sift_t = cv::xfeatures2d::SIFT; @@ -180,7 +180,7 @@ void CFeatureExtraction::internal_computeSiftDescriptors( ASSERT_(options.SIFTOptions.implementation == OpenCV); // in opencv 4.4 SIFT got into the main repo -#if MRPT_OPENCV_VERSION_NUM >= 0x440 +#if MRPT_OPENCV_VERSION_NUM >= 0x040400 using namespace cv; vector cv_feats; diff --git a/libs/vision/src/CFeatureExtraction_SURF.cpp b/libs/vision/src/CFeatureExtraction_SURF.cpp index 21c12dd474..72cf675a63 100644 --- a/libs/vision/src/CFeatureExtraction_SURF.cpp +++ b/libs/vision/src/CFeatureExtraction_SURF.cpp @@ -33,7 +33,7 @@ using namespace std; // Was: MRPT_HAS_OPENCV_NONFREE #if defined(HAVE_OPENCV_XFEATURES2D) || \ - (MRPT_OPENCV_VERSION_NUM < 0x300 && MRPT_OPENCV_VERSION_NUM >= 0x240) + (MRPT_OPENCV_VERSION_NUM < 0x030000 && MRPT_OPENCV_VERSION_NUM >= 0x020400) #define HAVE_OPENCV_WITH_SURF 1 #else #define HAVE_OPENCV_WITH_SURF 0 @@ -56,7 +56,7 @@ void CFeatureExtraction::extractFeaturesSURF( // gb redesign start -make sure that the Algorithm::create is used only for // older openCV versions -#if MRPT_OPENCV_VERSION_NUM < 0x300 && MRPT_OPENCV_VERSION_NUM >= 0x240 +#if MRPT_OPENCV_VERSION_NUM < 0x030000 && MRPT_OPENCV_VERSION_NUM >= 0x020400 Ptr surf = Algorithm::create("Feature2D.SURF"); if (surf.empty()) @@ -181,7 +181,7 @@ void CFeatureExtraction::internal_computeSurfDescriptors( // Only computes the descriptors: // gb redesign -#if MRPT_OPENCV_VERSION_NUM < 0x300 && MRPT_OPENCV_VERSION_NUM >= 0x240 +#if MRPT_OPENCV_VERSION_NUM < 0x030000 && MRPT_OPENCV_VERSION_NUM >= 0x020400 Ptr surf = Algorithm::create("Feature2D.SURF"); if (surf.empty()) diff --git a/libs/vision/src/CFeatureExtraction_logPolarImg.cpp b/libs/vision/src/CFeatureExtraction_logPolarImg.cpp index be92abfdf1..7a02f974b5 100644 --- a/libs/vision/src/CFeatureExtraction_logPolarImg.cpp +++ b/libs/vision/src/CFeatureExtraction_logPolarImg.cpp @@ -53,14 +53,14 @@ void CFeatureExtraction::internal_computeLogPolarImageDescriptors( const cv::Mat& in = in_img.asCvMatRef(); cv::Mat& out = logpolar_frame.asCvMatRef(); -#if MRPT_OPENCV_VERSION_NUM < 0x300 +#if MRPT_OPENCV_VERSION_NUM < 0x030000 IplImage cvin, cvout; in_img.getAsIplImage(&cvin); logpolar_frame.getAsIplImage(&cvout); cvLogPolar( &cvin, &cvout, pt, radius, CV_INTER_LINEAR + CV_WARP_FILL_OUTLIERS); -#elif MRPT_OPENCV_VERSION_NUM < 0x342 +#elif MRPT_OPENCV_VERSION_NUM < 0x030402 cv::logPolar( in(cv::Rect( round(pt.x - radius), round(pt.y - radius), diff --git a/libs/vision/src/CFeatureExtraction_polarImg.cpp b/libs/vision/src/CFeatureExtraction_polarImg.cpp index 9a8627bf36..6abfff0f58 100644 --- a/libs/vision/src/CFeatureExtraction_polarImg.cpp +++ b/libs/vision/src/CFeatureExtraction_polarImg.cpp @@ -54,13 +54,13 @@ void CFeatureExtraction::internal_computePolarImageDescriptors( const cv::Mat& in = in_img.asCvMatRef(); cv::Mat& out = linpolar_frame.asCvMatRef(); -#if MRPT_OPENCV_VERSION_NUM < 0x300 +#if MRPT_OPENCV_VERSION_NUM < 0x030000 IplImage cvin, cvout; in_img.getAsIplImage(&cvin); linpolar_frame.getAsIplImage(&cvout); cvLinearPolar( &cvin, &cvout, pt, radius, CV_INTER_LINEAR + CV_WARP_FILL_OUTLIERS); -#elif MRPT_OPENCV_VERSION_NUM < 0x342 +#elif MRPT_OPENCV_VERSION_NUM < 0x030402 cv::linearPolar( in(cv::Rect( mrpt::round(pt.x - radius), mrpt::round(pt.y - radius), diff --git a/libs/vision/src/pnp/pnp_unittest.cpp b/libs/vision/src/pnp/pnp_unittest.cpp index 9905d7a49e..97c990cdd9 100644 --- a/libs/vision/src/pnp/pnp_unittest.cpp +++ b/libs/vision/src/pnp/pnp_unittest.cpp @@ -15,7 +15,7 @@ // Opencv 2.3 had a broken in Ubuntu 14.04 Trusty => Disable // PNP classes #include -#if MRPT_HAS_OPENCV && MRPT_OPENCV_VERSION_NUM < 0x240 +#if MRPT_HAS_OPENCV && MRPT_OPENCV_VERSION_NUM < 0x020400 #undef MRPT_HAS_OPENCV #define MRPT_HAS_OPENCV 0 #endif diff --git a/parse-files/version.h.in b/parse-files/version.h.in index d7b05c6a4b..a190905443 100644 --- a/parse-files/version.h.in +++ b/parse-files/version.h.in @@ -8,7 +8,7 @@ const char MRPT_version_str[] = "${CMAKE_MRPT_COMPLETE_NAME}"; /** Version number of package in hexadecimal: - * A three digits version code, eg. 1.2.0 -> 0x120, 2.5.11 -> 0x25B */ + * A 0x112233 hexadecimal version code, eg. 2.10.2 -> 0x020A02 */ // clang-format off #define MRPT_VERSION ${CMAKE_MRPT_VERSION_CODE} // clang-format on From 49a36e7e4b1d6b3141db3908eafdca9b271d3cf5 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 11 Sep 2023 12:04:01 +0200 Subject: [PATCH 19/31] fix clang-format --- libs/vision/src/CFeatureExtraction_SURF.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libs/vision/src/CFeatureExtraction_SURF.cpp b/libs/vision/src/CFeatureExtraction_SURF.cpp index 72cf675a63..fb12a2aaf7 100644 --- a/libs/vision/src/CFeatureExtraction_SURF.cpp +++ b/libs/vision/src/CFeatureExtraction_SURF.cpp @@ -33,7 +33,8 @@ using namespace std; // Was: MRPT_HAS_OPENCV_NONFREE #if defined(HAVE_OPENCV_XFEATURES2D) || \ - (MRPT_OPENCV_VERSION_NUM < 0x030000 && MRPT_OPENCV_VERSION_NUM >= 0x020400) + (MRPT_OPENCV_VERSION_NUM < 0x030000 && \ + MRPT_OPENCV_VERSION_NUM >= 0x020400) #define HAVE_OPENCV_WITH_SURF 1 #else #define HAVE_OPENCV_WITH_SURF 0 From 0165ac55785f3643b63a087416205c57ca733cec Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 13 Sep 2023 00:03:28 +0200 Subject: [PATCH 20/31] Update changelog.md --- doc/source/doxygen-docs/changelog.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 3e6f4d9785..f0abd003a3 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -2,6 +2,7 @@ # Version 2.10.2: UNRELEASED - Build system: + - ROS: fix missing deps in package.xml needed for build via Nix. - MRPT and OpenCV versions were until now exposed as macros with 3 hexadecimal digits (e.g. `2.4.0`->`0x240`), with a clear limitation of versions greater than 15. Now, both symbols `MRPT_VERSION` and `MRPT_OPENCV_VERSION_NUM` use TWO hexadecimal digits per version part, like: `2.10.2` -> `0x010A02`, which is much more general and safe for the future. For backwards compatibility, just make sure your user code only uses `MRPT_VERSION>=xxx` or `MRPT_VERSION>xxx` comparisons, instead of less-than comparisons (Fixes [issue #1285](https://github.com/MRPT/mrpt/issues/1285)). - Changes in apps: - rawlog-edit: Add `--select-label` optional filter to command `--remap-timestamps`. @@ -10,8 +11,6 @@ - BUG FIXES: - 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) -- Build system: - - ROS: fix missing deps in package.xml needed for build via Nix. # Version 2.10.1: Released August 10th, 2023 - Build system: From 91f841ead6eef84e526221f8050020187a21ce60 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Sat, 16 Sep 2023 00:20:51 +0200 Subject: [PATCH 21/31] Fix missing package in ROS noetic (u20.04) cc: @wentasah --- package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/package.xml b/package.xml index 844cf5fe7c..60d246eb00 100644 --- a/package.xml +++ b/package.xml @@ -41,7 +41,7 @@ assimp-dev ffmpeg libfreenect-dev - libfyaml-dev + libfyaml-dev libjpeg libjsoncpp-dev libopenni2-dev From 6281bdab340ded4c340684da20d2854ab327a67b Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 18 Sep 2023 00:12:32 +0200 Subject: [PATCH 22/31] ROS package.xml: add build dep on qt5 --- package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/package.xml b/package.xml index 60d246eb00..5dd2229319 100644 --- a/package.xml +++ b/package.xml @@ -48,9 +48,11 @@ libpcap libudev-dev libusb-1.0-dev + libqt5-opengl-dev pkg-config pybind11-dev python3-pip + qtbase5-dev tinyxml2 wx-common wxwidgets From 7790c05e0982fe7830ae09e8d551e233e8d98b01 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Tue, 19 Sep 2023 23:05:07 +0200 Subject: [PATCH 23/31] Fix build error in u20.04 PPA with the new pybuild --- doc/man-pages/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/doc/man-pages/CMakeLists.txt b/doc/man-pages/CMakeLists.txt index ea9071da04..c525468efb 100644 --- a/doc/man-pages/CMakeLists.txt +++ b/doc/man-pages/CMakeLists.txt @@ -19,15 +19,15 @@ if (PROG_GZIP AND PROG_POD2MAN) # Macro for declaring man-pages targets: macro(CREATE_MANPAGE_PROJECT appname) add_custom_target(man_page_${appname} - COMMAND pod2man --center="Mobile Robot Programming Toolkit - MRPT" ${MRPT_SOURCE_DIR}/doc/man-pages/pod/${appname}.pod |gzip -c > ${MRPT_BINARY_DIR}/man-pages/${appname}.1.gz - WORKING_DIRECTORY ${MRPT_SOURCE_DIR}/ + COMMAND pod2man --center="Mobile Robot Programming Toolkit - MRPT" ${MRPT_SOURCE_DIR}/doc/man-pages/pod/${appname}.pod | gzip -c > ${appname}.1.gz + WORKING_DIRECTORY "${MRPT_BINARY_DIR}/man-pages" COMMENT "Generating MRPT man pages" ) add_dependencies(man_pages_all man_page_${appname}) if (UNIX) install(FILES "${MRPT_BINARY_DIR}/man-pages/${appname}.1.gz" DESTINATION ${mrpt_apps_INSTALL_PREFIX}share/man/man1/ ) endif() - endmacro(CREATE_MANPAGE_PROJECT) + endmacro() # The main (empty) target: add_custom_target(man_pages_all ALL) From a4e81421db8a3eb74c6c2f7250f04bdeb7b22b0e Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 27 Sep 2023 00:28:17 +0200 Subject: [PATCH 24/31] const correctness --- libs/poses/src/CPose3DQuatPDF.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libs/poses/src/CPose3DQuatPDF.cpp b/libs/poses/src/CPose3DQuatPDF.cpp index ad5805f3e7..cafddb5c27 100644 --- a/libs/poses/src/CPose3DQuatPDF.cpp +++ b/libs/poses/src/CPose3DQuatPDF.cpp @@ -62,7 +62,7 @@ void CPose3DQuatPDF::jacobiansPoseComposition( const double q2y = u.quat().y(); const double q2z = u.quat().z(); - CPose3DQuat x_plus_u = x + u; // needed for the normalization Jacobian: + const CPose3DQuat x_plus_u = x + u; // for the normalization Jacobian CMatrixDouble44 norm_jacob(UNINITIALIZED_MATRIX); x_plus_u.quat().normalizationJacobian(norm_jacob); From 4e5f8094ed435db862838c4e6fcf0ecf05ba3b8b Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 27 Sep 2023 00:30:53 +0200 Subject: [PATCH 25/31] fix obsolete URL --- libs/poses/include/mrpt/poses/CPose3DPDFGaussian.h | 6 ++---- libs/poses/include/mrpt/poses/CPose3DPDFGaussianInf.h | 6 ++---- libs/poses/include/mrpt/poses/CPose3DQuatPDFGaussian.h | 6 ++---- libs/poses/include/mrpt/poses/CPose3DQuatPDFGaussianInf.h | 6 ++---- 4 files changed, 8 insertions(+), 16 deletions(-) diff --git a/libs/poses/include/mrpt/poses/CPose3DPDFGaussian.h b/libs/poses/include/mrpt/poses/CPose3DPDFGaussian.h index 014a9decf6..6008771861 100644 --- a/libs/poses/include/mrpt/poses/CPose3DPDFGaussian.h +++ b/libs/poses/include/mrpt/poses/CPose3DPDFGaussian.h @@ -29,10 +29,8 @@ class CPose3DQuatPDFGaussian; * Uncertainty of pose composition operations (\f$ y = x \oplus u \f$) is * implemented in the method "CPose3DPDFGaussian::operator+=". * - * For further details on implemented methods and the theory behind them, - * see this report. + * \note Read also: "A tutorial on SE(3) transformation parameterizations and + * on-manifold optimization", in \cite blanco_se3_tutorial * * \sa CPose3D, CPose3DPDF, CPose3DPDFParticles * \ingroup poses_pdf_grp diff --git a/libs/poses/include/mrpt/poses/CPose3DPDFGaussianInf.h b/libs/poses/include/mrpt/poses/CPose3DPDFGaussianInf.h index a6e3581b78..cca9efda85 100644 --- a/libs/poses/include/mrpt/poses/CPose3DPDFGaussianInf.h +++ b/libs/poses/include/mrpt/poses/CPose3DPDFGaussianInf.h @@ -28,10 +28,8 @@ class CPose3DQuatPDFGaussian; * Uncertainty of pose composition operations (\f$ y = x \oplus u \f$) is * implemented in the method "CPose3DPDFGaussianInf::operator+=". * - * For further details on implemented methods and the theory behind them, - * see this report. + * \note Read also: "A tutorial on SE(3) transformation parameterizations and + * on-manifold optimization", in \cite blanco_se3_tutorial * * \sa CPose3D, CPose3DPDF, CPose3DPDFParticles, CPose3DPDFGaussian * \ingroup poses_pdf_grp diff --git a/libs/poses/include/mrpt/poses/CPose3DQuatPDFGaussian.h b/libs/poses/include/mrpt/poses/CPose3DQuatPDFGaussian.h index 7bb9d6fc01..b1eb421052 100644 --- a/libs/poses/include/mrpt/poses/CPose3DQuatPDFGaussian.h +++ b/libs/poses/include/mrpt/poses/CPose3DQuatPDFGaussian.h @@ -32,10 +32,8 @@ class CPose3DPDFGaussian; * implemented in the methods "CPose3DQuatPDFGaussian::operator+=" and * "CPose3DQuatPDF::jacobiansPoseComposition". * - * For further details on implemented methods and the theory behind them, - * see this report. + * \note Read also: "A tutorial on SE(3) transformation parameterizations and + * on-manifold optimization", in \cite blanco_se3_tutorial * * \sa CPose3DQuat, CPose3DQuatPDF, CPose3DPDF, CPose3DQuatPDFGaussianInf * \ingroup poses_pdf_grp diff --git a/libs/poses/include/mrpt/poses/CPose3DQuatPDFGaussianInf.h b/libs/poses/include/mrpt/poses/CPose3DQuatPDFGaussianInf.h index 7efa3ffd75..05f908108a 100644 --- a/libs/poses/include/mrpt/poses/CPose3DQuatPDFGaussianInf.h +++ b/libs/poses/include/mrpt/poses/CPose3DQuatPDFGaussianInf.h @@ -31,10 +31,8 @@ class CPose3DPDFGaussian; * implemented in the methods "CPose3DQuatPDFGaussianInf::operator+=" and * "CPose3DQuatPDF::jacobiansPoseComposition". * - * For further details on implemented methods and the theory behind them, - * see this report. + * \note Read also: "A tutorial on SE(3) transformation parameterizations and + * on-manifold optimization", in \cite blanco_se3_tutorial * * \sa CPose3DQuat, CPose3DQuatPDF, CPose3DPDF, CPose3DQuatPDFGaussian * \ingroup poses_pdf_grp From 3f39f1acef461848beb931d8a6124bc8c7787c63 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 27 Sep 2023 01:28:39 +0200 Subject: [PATCH 26/31] Fix wrong Jacobian formula for gimbal lock. More unit tests. --- doc/source/doxygen-docs/changelog.md | 1 + libs/math/include/mrpt/math/CQuaternion.h | 12 ++-- .../src/CPose3DQuatPDFGaussian_unittest.cpp | 63 +++++++++++++++---- libs/poses/src/CQuaternion_unittest.cpp | 22 +++++++ 4 files changed, 81 insertions(+), 17 deletions(-) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index f0abd003a3..6603c415fa 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -11,6 +11,7 @@ - BUG FIXES: - 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) + - Fix wrong Jacobian in mrpt::math::CQuaternion::rpy_and_jacobian() for the case of Gimbal Lock. Thanks @giafranchini for reporting!. PR [#1290](https://github.com/MRPT/mrpt/pull/1290) (Closes [#1289](https://github.com/MRPT/mrpt/issues/1289)) # Version 2.10.1: Released August 10th, 2023 - Build system: diff --git a/libs/math/include/mrpt/math/CQuaternion.h b/libs/math/include/mrpt/math/CQuaternion.h index 7e61f728d3..cf95b515bc 100644 --- a/libs/math/include/mrpt/math/CQuaternion.h +++ b/libs/math/include/mrpt/math/CQuaternion.h @@ -465,8 +465,10 @@ class CQuaternion : public CVectorFixed if (out_dr_dq) { out_dr_dq->setZero(); - (*out_dr_dq)(0, 0) = +2 / x(); - (*out_dr_dq)(0, 2) = -2 * r() / (x() * x()); + // d{yaw}_d{r}: + (*out_dr_dq)(0, 0) = +2 * x() / (r() * r() + x() * x()); + // d{yaw}_d{x}: + (*out_dr_dq)(0, 1) = -2 * r() / (r() * r() + x() * x()); } } else if (discr < -0.49999) @@ -477,8 +479,10 @@ class CQuaternion : public CVectorFixed if (out_dr_dq) { out_dr_dq->setZero(); - (*out_dr_dq)(0, 0) = -2 / x(); - (*out_dr_dq)(0, 2) = +2 * r() / (x() * x()); + // d{yaw}_d{r}: + (*out_dr_dq)(0, 0) = -2 * x() / (r() * r() + x() * x()); + // d{yaw}_d{x}: + (*out_dr_dq)(0, 1) = +2 * r() / (r() * r() + x() * x()); } } else diff --git a/libs/poses/src/CPose3DQuatPDFGaussian_unittest.cpp b/libs/poses/src/CPose3DQuatPDFGaussian_unittest.cpp index db7bc6f6fe..b74ac5b858 100755 --- a/libs/poses/src/CPose3DQuatPDFGaussian_unittest.cpp +++ b/libs/poses/src/CPose3DQuatPDFGaussian_unittest.cpp @@ -53,23 +53,54 @@ class Pose3DQuatPDFGaussTests : public ::testing::Test return p6pdf; } - void test_toFromYPRGauss(double yaw, double pitch, double roll) + void test_toFromYPRGauss( + double yaw, double pitch, double roll, bool useGimbalLockCov = false) { + const bool usesSUT = + mrpt::global_settings::USE_SUT_QUAT2EULER_CONVERSION(); + // Random pose: CPose3DPDFGaussian p1ypr = - generateRandomPose3DPDF(1.0, 2.0, 3.0, yaw, pitch, roll, 0.1); + generateRandomPose3DPDF(1.0, 2.0, 3.0, yaw, pitch, roll, 1e-2); + + // In gimbal-lock, it's impossible to recover uncertainty for + // pitch/roll, since both are fixed values: + if (useGimbalLockCov) + { + for (int i = 0; i < 6; i++) + for (int j = 4; j < 6; j++) + p1ypr.cov(i, j) = p1ypr.cov(j, i) = 0; + } + CPose3DQuatPDFGaussian p1quat = CPose3DQuatPDFGaussian(p1ypr); // Convert back to a 6x6 representation: CPose3DPDFGaussian p2ypr = CPose3DPDFGaussian(p1quat); - EXPECT_NEAR(0, (p2ypr.cov - p1ypr.cov).array().abs().maxCoeff(), 1e-6) - << "p1ypr: " << endl - << p1ypr << endl - << "p1quat : " << endl - << p1quat << endl - << "p2ypr : " << endl - << p2ypr << endl; + std::stringstream onFailMsg; + onFailMsg << "p1ypr: " << endl + << p1ypr << endl + << "p1quat : " << endl + << p1quat << endl + << "p2ypr : " << endl + << p2ypr << endl + << "USE_SUT_QUAT2EULER_CONVERSION: " + << mrpt::global_settings::USE_SUT_QUAT2EULER_CONVERSION() + << endl; + + EXPECT_NEAR( + 0, (p2ypr.cov - p1ypr.cov).array().abs().maxCoeff(), + usesSUT ? 1e-2 : 1e-6) + << onFailMsg.str(); + + EXPECT_NEAR( + 0, + (p2ypr.mean.asVectorVal() - p1ypr.mean.asVectorVal()) + .array() + .abs() + .maxCoeff(), + usesSUT ? 0.1 : 1e-4) + << onFailMsg.str(); } static void func_compose( @@ -366,10 +397,16 @@ class Pose3DQuatPDFGaussTests : public ::testing::Test TEST_F(Pose3DQuatPDFGaussTests, ToYPRGaussPDFAndBack) { - test_toFromYPRGauss(-30.0_deg, 10.0_deg, 60.0_deg); - test_toFromYPRGauss(30.0_deg, 88.0_deg, 0.0_deg); - test_toFromYPRGauss(30.0_deg, 89.5_deg, 0.0_deg); - // The formulas break at pitch=90, but this we cannot avoid... + for (int USE_SUT = 0; USE_SUT <= 1; USE_SUT++) + { + mrpt::global_settings::USE_SUT_QUAT2EULER_CONVERSION(USE_SUT != 0); + + test_toFromYPRGauss(-30.0_deg, 10.0_deg, 60.0_deg); + test_toFromYPRGauss(30.0_deg, 88.0_deg, 0.0_deg); + test_toFromYPRGauss(30.0_deg, 89.5_deg, 0.0_deg); + test_toFromYPRGauss(20.0_deg, 89.999_deg, 0.0_deg, true /*gimbal*/); + test_toFromYPRGauss(20.0_deg, -89.999_deg, 0.0_deg, true /*gimbal*/); + } } TEST_F(Pose3DQuatPDFGaussTests, CompositionJacobian) diff --git a/libs/poses/src/CQuaternion_unittest.cpp b/libs/poses/src/CQuaternion_unittest.cpp index 9591b14437..48309a7c72 100644 --- a/libs/poses/src/CQuaternion_unittest.cpp +++ b/libs/poses/src/CQuaternion_unittest.cpp @@ -192,3 +192,25 @@ TEST_F(QuaternionTests, ExpAndLnMatches) for (const auto& i : list_test_XYZ) test_ExpAndLnMatches(i[0], i[1], i[2]); } + +TEST_F(QuaternionTests, ThrowOnNotNormalized) +{ + EXPECT_NO_THROW(mrpt::math::CQuaternion(1.0, 0.0, 0.0, 0.0)); + EXPECT_ANY_THROW(mrpt::math::CQuaternion(0.9, 0.0, 0.0, 0.0)); + EXPECT_ANY_THROW(mrpt::math::CQuaternion(1.1, 0.0, 0.0, 0.0)); + EXPECT_ANY_THROW(mrpt::math::CQuaternion(1.0, 0.1, 0.0, 0.0)); + EXPECT_ANY_THROW(mrpt::math::CQuaternion(1.0, 0.0, -0.1, 0.0)); + EXPECT_ANY_THROW(mrpt::math::CQuaternion(1.0, 0.0, 0.0, -0.1)); +} + +TEST_F(QuaternionTests, ensurePositiveRealPart) +{ + { + auto q = mrpt::math::CQuaternion(1.0, 0.0, 0.0, 0.0); + EXPECT_GE(q.r(), 0.0); + } + { + auto q = mrpt::math::CQuaternion(-1.0, 0.0, 0.0, 0.0); + EXPECT_GE(q.r(), 0.0); + } +} From e0f4ccdf695e788c2539027d5bce18d5239d7b18 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Sun, 1 Oct 2023 01:57:03 +0200 Subject: [PATCH 27/31] Avoid problematic tests on RISCV (Closes #1287) --- doc/source/doxygen-docs/changelog.md | 1 + libs/opengl/src/CFBORender_unittest.cpp | 4 ++++ 2 files changed, 5 insertions(+) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 6603c415fa..ccae02d64d 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -12,6 +12,7 @@ - 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) - Fix wrong Jacobian in mrpt::math::CQuaternion::rpy_and_jacobian() for the case of Gimbal Lock. Thanks @giafranchini for reporting!. PR [#1290](https://github.com/MRPT/mrpt/pull/1290) (Closes [#1289](https://github.com/MRPT/mrpt/issues/1289)) + - Fix spurious failures in offscreen render unit tests in RISCV64 (Closes [#1287](https://github.com/MRPT/mrpt/issues/1287)). # Version 2.10.1: Released August 10th, 2023 - Build system: diff --git a/libs/opengl/src/CFBORender_unittest.cpp b/libs/opengl/src/CFBORender_unittest.cpp index 08bfa65d11..a61d44075d 100644 --- a/libs/opengl/src/CFBORender_unittest.cpp +++ b/libs/opengl/src/CFBORender_unittest.cpp @@ -42,6 +42,10 @@ #if defined(__arm__) && MRPT_WORD_SIZE == 32 #undef RUN_OFFSCREEN_RENDER_TESTS #endif +// Idem with RISCV64 arch: +#if defined(__riscv) +#undef RUN_OFFSCREEN_RENDER_TESTS +#endif static float imageDiff( const mrpt::img::CImage& im1, const mrpt::img::CImage& im2) From 4254ed7786872e50244241f10e643ac163948a9b Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 3 Oct 2023 00:13:26 +0000 Subject: [PATCH 28/31] Bump urllib3 from 2.0.4 to 2.0.6 in /doc Bumps [urllib3](https://github.com/urllib3/urllib3) from 2.0.4 to 2.0.6. - [Release notes](https://github.com/urllib3/urllib3/releases) - [Changelog](https://github.com/urllib3/urllib3/blob/main/CHANGES.rst) - [Commits](https://github.com/urllib3/urllib3/compare/2.0.4...2.0.6) --- updated-dependencies: - dependency-name: urllib3 dependency-type: direct:production ... Signed-off-by: dependabot[bot] --- doc/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/requirements.txt b/doc/requirements.txt index fcf73a604f..f707808a98 100644 --- a/doc/requirements.txt +++ b/doc/requirements.txt @@ -29,4 +29,4 @@ sphinxcontrib-jquery==4.1 sphinxcontrib-jsmath==1.0.1 sphinxcontrib-qthelp==1.0.6 sphinxcontrib-serializinghtml==1.1.9 -urllib3==2.0.4 +urllib3==2.0.6 From ddc6f6e1b12a793fd9a77a5758f2adce91b1b04c Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 4 Oct 2023 23:31:46 +0200 Subject: [PATCH 29/31] ffmpeg reader: added read overload returning PTS --- doc/source/doxygen-docs/changelog.md | 2 ++ .../include/mrpt/hwdrivers/CFFMPEG_InputStream.h | 5 +++++ libs/hwdrivers/src/CFFMPEG_InputStream.cpp | 12 ++++++++++++ samples/hwdrivers_capture_video_ffmpeg/test.cpp | 10 ++++++++-- 4 files changed, 27 insertions(+), 2 deletions(-) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index ccae02d64d..437d0edd15 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -8,6 +8,8 @@ - rawlog-edit: Add `--select-label` optional filter to command `--remap-timestamps`. - Changes in libraries: - mrpt-ros1bridge and mrpt-ros2bridge: Remove leftover printf debugging trace printing ``Ok`` to console. + - \ref mrpt_hwdrivers_grp + - New overload mrpt::hwdrivers::CFFMPEG_InputStream::retrieveFrame() returning the frame PTS (presentation timestamp). - BUG FIXES: - 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) diff --git a/libs/hwdrivers/include/mrpt/hwdrivers/CFFMPEG_InputStream.h b/libs/hwdrivers/include/mrpt/hwdrivers/CFFMPEG_InputStream.h index 0f1a197a55..1ac660bf08 100644 --- a/libs/hwdrivers/include/mrpt/hwdrivers/CFFMPEG_InputStream.h +++ b/libs/hwdrivers/include/mrpt/hwdrivers/CFFMPEG_InputStream.h @@ -97,5 +97,10 @@ class CFFMPEG_InputStream * \sa openURL, close, isOpen */ bool retrieveFrame(mrpt::img::CImage& out_img); + + /** \overload also returning the frame PTS (frame presentation timestamp). + * Refer to docs for ffmpeg AVFrame::pts + */ + bool retrieveFrame(mrpt::img::CImage& out_img, int64_t& outPTS); }; } // namespace mrpt::hwdrivers diff --git a/libs/hwdrivers/src/CFFMPEG_InputStream.cpp b/libs/hwdrivers/src/CFFMPEG_InputStream.cpp index 602f43f1ba..436eafac87 100644 --- a/libs/hwdrivers/src/CFFMPEG_InputStream.cpp +++ b/libs/hwdrivers/src/CFFMPEG_InputStream.cpp @@ -321,8 +321,17 @@ void CFFMPEG_InputStream::close() retrieveFrame -------------------------------------------------------- */ bool CFFMPEG_InputStream::retrieveFrame(mrpt::img::CImage& out_img) +{ + [[maybe_unused]] int64_t outPTS = 0; + return retrieveFrame(out_img, outPTS); +} + +bool CFFMPEG_InputStream::retrieveFrame( + mrpt::img::CImage& out_img, int64_t& outPTS) { #if MRPT_HAS_FFMPEG + outPTS = 0; + if (!this->isOpen()) return false; TFFMPEGContext* ctx = &m_impl->m_state; @@ -410,6 +419,9 @@ bool CFFMPEG_InputStream::retrieveFrame(mrpt::img::CImage& out_img) out_img.loadFromMemoryBuffer( width, height, !m_grab_as_grayscale, ctx->pFrameRGB->data[0]); + // Output frame timestamp: + outPTS = ctx->pFrame->pts; + // Free the packet that was allocated by av_read_frame av_packet_unref(&packet); return true; diff --git a/samples/hwdrivers_capture_video_ffmpeg/test.cpp b/samples/hwdrivers_capture_video_ffmpeg/test.cpp index 9590b8522d..a83494c724 100644 --- a/samples/hwdrivers_capture_video_ffmpeg/test.cpp +++ b/samples/hwdrivers_capture_video_ffmpeg/test.cpp @@ -50,7 +50,8 @@ void Test_FFMPEG_CaptureCamera(const std::string& video_url) std::cout << "Window closed. Quitting.\n"; break; } - if (!in_video.retrieveFrame(img)) + int64_t framePTS = 0; // frame timestamp + if (!in_video.retrieveFrame(img, framePTS)) { std::cout << "Video stream ended. Quitting.\n"; break; @@ -62,8 +63,13 @@ void Test_FFMPEG_CaptureCamera(const std::string& video_url) while (img.getWidth() > 1024) img = img.scaleHalf(mrpt::img::IMG_INTERP_LINEAR); + img.selectTextFont("10x20"); img.textOut( - 5, 5, mrpt::format("%.02f fps", fps), TColor(0x80, 0x80, 0x80)); + 5, 5, + mrpt::format( + "Read: %.02f FPS | Nominal: %.02f FPS | PTS=%i", fps, + in_video.getVideoFPS(), static_cast(framePTS)), + TColor(0x80, 0x80, 0x80)); if (nFrames > 100) { tictac.Tic(); From 59edb712739ccfabf5002d343ef9655cedfaf1ea Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 4 Oct 2023 23:51:16 +0200 Subject: [PATCH 30/31] Update python wrapper --- python/src/mrpt/hwdrivers/CDUO3DCamera.cpp | 1 + python/src/mrpt/poses/CPose3DPDF.cpp | 6 +++--- python/src/mrpt/poses/CPose3DPDFGaussian.cpp | 4 ++-- python/src/mrpt/poses/CPose3DPDFGaussianInf.cpp | 6 +++--- python/src/mrpt/poses/CPose3DPDFSOG.cpp | 6 +++--- python/src/mrpt/poses/CPose3DQuatPDFGaussian.cpp | 4 ++-- python/src/mrpt/poses/CPose3DQuatPDFGaussianInf.cpp | 6 +++--- 7 files changed, 17 insertions(+), 16 deletions(-) diff --git a/python/src/mrpt/hwdrivers/CDUO3DCamera.cpp b/python/src/mrpt/hwdrivers/CDUO3DCamera.cpp index 576a3efe34..7d66d16568 100644 --- a/python/src/mrpt/hwdrivers/CDUO3DCamera.cpp +++ b/python/src/mrpt/hwdrivers/CDUO3DCamera.cpp @@ -83,6 +83,7 @@ void bind_mrpt_hwdrivers_CDUO3DCamera(std::function< pybind11::module &(std::str cl.def("close", (void (mrpt::hwdrivers::CFFMPEG_InputStream::*)()) &mrpt::hwdrivers::CFFMPEG_InputStream::close, "Close the video stream (this is called automatically at destruction).\n \n\n openURL\n\nC++: mrpt::hwdrivers::CFFMPEG_InputStream::close() --> void"); cl.def("getVideoFPS", (double (mrpt::hwdrivers::CFFMPEG_InputStream::*)() const) &mrpt::hwdrivers::CFFMPEG_InputStream::getVideoFPS, "Get the frame-per-second (FPS) of the video source, or \"-1\" if the video\n is not open. \n\nC++: mrpt::hwdrivers::CFFMPEG_InputStream::getVideoFPS() const --> double"); cl.def("retrieveFrame", (bool (mrpt::hwdrivers::CFFMPEG_InputStream::*)(class mrpt::img::CImage &)) &mrpt::hwdrivers::CFFMPEG_InputStream::retrieveFrame, "Get the next frame from the video stream.\n Note that for remote streams (IP cameras) this method may block until\n enough information is read to generate a new frame.\n Images are returned as 8-bit depth grayscale if \"grab_as_grayscale\" is\n true.\n \n\n false on any error, true on success.\n \n\n openURL, close, isOpen\n\nC++: mrpt::hwdrivers::CFFMPEG_InputStream::retrieveFrame(class mrpt::img::CImage &) --> bool", pybind11::arg("out_img")); + cl.def("retrieveFrame", (bool (mrpt::hwdrivers::CFFMPEG_InputStream::*)(class mrpt::img::CImage &, long &)) &mrpt::hwdrivers::CFFMPEG_InputStream::retrieveFrame, "Refer to docs for ffmpeg AVFrame::pts\n\nC++: mrpt::hwdrivers::CFFMPEG_InputStream::retrieveFrame(class mrpt::img::CImage &, long &) --> bool", pybind11::arg("out_img"), pybind11::arg("outPTS")); cl.def("assign", (class mrpt::hwdrivers::CFFMPEG_InputStream & (mrpt::hwdrivers::CFFMPEG_InputStream::*)(const class mrpt::hwdrivers::CFFMPEG_InputStream &)) &mrpt::hwdrivers::CFFMPEG_InputStream::operator=, "C++: mrpt::hwdrivers::CFFMPEG_InputStream::operator=(const class mrpt::hwdrivers::CFFMPEG_InputStream &) --> class mrpt::hwdrivers::CFFMPEG_InputStream &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/src/mrpt/poses/CPose3DPDF.cpp b/python/src/mrpt/poses/CPose3DPDF.cpp index 472022c93b..d3b495a2af 100644 --- a/python/src/mrpt/poses/CPose3DPDF.cpp +++ b/python/src/mrpt/poses/CPose3DPDF.cpp @@ -256,7 +256,7 @@ struct PyCallBack_mrpt_poses_CPose3DPDF : public mrpt::poses::CPose3DPDF { } }; -// mrpt::poses::CPose3DPDFGaussian file:mrpt/poses/CPose3DPDFGaussian.h line:40 +// mrpt::poses::CPose3DPDFGaussian file:mrpt/poses/CPose3DPDFGaussian.h line:38 struct PyCallBack_mrpt_poses_CPose3DPDFGaussian : public mrpt::poses::CPose3DPDFGaussian { using mrpt::poses::CPose3DPDFGaussian::CPose3DPDFGaussian; @@ -489,8 +489,8 @@ void bind_mrpt_poses_CPose3DPDF(std::function< pybind11::module &(std::string co cl.def_static("is_PDF", (bool (*)()) &mrpt::poses::CPose3DPDF::is_PDF, "C++: mrpt::poses::CPose3DPDF::is_PDF() --> bool"); cl.def("assign", (class mrpt::poses::CPose3DPDF & (mrpt::poses::CPose3DPDF::*)(const class mrpt::poses::CPose3DPDF &)) &mrpt::poses::CPose3DPDF::operator=, "C++: mrpt::poses::CPose3DPDF::operator=(const class mrpt::poses::CPose3DPDF &) --> class mrpt::poses::CPose3DPDF &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::poses::CPose3DPDFGaussian file:mrpt/poses/CPose3DPDFGaussian.h line:40 - pybind11::class_, PyCallBack_mrpt_poses_CPose3DPDFGaussian, mrpt::poses::CPose3DPDF, mrpt::Stringifyable> cl(M("mrpt::poses"), "CPose3DPDFGaussian", "Declares a class that represents a Probability Density function (PDF) of a\n 3D pose \n\n.\n\n This class implements that PDF using a mono-modal Gaussian distribution.\n See mrpt::poses::CPose3DPDF for more details.\n\n Uncertainty of pose composition operations (\n) is\n implemented in the method \"CPose3DPDFGaussian::operator+=\".\n\n For further details on implemented methods and the theory behind them,\n see \n* href=\"http://www.mrpt.org/6D_poses:equivalences_compositions_and_uncertainty\"\n >this report.\n\n \n CPose3D, CPose3DPDF, CPose3DPDFParticles\n \n\n\n "); + { // mrpt::poses::CPose3DPDFGaussian file:mrpt/poses/CPose3DPDFGaussian.h line:38 + pybind11::class_, PyCallBack_mrpt_poses_CPose3DPDFGaussian, mrpt::poses::CPose3DPDF, mrpt::Stringifyable> cl(M("mrpt::poses"), "CPose3DPDFGaussian", "Declares a class that represents a Probability Density function (PDF) of a\n 3D pose \n\n.\n\n This class implements that PDF using a mono-modal Gaussian distribution.\n See mrpt::poses::CPose3DPDF for more details.\n\n Uncertainty of pose composition operations (\n) is\n implemented in the method \"CPose3DPDFGaussian::operator+=\".\n\n \n Read also: \"A tutorial on SE(3) transformation parameterizations and\n on-manifold optimization\", in \n\n \n CPose3D, CPose3DPDF, CPose3DPDFParticles\n \n\n\n "); cl.def( pybind11::init( [](){ return new mrpt::poses::CPose3DPDFGaussian(); }, [](){ return new PyCallBack_mrpt_poses_CPose3DPDFGaussian(); } ) ); cl.def( pybind11::init(), pybind11::arg("init_Mean") ); diff --git a/python/src/mrpt/poses/CPose3DPDFGaussian.cpp b/python/src/mrpt/poses/CPose3DPDFGaussian.cpp index b5827d55c7..1fef059e2f 100644 --- a/python/src/mrpt/poses/CPose3DPDFGaussian.cpp +++ b/python/src/mrpt/poses/CPose3DPDFGaussian.cpp @@ -15,10 +15,10 @@ void bind_mrpt_poses_CPose3DPDFGaussian(std::function< pybind11::module &(std::string const &namespace_) > &M) { - // mrpt::global_settings::USE_SUT_QUAT2EULER_CONVERSION(bool) file:mrpt/poses/CPose3DPDFGaussian.h line:242 + // mrpt::global_settings::USE_SUT_QUAT2EULER_CONVERSION(bool) file:mrpt/poses/CPose3DPDFGaussian.h line:240 M("mrpt::global_settings").def("USE_SUT_QUAT2EULER_CONVERSION", (void (*)(bool)) &mrpt::global_settings::USE_SUT_QUAT2EULER_CONVERSION, "If set to true (false), a Scaled Unscented Transform is used instead of a\nlinear approximation with Jacobians.\n Affects to:\n - CPose3DPDFGaussian::CPose3DPDFGaussian( const CPose3DQuatPDFGaussian\n&o)\n\nC++: mrpt::global_settings::USE_SUT_QUAT2EULER_CONVERSION(bool) --> void", pybind11::arg("value")); - // mrpt::global_settings::USE_SUT_QUAT2EULER_CONVERSION() file:mrpt/poses/CPose3DPDFGaussian.h line:243 + // mrpt::global_settings::USE_SUT_QUAT2EULER_CONVERSION() file:mrpt/poses/CPose3DPDFGaussian.h line:241 M("mrpt::global_settings").def("USE_SUT_QUAT2EULER_CONVERSION", (bool (*)()) &mrpt::global_settings::USE_SUT_QUAT2EULER_CONVERSION, "C++: mrpt::global_settings::USE_SUT_QUAT2EULER_CONVERSION() --> bool"); } diff --git a/python/src/mrpt/poses/CPose3DPDFGaussianInf.cpp b/python/src/mrpt/poses/CPose3DPDFGaussianInf.cpp index 3f249106bc..5f731250c7 100644 --- a/python/src/mrpt/poses/CPose3DPDFGaussianInf.cpp +++ b/python/src/mrpt/poses/CPose3DPDFGaussianInf.cpp @@ -55,7 +55,7 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::poses::CPose3DPDFGaussianInf file:mrpt/poses/CPose3DPDFGaussianInf.h line:39 +// mrpt::poses::CPose3DPDFGaussianInf file:mrpt/poses/CPose3DPDFGaussianInf.h line:37 struct PyCallBack_mrpt_poses_CPose3DPDFGaussianInf : public mrpt::poses::CPose3DPDFGaussianInf { using mrpt::poses::CPose3DPDFGaussianInf::CPose3DPDFGaussianInf; @@ -461,8 +461,8 @@ struct PyCallBack_mrpt_poses_CPose3DPDFGrid : public mrpt::poses::CPose3DPDFGrid void bind_mrpt_poses_CPose3DPDFGaussianInf(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::poses::CPose3DPDFGaussianInf file:mrpt/poses/CPose3DPDFGaussianInf.h line:39 - pybind11::class_, PyCallBack_mrpt_poses_CPose3DPDFGaussianInf, mrpt::poses::CPose3DPDF> cl(M("mrpt::poses"), "CPose3DPDFGaussianInf", "Declares a class that represents a Probability Density function (PDF) of a\n 3D pose \n\n as a\n Gaussian described by its mean and its inverse covariance matrix.\n\n This class implements that PDF using a mono-modal Gaussian distribution in\n \"information\" form (inverse covariance matrix).\n\n Uncertainty of pose composition operations (\n) is\n implemented in the method \"CPose3DPDFGaussianInf::operator+=\".\n\n For further details on implemented methods and the theory behind them,\n see \n* href=\"http://www.mrpt.org/6D_poses:equivalences_compositions_and_uncertainty\"\n >this report.\n\n \n CPose3D, CPose3DPDF, CPose3DPDFParticles, CPose3DPDFGaussian\n \n\n\n "); + { // mrpt::poses::CPose3DPDFGaussianInf file:mrpt/poses/CPose3DPDFGaussianInf.h line:37 + pybind11::class_, PyCallBack_mrpt_poses_CPose3DPDFGaussianInf, mrpt::poses::CPose3DPDF> cl(M("mrpt::poses"), "CPose3DPDFGaussianInf", "Declares a class that represents a Probability Density function (PDF) of a\n 3D pose \n\n as a\n Gaussian described by its mean and its inverse covariance matrix.\n\n This class implements that PDF using a mono-modal Gaussian distribution in\n \"information\" form (inverse covariance matrix).\n\n Uncertainty of pose composition operations (\n) is\n implemented in the method \"CPose3DPDFGaussianInf::operator+=\".\n\n \n Read also: \"A tutorial on SE(3) transformation parameterizations and\n on-manifold optimization\", in \n\n \n CPose3D, CPose3DPDF, CPose3DPDFParticles, CPose3DPDFGaussian\n \n\n\n "); cl.def( pybind11::init( [](){ return new mrpt::poses::CPose3DPDFGaussianInf(); }, [](){ return new PyCallBack_mrpt_poses_CPose3DPDFGaussianInf(); } ) ); cl.def( pybind11::init(), pybind11::arg("init_Mean") ); diff --git a/python/src/mrpt/poses/CPose3DPDFSOG.cpp b/python/src/mrpt/poses/CPose3DPDFSOG.cpp index 7792511317..168b9e1d1f 100644 --- a/python/src/mrpt/poses/CPose3DPDFSOG.cpp +++ b/python/src/mrpt/poses/CPose3DPDFSOG.cpp @@ -447,7 +447,7 @@ struct PyCallBack_mrpt_poses_CPose3DQuatPDF : public mrpt::poses::CPose3DQuatPDF } }; -// mrpt::poses::CPose3DQuatPDFGaussian file:mrpt/poses/CPose3DQuatPDFGaussian.h line:43 +// mrpt::poses::CPose3DQuatPDFGaussian file:mrpt/poses/CPose3DQuatPDFGaussian.h line:41 struct PyCallBack_mrpt_poses_CPose3DQuatPDFGaussian : public mrpt::poses::CPose3DQuatPDFGaussian { using mrpt::poses::CPose3DQuatPDFGaussian::CPose3DQuatPDFGaussian; @@ -689,8 +689,8 @@ void bind_mrpt_poses_CPose3DPDFSOG(std::function< pybind11::module &(std::string cl.def_static("jacobiansPoseComposition", (void (*)(const class mrpt::poses::CPose3DQuat &, const class mrpt::poses::CPose3DQuat &, class mrpt::math::CMatrixFixed &, class mrpt::math::CMatrixFixed &, class mrpt::poses::CPose3DQuat *)) &mrpt::poses::CPose3DQuatPDF::jacobiansPoseComposition, "This static method computes the two Jacobians of a pose composition\n operation \n\n\n \n If set to !=nullptr, the result of \"x+u\" will be\n stored here (it will be computed internally anyway).\n To see the mathematical derivation of the formulas, refer to the\n technical report here:\n -\n https://www.mrpt.org/Probability_Density_Distributions_Over_Spatial_Representations\n\nC++: mrpt::poses::CPose3DQuatPDF::jacobiansPoseComposition(const class mrpt::poses::CPose3DQuat &, const class mrpt::poses::CPose3DQuat &, class mrpt::math::CMatrixFixed &, class mrpt::math::CMatrixFixed &, class mrpt::poses::CPose3DQuat *) --> void", pybind11::arg("x"), pybind11::arg("u"), pybind11::arg("df_dx"), pybind11::arg("df_du"), pybind11::arg("out_x_oplus_u")); cl.def("assign", (class mrpt::poses::CPose3DQuatPDF & (mrpt::poses::CPose3DQuatPDF::*)(const class mrpt::poses::CPose3DQuatPDF &)) &mrpt::poses::CPose3DQuatPDF::operator=, "C++: mrpt::poses::CPose3DQuatPDF::operator=(const class mrpt::poses::CPose3DQuatPDF &) --> class mrpt::poses::CPose3DQuatPDF &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::poses::CPose3DQuatPDFGaussian file:mrpt/poses/CPose3DQuatPDFGaussian.h line:43 - pybind11::class_, PyCallBack_mrpt_poses_CPose3DQuatPDFGaussian, mrpt::poses::CPose3DQuatPDF> cl(M("mrpt::poses"), "CPose3DQuatPDFGaussian", "Declares a class that represents a Probability Density function (PDF) of a\n 3D pose using a quaternion \n\n\n\n.\n\n This class implements that PDF using a mono-modal Gaussian distribution.\n See mrpt::poses::CPose3DQuatPDF for more details, or\n mrpt::poses::CPose3DPDF for classes based on Euler angles instead.\n\n Uncertainty of pose composition operations (\n) is\n implemented in the methods \"CPose3DQuatPDFGaussian::operator+=\" and\n \"CPose3DQuatPDF::jacobiansPoseComposition\".\n\n For further details on implemented methods and the theory behind them,\n see \n* href=\"http://www.mrpt.org/6D_poses:equivalences_compositions_and_uncertainty\"\n >this report.\n\n \n CPose3DQuat, CPose3DQuatPDF, CPose3DPDF, CPose3DQuatPDFGaussianInf\n \n\n\n "); + { // mrpt::poses::CPose3DQuatPDFGaussian file:mrpt/poses/CPose3DQuatPDFGaussian.h line:41 + pybind11::class_, PyCallBack_mrpt_poses_CPose3DQuatPDFGaussian, mrpt::poses::CPose3DQuatPDF> cl(M("mrpt::poses"), "CPose3DQuatPDFGaussian", "Declares a class that represents a Probability Density function (PDF) of a\n 3D pose using a quaternion \n\n\n\n.\n\n This class implements that PDF using a mono-modal Gaussian distribution.\n See mrpt::poses::CPose3DQuatPDF for more details, or\n mrpt::poses::CPose3DPDF for classes based on Euler angles instead.\n\n Uncertainty of pose composition operations (\n) is\n implemented in the methods \"CPose3DQuatPDFGaussian::operator+=\" and\n \"CPose3DQuatPDF::jacobiansPoseComposition\".\n\n \n Read also: \"A tutorial on SE(3) transformation parameterizations and\n on-manifold optimization\", in \n\n \n CPose3DQuat, CPose3DQuatPDF, CPose3DPDF, CPose3DQuatPDFGaussianInf\n \n\n\n "); cl.def( pybind11::init( [](){ return new mrpt::poses::CPose3DQuatPDFGaussian(); }, [](){ return new PyCallBack_mrpt_poses_CPose3DQuatPDFGaussian(); } ) ); cl.def( pybind11::init(), pybind11::arg("constructor_dummy_param") ); diff --git a/python/src/mrpt/poses/CPose3DQuatPDFGaussian.cpp b/python/src/mrpt/poses/CPose3DQuatPDFGaussian.cpp index 3f699ef484..9ffb89835b 100644 --- a/python/src/mrpt/poses/CPose3DQuatPDFGaussian.cpp +++ b/python/src/mrpt/poses/CPose3DQuatPDFGaussian.cpp @@ -15,10 +15,10 @@ void bind_mrpt_poses_CPose3DQuatPDFGaussian(std::function< pybind11::module &(std::string const &namespace_) > &M) { - // mrpt::global_settings::USE_SUT_EULER2QUAT_CONVERSION(bool) file:mrpt/poses/CPose3DQuatPDFGaussian.h line:207 + // mrpt::global_settings::USE_SUT_EULER2QUAT_CONVERSION(bool) file:mrpt/poses/CPose3DQuatPDFGaussian.h line:205 M("mrpt::global_settings").def("USE_SUT_EULER2QUAT_CONVERSION", (void (*)(bool)) &mrpt::global_settings::USE_SUT_EULER2QUAT_CONVERSION, "If set to true (default), a Scaled Unscented Transform is used instead of a\nlinear approximation with Jacobians.\n Affects to:\n - CPose3DQuatPDFGaussian::copyFrom(const CPose3DPDFGaussian &o)\n - CPose3DQuatPDFGaussianInf::copyFrom(const CPose3DPDFGaussianInf &o)\n\nC++: mrpt::global_settings::USE_SUT_EULER2QUAT_CONVERSION(bool) --> void", pybind11::arg("value")); - // mrpt::global_settings::USE_SUT_EULER2QUAT_CONVERSION() file:mrpt/poses/CPose3DQuatPDFGaussian.h line:208 + // mrpt::global_settings::USE_SUT_EULER2QUAT_CONVERSION() file:mrpt/poses/CPose3DQuatPDFGaussian.h line:206 M("mrpt::global_settings").def("USE_SUT_EULER2QUAT_CONVERSION", (bool (*)()) &mrpt::global_settings::USE_SUT_EULER2QUAT_CONVERSION, "C++: mrpt::global_settings::USE_SUT_EULER2QUAT_CONVERSION() --> bool"); } diff --git a/python/src/mrpt/poses/CPose3DQuatPDFGaussianInf.cpp b/python/src/mrpt/poses/CPose3DQuatPDFGaussianInf.cpp index c3d2a60017..543bb290b4 100644 --- a/python/src/mrpt/poses/CPose3DQuatPDFGaussianInf.cpp +++ b/python/src/mrpt/poses/CPose3DQuatPDFGaussianInf.cpp @@ -53,7 +53,7 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::poses::CPose3DQuatPDFGaussianInf file:mrpt/poses/CPose3DQuatPDFGaussianInf.h line:42 +// mrpt::poses::CPose3DQuatPDFGaussianInf file:mrpt/poses/CPose3DQuatPDFGaussianInf.h line:40 struct PyCallBack_mrpt_poses_CPose3DQuatPDFGaussianInf : public mrpt::poses::CPose3DQuatPDFGaussianInf { using mrpt::poses::CPose3DQuatPDFGaussianInf::CPose3DQuatPDFGaussianInf; @@ -446,8 +446,8 @@ struct PyCallBack_mrpt_poses_CPosePDFGaussianInf : public mrpt::poses::CPosePDFG void bind_mrpt_poses_CPose3DQuatPDFGaussianInf(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::poses::CPose3DQuatPDFGaussianInf file:mrpt/poses/CPose3DQuatPDFGaussianInf.h line:42 - pybind11::class_, PyCallBack_mrpt_poses_CPose3DQuatPDFGaussianInf, mrpt::poses::CPose3DQuatPDF> cl(M("mrpt::poses"), "CPose3DQuatPDFGaussianInf", "Declares a class that represents a Probability Density function (PDF) of a\n 3D pose using a quaternion \n\n\n\n.\n\n This class implements that PDF using a mono-modal Gaussian distribution\n storing the information matrix instead of its inverse, the covariance matrix.\n See mrpt::poses::CPose3DQuatPDF for more details, or\n mrpt::poses::CPose3DPDF for classes based on Euler angles instead.\n\n Uncertainty of pose composition operations (\n) is\n implemented in the methods \"CPose3DQuatPDFGaussianInf::operator+=\" and\n \"CPose3DQuatPDF::jacobiansPoseComposition\".\n\n For further details on implemented methods and the theory behind them,\n see \n* href=\"http://www.mrpt.org/6D_poses:equivalences_compositions_and_uncertainty\"\n >this report.\n\n \n CPose3DQuat, CPose3DQuatPDF, CPose3DPDF, CPose3DQuatPDFGaussian\n \n\n\n "); + { // mrpt::poses::CPose3DQuatPDFGaussianInf file:mrpt/poses/CPose3DQuatPDFGaussianInf.h line:40 + pybind11::class_, PyCallBack_mrpt_poses_CPose3DQuatPDFGaussianInf, mrpt::poses::CPose3DQuatPDF> cl(M("mrpt::poses"), "CPose3DQuatPDFGaussianInf", "Declares a class that represents a Probability Density function (PDF) of a\n 3D pose using a quaternion \n\n\n\n.\n\n This class implements that PDF using a mono-modal Gaussian distribution\n storing the information matrix instead of its inverse, the covariance matrix.\n See mrpt::poses::CPose3DQuatPDF for more details, or\n mrpt::poses::CPose3DPDF for classes based on Euler angles instead.\n\n Uncertainty of pose composition operations (\n) is\n implemented in the methods \"CPose3DQuatPDFGaussianInf::operator+=\" and\n \"CPose3DQuatPDF::jacobiansPoseComposition\".\n\n \n Read also: \"A tutorial on SE(3) transformation parameterizations and\n on-manifold optimization\", in \n\n \n CPose3DQuat, CPose3DQuatPDF, CPose3DPDF, CPose3DQuatPDFGaussian\n \n\n\n "); cl.def( pybind11::init( [](){ return new mrpt::poses::CPose3DQuatPDFGaussianInf(); }, [](){ return new PyCallBack_mrpt_poses_CPose3DQuatPDFGaussianInf(); } ) ); cl.def( pybind11::init(), pybind11::arg("constructor_dummy_param") ); From 013a92ddfaf7b5009cbd469173b2b5b413f082a7 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Thu, 5 Oct 2023 00:10:07 +0200 Subject: [PATCH 31/31] changelog: Release date --- doc/source/doxygen-docs/changelog.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 437d0edd15..19e92ccc9e 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -1,6 +1,6 @@ \page changelog Change Log -# Version 2.10.2: UNRELEASED +# Version 2.10.2: Released Oct 5th, 2023 - Build system: - ROS: fix missing deps in package.xml needed for build via Nix. - MRPT and OpenCV versions were until now exposed as macros with 3 hexadecimal digits (e.g. `2.4.0`->`0x240`), with a clear limitation of versions greater than 15. Now, both symbols `MRPT_VERSION` and `MRPT_OPENCV_VERSION_NUM` use TWO hexadecimal digits per version part, like: `2.10.2` -> `0x010A02`, which is much more general and safe for the future. For backwards compatibility, just make sure your user code only uses `MRPT_VERSION>=xxx` or `MRPT_VERSION>xxx` comparisons, instead of less-than comparisons (Fixes [issue #1285](https://github.com/MRPT/mrpt/issues/1285)).