diff --git a/CMakeLists.txt b/CMakeLists.txt index d819359592..44b88ddf66 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -308,6 +308,7 @@ include(cmakemodules/script_SIMD.cmake REQUIRED) # SSE2/SSE3/... optimiza include(cmakemodules/script_simpleini.cmake REQUIRED) # SimpleINI lib include(cmakemodules/script_suitesparse.cmake REQUIRED) # SuiteSparse libs include(cmakemodules/script_swissrange.cmake REQUIRED) # Support for SWISSRANGE 3D camera: +include(cmakemodules/script_tbb.cmake REQUIRED) # TBB include(cmakemodules/script_tinyxml2.cmake REQUIRED) # tinyxml2 lib include(cmakemodules/script_triclops.cmake REQUIRED) # Check for PointGreyResearch (PGR) Triclops library include(cmakemodules/script_videre_svs.cmake REQUIRED) # Support for Videre Design stereo camera: diff --git a/apps/ro-localization/CPosePDFParticlesExtended.h b/apps/ro-localization/CPosePDFParticlesExtended.h index 8f99645b37..13e58f7d0f 100644 --- a/apps/ro-localization/CPosePDFParticlesExtended.h +++ b/apps/ro-localization/CPosePDFParticlesExtended.h @@ -30,8 +30,6 @@ class TExtendedCPose2D mrpt::math::CVectorDouble state; }; -#define DUMMY_LINKAGE - /** Declares a class that represents a Probability Distribution * function (PDF) of a 2D pose (x,y,phi). * This class implements that PDF using a set of particles diff --git a/appveyor.yml b/appveyor.yml index 04450d4081..89a4f73fd7 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -1,5 +1,5 @@ # version format -version: 2.13.8-{branch}-build{build} +version: 2.14.0-{branch}-build{build} os: Visual Studio 2019 diff --git a/cmakemodules/script_show_final_summary.cmake b/cmakemodules/script_show_final_summary.cmake index 120854f2b7..18c193acb8 100644 --- a/cmakemodules/script_show_final_summary.cmake +++ b/cmakemodules/script_show_final_summary.cmake @@ -143,6 +143,7 @@ SHOW_CONFIG_LINE_SYSTEM("OpenGL GLES " CMAKE_MRPT_HAS_GL SHOW_CONFIG_LINE_SYSTEM("GLUT " CMAKE_MRPT_HAS_GLUT) SHOW_CONFIG_LINE_SYSTEM("PCAP (Wireshark logs for Velodyne) " CMAKE_MRPT_HAS_LIBPCAP) SHOW_CONFIG_LINE_SYSTEM("SuiteSparse " CMAKE_MRPT_HAS_SUITESPARSE "[Version: ${SuiteSparse_VERSION}]") +SHOW_CONFIG_LINE_SYSTEM("TBB " CMAKE_MRPT_HAS_TBB "[Version: ${TBB_VERSION}]") SHOW_CONFIG_LINE_SYSTEM("tinyxml2 " CMAKE_MRPT_HAS_TINYXML2) SHOW_CONFIG_LINE_SYSTEM("wxWidgets " CMAKE_MRPT_HAS_WXWIDGETS "[Version: ${wxWidgets_VERSION_STRING} ${CMAKE_WXWIDGETS_TOOLKIT_NAME}]") message(STATUS "") diff --git a/cmakemodules/script_tbb.cmake b/cmakemodules/script_tbb.cmake new file mode 100644 index 0000000000..a6ed26147d --- /dev/null +++ b/cmakemodules/script_tbb.cmake @@ -0,0 +1,16 @@ + +set(CMAKE_MRPT_HAS_TBB 0) +set(CMAKE_MRPT_HAS_TBB_SYSTEM 0) + +option(DISABLE_TBB "Force not using TBB" "OFF") +mark_as_advanced(DISABLE_TBB) +if(DISABLE_TBB) + return() +endif() + +find_package(TBB QUIET) + +if(TBB_FOUND) + set(CMAKE_MRPT_HAS_TBB 1) + set(CMAKE_MRPT_HAS_TBB_SYSTEM 1) +endif() diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 5835cec8ab..2c7c66dc99 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -1,5 +1,18 @@ \page changelog Change Log +# Version 2.14.0: Released Sep 15th, 2024 +- Changes in libraries: + - \ref mrpt_slam_grp: + - Particle filtering algorithm pfStandardProposal now uses TBB (if present) for automatically running weight updates in parallel. + - \ref mrpt_rtti_grp: + - mrpt::rtti::CObject::GetRuntimeClassIdStatic() no longer depends on static variables, but on constexpr. This totally removes the possibility of initialization order fiasco while registering classes. + - **IMPORTANT CHANGE**: To make the change above possible, these macros have changed: + - `DEFINE_VIRTUAL_SERIALIZABLE(class)` ==>`DEFINE_VIRTUAL_SERIALIZABLE(class, namespace)` + - `DEFINE_VIRTUAL_MRPT_OBJECT(class)` ==>`DEFINE_VIRTUAL_MRPT_OBJECT(class, namespace)` +- BUG FIXES: + - Fix recursive mutex lock if calling mrpt::opengl::CPointCloud::insertPoint() with signatures for mrpt::math::TPoint3D. + - Fix potential initialization-order fiasco accessing GetRuntimeClassIdStatic() in clang (see change above). + # Version 2.13.8: Released Sep 7th, 2024 - Changes in libraries: - \ref mrpt_vision_grp: diff --git a/libs/kinematics/include/mrpt/kinematics/CVehicleVelCmd.h b/libs/kinematics/include/mrpt/kinematics/CVehicleVelCmd.h index 379f89632c..1feb9d8fc0 100644 --- a/libs/kinematics/include/mrpt/kinematics/CVehicleVelCmd.h +++ b/libs/kinematics/include/mrpt/kinematics/CVehicleVelCmd.h @@ -21,7 +21,7 @@ namespace mrpt::kinematics * \ingroup mrpt_kinematics_grp */ class CVehicleVelCmd : public mrpt::serialization::CSerializable, public mrpt::Stringifyable { - DEFINE_VIRTUAL_SERIALIZABLE(CVehicleVelCmd) + DEFINE_VIRTUAL_SERIALIZABLE(CVehicleVelCmd, mrpt::kinematics) public: CVehicleVelCmd(); CVehicleVelCmd(const CVehicleVelCmd& other); diff --git a/libs/maps/include/mrpt/maps/CPointsMap.h b/libs/maps/include/mrpt/maps/CPointsMap.h index 0ec76a2dc6..a0551baaba 100644 --- a/libs/maps/include/mrpt/maps/CPointsMap.h +++ b/libs/maps/include/mrpt/maps/CPointsMap.h @@ -75,7 +75,7 @@ class CPointsMap : public mrpt::opengl::PLY_Exporter, public mrpt::maps::NearestNeighborsCapable { - DEFINE_VIRTUAL_SERIALIZABLE(CPointsMap) + DEFINE_VIRTUAL_SERIALIZABLE(CPointsMap, mrpt::maps) // This must be added for declaration of MEX-related functions DECLARE_MEX_CONVERSION diff --git a/libs/maps/include/mrpt/maps/CRandomFieldGridMap2D.h b/libs/maps/include/mrpt/maps/CRandomFieldGridMap2D.h index 5202c6a45d..6beea84064 100644 --- a/libs/maps/include/mrpt/maps/CRandomFieldGridMap2D.h +++ b/libs/maps/include/mrpt/maps/CRandomFieldGridMap2D.h @@ -158,7 +158,7 @@ class CRandomFieldGridMap2D : { using BASE = mrpt::containers::CDynamicGrid; - DEFINE_VIRTUAL_SERIALIZABLE(CRandomFieldGridMap2D) + DEFINE_VIRTUAL_SERIALIZABLE(CRandomFieldGridMap2D, mrpt::maps) public: /** Calls the base CMetricMap::clear * Declared here to avoid ambiguity between the two clear() in both base diff --git a/libs/nav/include/mrpt/nav/holonomic/CAbstractHolonomicReactiveMethod.h b/libs/nav/include/mrpt/nav/holonomic/CAbstractHolonomicReactiveMethod.h index fb41b70c65..61a9f67a12 100644 --- a/libs/nav/include/mrpt/nav/holonomic/CAbstractHolonomicReactiveMethod.h +++ b/libs/nav/include/mrpt/nav/holonomic/CAbstractHolonomicReactiveMethod.h @@ -28,7 +28,7 @@ namespace mrpt::nav */ class CAbstractHolonomicReactiveMethod : public mrpt::serialization::CSerializable { - DEFINE_VIRTUAL_SERIALIZABLE(CAbstractHolonomicReactiveMethod) + DEFINE_VIRTUAL_SERIALIZABLE(CAbstractHolonomicReactiveMethod, mrpt::nav) public: /** Input parameters for CAbstractHolonomicReactiveMethod::navigate() */ struct NavInput diff --git a/libs/nav/include/mrpt/nav/holonomic/CHolonomicLogFileRecord.h b/libs/nav/include/mrpt/nav/holonomic/CHolonomicLogFileRecord.h index 5669ada410..301b1572c8 100644 --- a/libs/nav/include/mrpt/nav/holonomic/CHolonomicLogFileRecord.h +++ b/libs/nav/include/mrpt/nav/holonomic/CHolonomicLogFileRecord.h @@ -23,7 +23,7 @@ namespace mrpt::nav */ class CHolonomicLogFileRecord : public mrpt::serialization::CSerializable { - DEFINE_VIRTUAL_SERIALIZABLE(CHolonomicLogFileRecord) + DEFINE_VIRTUAL_SERIALIZABLE(CHolonomicLogFileRecord, mrpt::nav) public: /** Final [N-1] and earlier stages [0...N-1] evaluation scores for each * direction, in the same order of TP-Obstacles. May be not filled by all diff --git a/libs/nav/include/mrpt/nav/reactive/CMultiObjectiveMotionOptimizerBase.h b/libs/nav/include/mrpt/nav/reactive/CMultiObjectiveMotionOptimizerBase.h index 7b1349913e..b446a205c1 100644 --- a/libs/nav/include/mrpt/nav/reactive/CMultiObjectiveMotionOptimizerBase.h +++ b/libs/nav/include/mrpt/nav/reactive/CMultiObjectiveMotionOptimizerBase.h @@ -23,7 +23,7 @@ namespace mrpt::nav */ class CMultiObjectiveMotionOptimizerBase : public mrpt::rtti::CObject { - DEFINE_VIRTUAL_MRPT_OBJECT(CMultiObjectiveMotionOptimizerBase) + DEFINE_VIRTUAL_MRPT_OBJECT(CMultiObjectiveMotionOptimizerBase, mrpt::nav) public: /** Class factory from C++ class name */ static CMultiObjectiveMotionOptimizerBase::Ptr Factory(const std::string& className) noexcept; diff --git a/libs/nav/include/mrpt/nav/tpspace/CParameterizedTrajectoryGenerator.h b/libs/nav/include/mrpt/nav/tpspace/CParameterizedTrajectoryGenerator.h index 38904bac24..f7d4a19ea0 100644 --- a/libs/nav/include/mrpt/nav/tpspace/CParameterizedTrajectoryGenerator.h +++ b/libs/nav/include/mrpt/nav/tpspace/CParameterizedTrajectoryGenerator.h @@ -80,7 +80,7 @@ class CParameterizedTrajectoryGenerator : public mrpt::serialization::CSerializable, public mrpt::config::CLoadableOptions { - DEFINE_VIRTUAL_SERIALIZABLE(CParameterizedTrajectoryGenerator) + DEFINE_VIRTUAL_SERIALIZABLE(CParameterizedTrajectoryGenerator, mrpt::nav) public: /** Default ctor. Must call `loadFromConfigFile()` before initialization */ CParameterizedTrajectoryGenerator() = default; diff --git a/libs/nav/src/tpspace/CPTG_DiffDrive_CollisionGridBased.cpp b/libs/nav/src/tpspace/CPTG_DiffDrive_CollisionGridBased.cpp index 69823daba5..1834a80abd 100644 --- a/libs/nav/src/tpspace/CPTG_DiffDrive_CollisionGridBased.cpp +++ b/libs/nav/src/tpspace/CPTG_DiffDrive_CollisionGridBased.cpp @@ -9,6 +9,8 @@ #include "nav-precomp.h" // Precomp header // +#include +#include #include #include #include @@ -785,7 +787,7 @@ void CPTG_DiffDrive_CollisionGridBased::internal_initialize( } } // k - if (verbose) cout << format("Done! [%.03f sec]\n", tictac.Tac()); + if (verbose) cout << format("Done! [%.03f sec]", tictac.Tac()) << std::endl; // save it to the cache file for the next run: saveColGridsToFile(cacheFilename, m_robotShape); diff --git a/libs/obs/include/mrpt/maps/CMetricMap.h b/libs/obs/include/mrpt/maps/CMetricMap.h index 8284047b62..1452e4c4a3 100644 --- a/libs/obs/include/mrpt/maps/CMetricMap.h +++ b/libs/obs/include/mrpt/maps/CMetricMap.h @@ -76,7 +76,7 @@ class CMetricMap : public mrpt::Stringifyable, public mrpt::opengl::Visualizable { - DEFINE_VIRTUAL_SERIALIZABLE(CMetricMap) + DEFINE_VIRTUAL_SERIALIZABLE(CMetricMap, mrpt::obs) private: /** Internal method called by clear() */ diff --git a/libs/obs/include/mrpt/obs/CAction.h b/libs/obs/include/mrpt/obs/CAction.h index 2ea35e6ea9..1b3ceae896 100644 --- a/libs/obs/include/mrpt/obs/CAction.h +++ b/libs/obs/include/mrpt/obs/CAction.h @@ -23,7 +23,7 @@ namespace mrpt::obs */ class CAction : public mrpt::serialization::CSerializable { - DEFINE_VIRTUAL_SERIALIZABLE(CAction) + DEFINE_VIRTUAL_SERIALIZABLE(CAction, mrpt::obs) public: /** Default ctor */ CAction() = default; diff --git a/libs/obs/include/mrpt/obs/CObservation.h b/libs/obs/include/mrpt/obs/CObservation.h index 19d55eb033..249d942766 100644 --- a/libs/obs/include/mrpt/obs/CObservation.h +++ b/libs/obs/include/mrpt/obs/CObservation.h @@ -49,7 +49,7 @@ static constexpr int INVALID_LANDMARK_ID = -1; */ class CObservation : public mrpt::serialization::CSerializable, public mrpt::Stringifyable { - DEFINE_VIRTUAL_SERIALIZABLE(CObservation) + DEFINE_VIRTUAL_SERIALIZABLE(CObservation, mrpt::obs) protected: /** Swap with another observation, ONLY the data defined here in the base diff --git a/libs/obs/include/mrpt/obs/CObservation2DRangeScan.h b/libs/obs/include/mrpt/obs/CObservation2DRangeScan.h index 4e07f77cc9..88bf90ac02 100644 --- a/libs/obs/include/mrpt/obs/CObservation2DRangeScan.h +++ b/libs/obs/include/mrpt/obs/CObservation2DRangeScan.h @@ -8,7 +8,9 @@ +------------------------------------------------------------------------+ */ #pragma once +#include #include +#include #include #include #include @@ -16,6 +18,8 @@ #include #include +#include + // Add for declaration of mexplus::from template specialization DECLARE_MEXPLUS_FROM(mrpt::obs::CObservation2DRangeScan) @@ -166,6 +170,7 @@ class CObservation2DRangeScan : public CObservation * It's a generic smart pointer to avoid depending here in the library * mrpt-obs on classes on other libraries. */ + mutable mrpt::containers::NonCopiableData m_cachedMapMtx; mutable mrpt::maps::CMetricMap::Ptr m_cachedMap; /** Internal method, used from buildAuxPointsMap() */ void internal_buildAuxPointsMap(const void* options = nullptr) const; @@ -183,6 +188,7 @@ class CObservation2DRangeScan : public CObservation template inline const POINTSMAP* getAuxPointsMap() const { + auto lck = mrpt::lockHelper(m_cachedMapMtx.data); return static_cast(m_cachedMap.get()); } @@ -201,6 +207,8 @@ class CObservation2DRangeScan : public CObservation template inline const POINTSMAP* buildAuxPointsMap(const void* options = nullptr) const { + auto lck = mrpt::lockHelper(m_cachedMapMtx.data); + if (!m_cachedMap) internal_buildAuxPointsMap(options); return static_cast(m_cachedMap.get()); } diff --git a/libs/obs/src/CObservation2DRangeScan.cpp b/libs/obs/src/CObservation2DRangeScan.cpp index c67958a55b..0441ad13ba 100644 --- a/libs/obs/src/CObservation2DRangeScan.cpp +++ b/libs/obs/src/CObservation2DRangeScan.cpp @@ -178,6 +178,7 @@ void CObservation2DRangeScan::serializeFrom(mrpt::serialization::CArchive& in, u MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version); }; + auto lck = mrpt::lockHelper(m_cachedMapMtx.data); m_cachedMap.reset(); } @@ -423,6 +424,8 @@ void internal_set_build_points_map_from_scan2D(scan2pts_functor fn) ---------------------------------------------------------------*/ void CObservation2DRangeScan::internal_buildAuxPointsMap(const void* options) const { + auto lck = mrpt::lockHelper(m_cachedMapMtx.data); + if (!ptr_internal_build_points_map_from_scan2D) throw std::runtime_error( "[CObservation2DRangeScan::buildAuxPointsMap] ERROR: This function " diff --git a/libs/opengl/include/mrpt/opengl/CPointCloud.h b/libs/opengl/include/mrpt/opengl/CPointCloud.h index 9ff10574dd..bf19b9bdb2 100644 --- a/libs/opengl/include/mrpt/opengl/CPointCloud.h +++ b/libs/opengl/include/mrpt/opengl/CPointCloud.h @@ -195,12 +195,12 @@ class CPointCloud : void insertPoint(const mrpt::math::TPoint3Df& p) { - std::unique_lock wfWriteLock(CRenderizableShaderPoints::m_pointsMtx.data); + // lock already hold by insertPoint() below insertPoint(p.x, p.y, p.z); } void insertPoint(const mrpt::math::TPoint3D& p) { - std::unique_lock wfWriteLock(CRenderizableShaderPoints::m_pointsMtx.data); + // lock already hold by insertPoint() below insertPoint(p.x, p.y, p.z); } diff --git a/libs/opengl/include/mrpt/opengl/CRenderizable.h b/libs/opengl/include/mrpt/opengl/CRenderizable.h index cfa533306c..0934a241c7 100644 --- a/libs/opengl/include/mrpt/opengl/CRenderizable.h +++ b/libs/opengl/include/mrpt/opengl/CRenderizable.h @@ -70,7 +70,7 @@ enum class TCullFace : uint8_t */ class CRenderizable : public mrpt::serialization::CSerializable { - DEFINE_VIRTUAL_SERIALIZABLE(CRenderizable) + DEFINE_VIRTUAL_SERIALIZABLE(CRenderizable, mrpt::opengl) friend class mrpt::opengl::Viewport; friend class mrpt::opengl::CSetOfObjects; diff --git a/libs/opengl/include/mrpt/opengl/CRenderizableShaderPoints.h b/libs/opengl/include/mrpt/opengl/CRenderizableShaderPoints.h index 3ff760eb9c..bc20a17c0f 100644 --- a/libs/opengl/include/mrpt/opengl/CRenderizableShaderPoints.h +++ b/libs/opengl/include/mrpt/opengl/CRenderizableShaderPoints.h @@ -37,7 +37,7 @@ namespace mrpt::opengl */ class CRenderizableShaderPoints : public virtual CRenderizable { - DEFINE_VIRTUAL_SERIALIZABLE(CRenderizableShaderPoints) + DEFINE_VIRTUAL_SERIALIZABLE(CRenderizableShaderPoints, mrpt::opengl) public: CRenderizableShaderPoints() = default; diff --git a/libs/opengl/include/mrpt/opengl/CRenderizableShaderText.h b/libs/opengl/include/mrpt/opengl/CRenderizableShaderText.h index e723ded85c..7599ae6938 100644 --- a/libs/opengl/include/mrpt/opengl/CRenderizableShaderText.h +++ b/libs/opengl/include/mrpt/opengl/CRenderizableShaderText.h @@ -26,7 +26,7 @@ namespace mrpt::opengl */ class CRenderizableShaderText : public virtual CRenderizable { - DEFINE_VIRTUAL_SERIALIZABLE(CRenderizableShaderText) + DEFINE_VIRTUAL_SERIALIZABLE(CRenderizableShaderText, mrpt::opengl) public: CRenderizableShaderText() = default; diff --git a/libs/opengl/include/mrpt/opengl/CRenderizableShaderTexturedTriangles.h b/libs/opengl/include/mrpt/opengl/CRenderizableShaderTexturedTriangles.h index 23da1e39e1..871be6586a 100644 --- a/libs/opengl/include/mrpt/opengl/CRenderizableShaderTexturedTriangles.h +++ b/libs/opengl/include/mrpt/opengl/CRenderizableShaderTexturedTriangles.h @@ -27,7 +27,7 @@ namespace mrpt::opengl */ class CRenderizableShaderTexturedTriangles : public virtual CRenderizable { - DEFINE_VIRTUAL_SERIALIZABLE(CRenderizableShaderTexturedTriangles) + DEFINE_VIRTUAL_SERIALIZABLE(CRenderizableShaderTexturedTriangles, mrpt::opengl) public: CRenderizableShaderTexturedTriangles() = default; diff --git a/libs/opengl/include/mrpt/opengl/CRenderizableShaderTriangles.h b/libs/opengl/include/mrpt/opengl/CRenderizableShaderTriangles.h index 54d5a5606a..b8c2655d86 100644 --- a/libs/opengl/include/mrpt/opengl/CRenderizableShaderTriangles.h +++ b/libs/opengl/include/mrpt/opengl/CRenderizableShaderTriangles.h @@ -26,7 +26,7 @@ namespace mrpt::opengl */ class CRenderizableShaderTriangles : public virtual CRenderizable { - DEFINE_VIRTUAL_SERIALIZABLE(CRenderizableShaderTriangles) + DEFINE_VIRTUAL_SERIALIZABLE(CRenderizableShaderTriangles, mrpt::opengl) public: CRenderizableShaderTriangles() = default; diff --git a/libs/opengl/include/mrpt/opengl/CRenderizableShaderWireFrame.h b/libs/opengl/include/mrpt/opengl/CRenderizableShaderWireFrame.h index 7973d6576f..ffc8bf595b 100644 --- a/libs/opengl/include/mrpt/opengl/CRenderizableShaderWireFrame.h +++ b/libs/opengl/include/mrpt/opengl/CRenderizableShaderWireFrame.h @@ -25,7 +25,7 @@ namespace mrpt::opengl */ class CRenderizableShaderWireFrame : public virtual CRenderizable { - DEFINE_VIRTUAL_SERIALIZABLE(CRenderizableShaderWireFrame) + DEFINE_VIRTUAL_SERIALIZABLE(CRenderizableShaderWireFrame, mrpt::opengl) public: CRenderizableShaderWireFrame() = default; diff --git a/libs/poses/include/mrpt/poses/CPoint2DPDF.h b/libs/poses/include/mrpt/poses/CPoint2DPDF.h index 70a7351997..1375bb3e80 100644 --- a/libs/poses/include/mrpt/poses/CPoint2DPDF.h +++ b/libs/poses/include/mrpt/poses/CPoint2DPDF.h @@ -34,7 +34,7 @@ class CPoint2DPDF : public mrpt::serialization::CSerializable, public mrpt::math::CProbabilityDensityFunction { - DEFINE_VIRTUAL_SERIALIZABLE(CPoint2DPDF) + DEFINE_VIRTUAL_SERIALIZABLE(CPoint2DPDF, mrpt::poses) public: /** Copy operator, translating if necessary (for example, between particles diff --git a/libs/poses/include/mrpt/poses/CPointPDF.h b/libs/poses/include/mrpt/poses/CPointPDF.h index 408a34d35c..09115ca326 100644 --- a/libs/poses/include/mrpt/poses/CPointPDF.h +++ b/libs/poses/include/mrpt/poses/CPointPDF.h @@ -36,7 +36,7 @@ class CPointPDF : public mrpt::serialization::CSerializable, public mrpt::math::CProbabilityDensityFunction { - DEFINE_VIRTUAL_SERIALIZABLE(CPointPDF) + DEFINE_VIRTUAL_SERIALIZABLE(CPointPDF, mrpt::poses) public: /** Copy operator, translating if necessary (for example, between particles diff --git a/libs/poses/include/mrpt/poses/CPose3DPDF.h b/libs/poses/include/mrpt/poses/CPose3DPDF.h index 93af402b99..9a6638036f 100644 --- a/libs/poses/include/mrpt/poses/CPose3DPDF.h +++ b/libs/poses/include/mrpt/poses/CPose3DPDF.h @@ -37,7 +37,7 @@ class CPose3DPDF : public mrpt::serialization::CSerializable, public mrpt::math::CProbabilityDensityFunction { - DEFINE_VIRTUAL_SERIALIZABLE(CPose3DPDF) + DEFINE_VIRTUAL_SERIALIZABLE(CPose3DPDF, mrpt::poses) public: /** Copy operator, translating if necessary (for example, between particles diff --git a/libs/poses/include/mrpt/poses/CPose3DQuatPDF.h b/libs/poses/include/mrpt/poses/CPose3DQuatPDF.h index 11534061cf..1539ead220 100644 --- a/libs/poses/include/mrpt/poses/CPose3DQuatPDF.h +++ b/libs/poses/include/mrpt/poses/CPose3DQuatPDF.h @@ -42,7 +42,7 @@ class CPose3DQuatPDF : public mrpt::serialization::CSerializable, public mrpt::math::CProbabilityDensityFunction { - DEFINE_VIRTUAL_SERIALIZABLE(CPose3DQuatPDF) + DEFINE_VIRTUAL_SERIALIZABLE(CPose3DQuatPDF, mrpt::poses) public: /** Copy operator, translating if necessary (for example, between particles diff --git a/libs/poses/include/mrpt/poses/CPosePDF.h b/libs/poses/include/mrpt/poses/CPosePDF.h index 389ca42ac8..796d3b9981 100644 --- a/libs/poses/include/mrpt/poses/CPosePDF.h +++ b/libs/poses/include/mrpt/poses/CPosePDF.h @@ -37,7 +37,7 @@ class CPosePDF : public mrpt::serialization::CSerializable, public mrpt::math::CProbabilityDensityFunction { - DEFINE_VIRTUAL_SERIALIZABLE(CPosePDF) + DEFINE_VIRTUAL_SERIALIZABLE(CPosePDF, mrpt::poses) public: /** Copy operator, translating if necessary (for example, between particles diff --git a/libs/rtti/include/mrpt/rtti/CObject.h b/libs/rtti/include/mrpt/rtti/CObject.h index 00eeaf7dfa..0eb8973f4c 100644 --- a/libs/rtti/include/mrpt/rtti/CObject.h +++ b/libs/rtti/include/mrpt/rtti/CObject.h @@ -12,7 +12,6 @@ #include #include // literal() -#include #include #include @@ -32,11 +31,12 @@ class CObject; struct TRuntimeClassId { using Ptr = safe_ptr; - const char* className; + const char* className = nullptr; /** Create an object of the related class, or nullptr if it is virtual. */ - std::function(void)> ptrCreateObject; + std::shared_ptr (*ptrCreateObject)() = nullptr; + /** Gets the base class runtime id. */ - const TRuntimeClassId* (*getBaseClass)(); + const TRuntimeClassId* (*getBaseClass)() = nullptr; // Operations std::shared_ptr createObject() const; @@ -176,7 +176,7 @@ class CObject { protected: static mrpt::rtti::TRuntimeClassId* _GetBaseClass(); - static const mrpt::rtti::TRuntimeClassId runtimeClassId; + static constexpr mrpt::rtti::TRuntimeClassId runtimeClassId = {"CObject", nullptr, nullptr}; public: using Ptr = std::shared_ptr; @@ -206,10 +206,6 @@ inline mrpt::rtti::CObject::Ptr CObject::duplicateGetSmartPtr() const #define DEFINE_MRPT_OBJECT(class_name, NameSpace) \ /*! @name RTTI stuff */ \ /*! @{ */ \ - protected: \ - static const mrpt::rtti::TRuntimeClassId* _GetBaseClass(); \ - static const mrpt::rtti::TRuntimeClassId runtimeClassId; \ - \ public: \ /*! A type for the associated smart pointer */ \ using Ptr = std::shared_ptr; \ @@ -240,49 +236,55 @@ inline mrpt::rtti::CObject::Ptr CObject::duplicateGetSmartPtr() const { \ return std::make_unique(std::forward(args)...); \ } \ + \ + protected: \ + static const mrpt::rtti::TRuntimeClassId* _GetBaseClass(); \ + static constexpr mrpt::rtti::TRuntimeClassId runtimeClassId = { \ + #NameSpace "::" #class_name, NameSpace::class_name::CreateObject, \ + &class_name::_GetBaseClass}; \ + \ /*! @} */ \ public: -#define INTERNAL_IMPLEMENTS_MRPT_OBJECT(class_name, base, NameSpace, class_registry_name) \ - mrpt::rtti::CObject::Ptr NameSpace::class_name::CreateObject() \ - { \ - return std::static_pointer_cast(std::make_shared()); \ - } \ - const mrpt::rtti::TRuntimeClassId* NameSpace::class_name::_GetBaseClass() \ - { \ - return CLASS_ID(base); \ - } \ - const mrpt::rtti::TRuntimeClassId& NameSpace::class_name::GetRuntimeClassIdStatic() \ - { \ - return NameSpace::class_name::runtimeClassId; \ - } \ - const mrpt::rtti::TRuntimeClassId NameSpace::class_name::runtimeClassId = { \ - class_registry_name, NameSpace::class_name::CreateObject, &class_name::_GetBaseClass}; \ - const mrpt::rtti::TRuntimeClassId* NameSpace::class_name::GetRuntimeClass() const \ - { \ - return CLASS_ID_NAMESPACE(class_name, NameSpace); \ - } \ - mrpt::rtti::CObject* NameSpace::class_name::clone() const \ - { \ - return mrpt::rtti::internal::CopyCtor< \ - std::is_copy_constructible::value>::clone(*this); \ +#define INTERNAL_IMPLEMENTS_MRPT_OBJECT(class_name, base, NameSpace) \ + mrpt::rtti::CObject::Ptr NameSpace::class_name::CreateObject() \ + { \ + return std::static_pointer_cast(std::make_shared()); \ + } \ + const mrpt::rtti::TRuntimeClassId* NameSpace::class_name::_GetBaseClass() \ + { \ + return CLASS_ID(base); \ + } \ + const mrpt::rtti::TRuntimeClassId& NameSpace::class_name::GetRuntimeClassIdStatic() \ + { \ + return NameSpace::class_name::runtimeClassId; \ + } \ + const mrpt::rtti::TRuntimeClassId* NameSpace::class_name::GetRuntimeClass() const \ + { \ + return CLASS_ID_NAMESPACE(class_name, NameSpace); \ + } \ + mrpt::rtti::CObject* NameSpace::class_name::clone() const \ + { \ + return mrpt::rtti::internal::CopyCtor< \ + std::is_copy_constructible::value>::clone(*this); \ } /** Must be added to all CObject-derived classes implementation file. * This registers class ns1::Foo as "ns1::Foo". */ #define IMPLEMENTS_MRPT_OBJECT(class_name, base, NameSpace) \ - INTERNAL_IMPLEMENTS_MRPT_OBJECT(class_name, base, NameSpace, #NameSpace "::" #class_name) + INTERNAL_IMPLEMENTS_MRPT_OBJECT(class_name, base, NameSpace) /** This declaration must be inserted in virtual CObject classes * definition: */ -#define DEFINE_VIRTUAL_MRPT_OBJECT(class_name) \ +#define DEFINE_VIRTUAL_MRPT_OBJECT(class_name, NameSpace) \ /*! @name RTTI stuff */ \ /*! @{ */ \ protected: \ static const mrpt::rtti::TRuntimeClassId* _GetBaseClass(); \ - static const mrpt::rtti::TRuntimeClassId runtimeClassId; \ + static constexpr mrpt::rtti::TRuntimeClassId runtimeClassId = { \ + #NameSpace "::" #class_name, nullptr, &class_name::_GetBaseClass}; \ \ public: \ using Ptr = std::shared_ptr; \ @@ -294,24 +296,22 @@ inline mrpt::rtti::CObject::Ptr CObject::duplicateGetSmartPtr() const /** This must be inserted as implementation of some required members for * virtual CObject classes: */ -#define INTERNAL_IMPLEMENTS_VIRTUAL_MRPT_OBJECT(class_name, base_name, NS, registered_name) \ - const mrpt::rtti::TRuntimeClassId* NS::class_name::_GetBaseClass() \ - { \ - return CLASS_ID(base_name); \ - } \ - const mrpt::rtti::TRuntimeClassId NS::class_name::runtimeClassId = { \ - registered_name, nullptr, &NS::class_name::_GetBaseClass}; \ - const mrpt::rtti::TRuntimeClassId* NS::class_name::GetRuntimeClass() const \ - { \ - return CLASS_ID(class_name); \ - } \ - const mrpt::rtti::TRuntimeClassId& NS::class_name::GetRuntimeClassIdStatic() \ - { \ - return NS::class_name::runtimeClassId; \ +#define INTERNAL_IMPLEMENTS_VIRTUAL_MRPT_OBJECT(class_name, base_name, NS) \ + const mrpt::rtti::TRuntimeClassId* NS::class_name::_GetBaseClass() \ + { \ + return CLASS_ID(base_name); \ + } \ + const mrpt::rtti::TRuntimeClassId* NS::class_name::GetRuntimeClass() const \ + { \ + return CLASS_ID(class_name); \ + } \ + const mrpt::rtti::TRuntimeClassId& NS::class_name::GetRuntimeClassIdStatic() \ + { \ + return NS::class_name::runtimeClassId; \ } #define IMPLEMENTS_VIRTUAL_MRPT_OBJECT(class_name, base, NS) \ - INTERNAL_IMPLEMENTS_VIRTUAL_MRPT_OBJECT(class_name, base, NS, #NS "::" #class_name) + INTERNAL_IMPLEMENTS_VIRTUAL_MRPT_OBJECT(class_name, base, NS) /** Register all pending classes - to be called just before * de-serializing an object, for example. After calling this method, diff --git a/libs/rtti/src/CObject.cpp b/libs/rtti/src/CObject.cpp index 30e0d46cd1..3ae24f7b24 100644 --- a/libs/rtti/src/CObject.cpp +++ b/libs/rtti/src/CObject.cpp @@ -102,7 +102,6 @@ CObject::Ptr TRuntimeClassId::createObject() const // since it has no base class. These methods are defined // automatically for derived classes. TRuntimeClassId* CObject::_GetBaseClass() { return nullptr; } -const struct TRuntimeClassId CObject::runtimeClassId = {"CObject", nullptr, nullptr}; mrpt::rtti::CObject::Ptr mrpt::rtti::classFactory(const std::string& className) { diff --git a/libs/serialization/include/mrpt/serialization/CSerializable.h b/libs/serialization/include/mrpt/serialization/CSerializable.h index 66e007f226..1dda8ba551 100644 --- a/libs/serialization/include/mrpt/serialization/CSerializable.h +++ b/libs/serialization/include/mrpt/serialization/CSerializable.h @@ -34,9 +34,7 @@ class CSerializable : public mrpt::rtti::CObject friend class CSchemeArchiveBase; // This must be added to any CObject derived class: - DEFINE_VIRTUAL_MRPT_OBJECT(CSerializable) - - ~CSerializable() override = default; + DEFINE_VIRTUAL_MRPT_OBJECT(CSerializable, mrpt::serialization) protected: /** @name CSerializable virtual methods @@ -163,7 +161,8 @@ void OctetVectorToObject(const std::vector& in_data, CSerializable::Ptr /** This declaration must be inserted in virtual CSerializable classes * definition: */ -#define DEFINE_VIRTUAL_SERIALIZABLE(class_name) DEFINE_VIRTUAL_MRPT_OBJECT(class_name) +#define DEFINE_VIRTUAL_SERIALIZABLE(class_name, NameSpace) \ + DEFINE_VIRTUAL_MRPT_OBJECT(class_name, NameSpace) /** This must be inserted as implementation of some required members for * virtual CSerializable classes: diff --git a/libs/serialization/src/CSerializable.cpp b/libs/serialization/src/CSerializable.cpp index 92f43f7c2e..358cba64a3 100644 --- a/libs/serialization/src/CSerializable.cpp +++ b/libs/serialization/src/CSerializable.cpp @@ -12,8 +12,6 @@ #include #include -#include - using namespace mrpt; using namespace mrpt::serialization; diff --git a/libs/slam/CMakeLists.txt b/libs/slam/CMakeLists.txt index dde709aadd..efa99147ad 100644 --- a/libs/slam/CMakeLists.txt +++ b/libs/slam/CMakeLists.txt @@ -10,6 +10,12 @@ list(APPEND slam_EXTRA_SRCS list(APPEND slam_EXTRA_SRCS_NAME "slam" "slam" "slam-headers") +if(CMAKE_MRPT_HAS_TBB) + set(tbb_dep TBB) +else() + set(tbb_dep "") +endif() + #--------------------------------------------- # Macro declared in "DeclareMRPTLib.cmake": #--------------------------------------------- @@ -19,8 +25,13 @@ define_mrpt_lib( # Dependencies mrpt-vision mrpt-maps + # Other imported targets: + ${tbb_dep} # find_package() lib name ) if(BUILD_mrpt-slam) + if (CMAKE_MRPT_HAS_TBB) + target_link_libraries(slam PUBLIC TBB::tbb) + endif() endif() diff --git a/libs/slam/include/mrpt/slam/PF_implementations.h b/libs/slam/include/mrpt/slam/PF_implementations.h index e3bbdb1de4..12f1c11eb8 100644 --- a/libs/slam/include/mrpt/slam/PF_implementations.h +++ b/libs/slam/include/mrpt/slam/PF_implementations.h @@ -11,6 +11,7 @@ #include #include +#include #include // averageLogLikelihood() #include // chi2inv #include @@ -21,6 +22,11 @@ #include #include +#include + +#if MRPT_HAS_TBB +#include +#endif /** \file PF_implementations.h * This file contains the implementations of the template members declared in @@ -334,17 +340,31 @@ void PF_implementation::PF_SLAM_implementation_p // UPDATE STAGE // ---------------------------------------------------------------------- // Compute all the likelihood values & update particles weight: +#if MRPT_HAS_TBB + tbb::parallel_for( + tbb::blocked_range(0, M), + [&](const tbb::blocked_range& r) + { + for (size_t i = r.begin(); i != r.end(); ++i) + { +#else for (size_t i = 0; i < M; i++) { - bool pose_is_valid; - const mrpt::math::TPose3D partPose = - getLastPose(i, pose_is_valid); // Take the particle data: - auto partPose2 = mrpt::poses::CPose3D(partPose); - const double obs_log_lik = - PF_SLAM_computeObservationLikelihoodForParticle(PF_options, i, *sf, partPose2); - ASSERT_(!std::isnan(obs_log_lik) && std::isfinite(obs_log_lik)); - me->m_particles[i].log_w += obs_log_lik * PF_options.powFactor; +#endif + bool pose_is_valid; + const mrpt::math::TPose3D partPose = + getLastPose(i, pose_is_valid); // Take the particle data: + auto partPose2 = mrpt::poses::CPose3D(partPose); + const double obs_log_lik = + PF_SLAM_computeObservationLikelihoodForParticle(PF_options, i, *sf, partPose2); + ASSERT_(!std::isnan(obs_log_lik) && std::isfinite(obs_log_lik)); + me->m_particles[i].log_w += obs_log_lik * PF_options.powFactor; +#if MRPT_HAS_TBB + } // for each particle "i" + }); +#else } // for each particle "i" +#endif // Normalization of weights is done outside of this method // automatically. diff --git a/parse-files/config.h.in b/parse-files/config.h.in index fd336a9306..3eaacdb248 100644 --- a/parse-files/config.h.in +++ b/parse-files/config.h.in @@ -112,6 +112,8 @@ ${CMAKE_MRPT_BUILD_SHARED_LIB} #define MRPT_HAS_SIMPLEINI ${CMAKE_MRPT_HAS_SIMPLEINI} #define MRPT_HAS_SIMPLEINI_SYSTEM ${CMAKE_MRPT_HAS_SIMPLEINI_SYSTEM} +#define MRPT_HAS_TBB ${CMAKE_MRPT_HAS_TBB} + #cmakedefine MRPT_ROS_VERSION ${MRPT_ROS_VERSION} /** These two values are detected in Eigen when building MRPT, so we have diff --git a/python/src/mrpt/img/TStereoCamera.cpp b/python/src/mrpt/img/TStereoCamera.cpp index 73dc45cb75..b36fd786ff 100644 --- a/python/src/mrpt/img/TStereoCamera.cpp +++ b/python/src/mrpt/img/TStereoCamera.cpp @@ -101,9 +101,9 @@ void bind_mrpt_img_TStereoCamera(std::function< pybind11::module &(std::string c { { // mrpt::img::TStereoCamera file:mrpt/img/TStereoCamera.h line:23 pybind11::class_, PyCallBack_mrpt_img_TStereoCamera, mrpt::serialization::CSerializable> cl(M("mrpt::img"), "TStereoCamera", "Structure to hold the parameters of a pinhole stereo camera model.\n The parameters obtained for one camera resolution can be used for any other\n resolution by means of the method TStereoCamera::scaleToResolution()\n\n \n mrpt::vision, the application stereo-calib-gui for calibrating a stereo\n camera"); + cl.def( pybind11::init( [](){ return new mrpt::img::TStereoCamera(); }, [](){ return new PyCallBack_mrpt_img_TStereoCamera(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_img_TStereoCamera const &o){ return new PyCallBack_mrpt_img_TStereoCamera(o); } ) ); cl.def( pybind11::init( [](mrpt::img::TStereoCamera const &o){ return new mrpt::img::TStereoCamera(o); } ) ); - cl.def( pybind11::init( [](){ return new mrpt::img::TStereoCamera(); }, [](){ return new PyCallBack_mrpt_img_TStereoCamera(); } ) ); cl.def_readwrite("leftCamera", &mrpt::img::TStereoCamera::leftCamera); cl.def_readwrite("rightCamera", &mrpt::img::TStereoCamera::rightCamera); cl.def_readwrite("rightCameraPose", &mrpt::img::TStereoCamera::rightCameraPose); diff --git a/python/src/mrpt/math/CProbabilityDensityFunction_1.cpp b/python/src/mrpt/math/CProbabilityDensityFunction_1.cpp index ae9067f162..4bbeca71fc 100644 --- a/python/src/mrpt/math/CProbabilityDensityFunction_1.cpp +++ b/python/src/mrpt/math/CProbabilityDensityFunction_1.cpp @@ -214,7 +214,6 @@ void bind_mrpt_math_CProbabilityDensityFunction_1(std::function< pybind11::modul { // mrpt::math::CProbabilityDensityFunction file:mrpt/math/CProbabilityDensityFunction.h line:30 pybind11::class_, std::shared_ptr>, PyCallBack_mrpt_math_CProbabilityDensityFunction_mrpt_poses_CPoint2D_2UL_t> cl(M("mrpt::math"), "CProbabilityDensityFunction_mrpt_poses_CPoint2D_2UL_t", ""); cl.def( pybind11::init( [](){ return new PyCallBack_mrpt_math_CProbabilityDensityFunction_mrpt_poses_CPoint2D_2UL_t(); } ) ); - cl.def(pybind11::init()); cl.def("getMean", (void (mrpt::math::CProbabilityDensityFunction::*)(class mrpt::poses::CPoint2D &) const) &mrpt::math::CProbabilityDensityFunction::getMean, "C++: mrpt::math::CProbabilityDensityFunction::getMean(class mrpt::poses::CPoint2D &) const --> void", pybind11::arg("mean_point")); cl.def("getCovarianceAndMean", (class std::tuple, class mrpt::poses::CPoint2D> (mrpt::math::CProbabilityDensityFunction::*)() const) &mrpt::math::CProbabilityDensityFunction::getCovarianceAndMean, "C++: mrpt::math::CProbabilityDensityFunction::getCovarianceAndMean() const --> class std::tuple, class mrpt::poses::CPoint2D>"); cl.def("getCovarianceAndMean", (void (mrpt::math::CProbabilityDensityFunction::*)(class mrpt::math::CMatrixFixed &, class mrpt::poses::CPoint2D &) const) &mrpt::math::CProbabilityDensityFunction::getCovarianceAndMean, "C++: mrpt::math::CProbabilityDensityFunction::getCovarianceAndMean(class mrpt::math::CMatrixFixed &, class mrpt::poses::CPoint2D &) const --> void", pybind11::arg("c"), pybind11::arg("mean")); diff --git a/python/src/mrpt/poses/CPoint2D.cpp b/python/src/mrpt/poses/CPoint2D.cpp index 1abc52e68f..9239169db5 100644 --- a/python/src/mrpt/poses/CPoint2D.cpp +++ b/python/src/mrpt/poses/CPoint2D.cpp @@ -558,7 +558,6 @@ void bind_mrpt_poses_CPoint2D(std::function< pybind11::module &(std::string cons { // mrpt::poses::CPoint2DPDF file:mrpt/poses/CPoint2DPDF.h line:33 pybind11::class_, PyCallBack_mrpt_poses_CPoint2DPDF, mrpt::serialization::CSerializable, mrpt::math::CProbabilityDensityFunction> cl(M("mrpt::poses"), "CPoint2DPDF", "Declares a class that represents a Probability Distribution function (PDF)\n of a 2D point (x,y).\n This class is just the base class for unifying many different\n ways this PDF can be implemented.\n\n For convenience, a pose composition is also defined for any\n PDF derived class, changeCoordinatesReference, in the form of a method\n rather than an operator.\n\n For a similar class for 6D poses (a 3D point with attitude), see CPose3DPDF\n\n See also:\n [probabilistic spatial representations](tutorial-pdf-over-poses.html)\n\n \n\n \n CPoint2D, CPointPDF"); cl.def( pybind11::init( [](){ return new PyCallBack_mrpt_poses_CPoint2DPDF(); } ) ); - cl.def(pybind11::init()); cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::poses::CPoint2DPDF::*)() const) &mrpt::poses::CPoint2DPDF::GetRuntimeClass, "C++: mrpt::poses::CPoint2DPDF::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::poses::CPoint2DPDF::GetRuntimeClassIdStatic, "C++: mrpt::poses::CPoint2DPDF::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); cl.def("copyFrom", (void (mrpt::poses::CPoint2DPDF::*)(const class mrpt::poses::CPoint2DPDF &)) &mrpt::poses::CPoint2DPDF::copyFrom, "Copy operator, translating if necessary (for example, between particles\n and gaussian representations)\n\nC++: mrpt::poses::CPoint2DPDF::copyFrom(const class mrpt::poses::CPoint2DPDF &) --> void", pybind11::arg("o")); diff --git a/python/src/mrpt/rtti/CObject.cpp b/python/src/mrpt/rtti/CObject.cpp index 88b5fd2984..07bce49c62 100644 --- a/python/src/mrpt/rtti/CObject.cpp +++ b/python/src/mrpt/rtti/CObject.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #include #include @@ -69,15 +70,12 @@ void bind_mrpt_rtti_CObject(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::rtti::TRuntimeClassId file:mrpt/rtti/CObject.h line:32 + { // mrpt::rtti::TRuntimeClassId file:mrpt/rtti/CObject.h line:31 pybind11::class_> cl(M("mrpt::rtti"), "TRuntimeClassId", "A structure that holds runtime class type information. Use\n CLASS_ID() to get a reference to the class_name's TRuntimeClassId\n descriptor.\n \n\n\n "); cl.def( pybind11::init( [](){ return new mrpt::rtti::TRuntimeClassId(); } ) ); - cl.def( pybind11::init( [](mrpt::rtti::TRuntimeClassId const &o){ return new mrpt::rtti::TRuntimeClassId(o); } ) ); - cl.def_readwrite("ptrCreateObject", &mrpt::rtti::TRuntimeClassId::ptrCreateObject); cl.def("createObject", (class std::shared_ptr (mrpt::rtti::TRuntimeClassId::*)() const) &mrpt::rtti::TRuntimeClassId::createObject, "C++: mrpt::rtti::TRuntimeClassId::createObject() const --> class std::shared_ptr"); cl.def("derivedFrom", (bool (mrpt::rtti::TRuntimeClassId::*)(const struct mrpt::rtti::TRuntimeClassId *) const) &mrpt::rtti::TRuntimeClassId::derivedFrom, "C++: mrpt::rtti::TRuntimeClassId::derivedFrom(const struct mrpt::rtti::TRuntimeClassId *) const --> bool", pybind11::arg("pBaseClass")); cl.def("derivedFrom", (bool (mrpt::rtti::TRuntimeClassId::*)(const char *) const) &mrpt::rtti::TRuntimeClassId::derivedFrom, "C++: mrpt::rtti::TRuntimeClassId::derivedFrom(const char *) const --> bool", pybind11::arg("pBaseClass_name")); - cl.def("assign", (struct mrpt::rtti::TRuntimeClassId & (mrpt::rtti::TRuntimeClassId::*)(const struct mrpt::rtti::TRuntimeClassId &)) &mrpt::rtti::TRuntimeClassId::operator=, "C++: mrpt::rtti::TRuntimeClassId::operator=(const struct mrpt::rtti::TRuntimeClassId &) --> struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic, pybind11::arg("")); } // mrpt::rtti::registerClass(const struct mrpt::rtti::TRuntimeClassId *) file:mrpt/rtti/CObject.h line:51 M("mrpt::rtti").def("registerClass", (void (*)(const struct mrpt::rtti::TRuntimeClassId *)) &mrpt::rtti::registerClass, "Register a class into the MRPT internal list of \"CObject\" descendents.\n Used internally in the macros DEFINE_SERIALIZABLE, etc...\n \n\n getAllRegisteredClasses\n\nC++: mrpt::rtti::registerClass(const struct mrpt::rtti::TRuntimeClassId *) --> void", pybind11::arg("pNewClass")); @@ -179,4 +177,9 @@ void bind_mrpt_rtti_CObject(std::function< pybind11::module &(std::string const cl.def( pybind11::init( [](){ return new mrpt::rtti::CLASS_ID_impl(); } ) ); cl.def_static("get", (const struct mrpt::rtti::TRuntimeClassId * (*)()) &mrpt::rtti::CLASS_ID_impl::get, "C++: mrpt::rtti::CLASS_ID_impl::get() --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); } + { // mrpt::rtti::CLASS_ID_impl file:mrpt/rtti/CObject.h line:91 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::rtti"), "CLASS_ID_impl_mrpt_obs_CSensoryFrame_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::rtti::CLASS_ID_impl(); } ) ); + cl.def_static("get", (const struct mrpt::rtti::TRuntimeClassId * (*)()) &mrpt::rtti::CLASS_ID_impl::get, "C++: mrpt::rtti::CLASS_ID_impl::get() --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + } } diff --git a/python/src/mrpt/rtti/CObject_1.cpp b/python/src/mrpt/rtti/CObject_1.cpp index bc18ba1ec1..2216fb9301 100644 --- a/python/src/mrpt/rtti/CObject_1.cpp +++ b/python/src/mrpt/rtti/CObject_1.cpp @@ -11,7 +11,6 @@ #include #include #include -#include #include #include #include @@ -40,11 +39,6 @@ void bind_mrpt_rtti_CObject_1(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::rtti::CLASS_ID_impl file:mrpt/rtti/CObject.h line:91 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::rtti"), "CLASS_ID_impl_mrpt_obs_CSensoryFrame_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::rtti::CLASS_ID_impl(); } ) ); - cl.def_static("get", (const struct mrpt::rtti::TRuntimeClassId * (*)()) &mrpt::rtti::CLASS_ID_impl::get, "C++: mrpt::rtti::CLASS_ID_impl::get() --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); - } { // mrpt::rtti::CLASS_ID_impl file:mrpt/rtti/CObject.h line:91 pybind11::class_, std::shared_ptr>> cl(M("mrpt::rtti"), "CLASS_ID_impl_mrpt_maps_CLandmarksMap_t", ""); cl.def( pybind11::init( [](){ return new mrpt::rtti::CLASS_ID_impl(); } ) ); diff --git a/python/src/mrpt/serialization/CSerializable.cpp b/python/src/mrpt/serialization/CSerializable.cpp index f33e7a3223..75033ddd91 100644 --- a/python/src/mrpt/serialization/CSerializable.cpp +++ b/python/src/mrpt/serialization/CSerializable.cpp @@ -103,10 +103,10 @@ void bind_mrpt_serialization_CSerializable(std::function< pybind11::module &(std cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::serialization::CSerializable::GetRuntimeClassIdStatic, "C++: mrpt::serialization::CSerializable::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); cl.def("assign", (class mrpt::serialization::CSerializable & (mrpt::serialization::CSerializable::*)(const class mrpt::serialization::CSerializable &)) &mrpt::serialization::CSerializable::operator=, "C++: mrpt::serialization::CSerializable::operator=(const class mrpt::serialization::CSerializable &) --> class mrpt::serialization::CSerializable &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - // mrpt::serialization::ObjectToOctetVector(const class mrpt::serialization::CSerializable *, class std::vector &) file:mrpt/serialization/CSerializable.h line:103 + // mrpt::serialization::ObjectToOctetVector(const class mrpt::serialization::CSerializable *, class std::vector &) file:mrpt/serialization/CSerializable.h line:101 M("mrpt::serialization").def("ObjectToOctetVector", (void (*)(const class mrpt::serialization::CSerializable *, class std::vector &)) &mrpt::serialization::ObjectToOctetVector, "Converts (serializes) an MRPT object into an array of bytes.\n \n\n The object to be serialized.\n \n\n The vector which at return will contain the data. Size will\n be set automatically.\n \n\n OctetVectorToObject, ObjectToString\n\nC++: mrpt::serialization::ObjectToOctetVector(const class mrpt::serialization::CSerializable *, class std::vector &) --> void", pybind11::arg("o"), pybind11::arg("out_vector")); - // mrpt::serialization::OctetVectorToObject(const class std::vector &, class std::shared_ptr &) file:mrpt/serialization/CSerializable.h line:113 + // mrpt::serialization::OctetVectorToObject(const class std::vector &, class std::shared_ptr &) file:mrpt/serialization/CSerializable.h line:111 M("mrpt::serialization").def("OctetVectorToObject", (void (*)(const class std::vector &, class std::shared_ptr &)) &mrpt::serialization::OctetVectorToObject, "Converts back (de-serializes) a sequence of binary data into a MRPT object,\n without prior information about the object's class.\n \n\n The serialized input data representing the object.\n \n\n The newly created object will be stored in this smart pointer.\n \n\n None On any internal exception, this function returns a nullptr\n pointer.\n \n\n ObjectToOctetVector, StringToObject\n\nC++: mrpt::serialization::OctetVectorToObject(const class std::vector &, class std::shared_ptr &) --> void", pybind11::arg("in_data"), pybind11::arg("obj")); } diff --git a/python/src/unknown/unknown_5.cpp b/python/src/unknown/unknown_5.cpp index 7a9b984611..6f6cae03a6 100644 --- a/python/src/unknown/unknown_5.cpp +++ b/python/src/unknown/unknown_5.cpp @@ -114,7 +114,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME : public mrp } }; -// mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:78 +// mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:2 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS : public mrpt::obs::gnss::Message_NV_OEM6_BESTPOS { using mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::Message_NV_OEM6_BESTPOS; @@ -159,7 +159,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS : public mrpt::obs::gnss } }; -// mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:84 +// mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:8 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS : public mrpt::obs::gnss::Message_NV_OEM6_INSPVAS { using mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::Message_NV_OEM6_INSPVAS; @@ -204,7 +204,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS : public mrpt::obs::gnss } }; -// mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:90 +// mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:14 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS : public mrpt::obs::gnss::Message_NV_OEM6_INSCOVS { using mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::Message_NV_OEM6_INSCOVS; @@ -316,7 +316,7 @@ void bind_unknown_unknown_5(std::function< pybind11::module &(std::string const cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness() --> void"); cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME & (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &)) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:78 + { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:2 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_BESTPOS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(o); } ) ); @@ -356,7 +356,7 @@ void bind_unknown_unknown_5(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:84 + { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:8 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSPVAS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(o); } ) ); @@ -388,7 +388,7 @@ void bind_unknown_unknown_5(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:90 + { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:14 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSCOVS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(o); } ) ); diff --git a/python/src/unknown/unknown_6.cpp b/python/src/unknown/unknown_6.cpp index 5e8feaf5ed..9b5d5b6f0b 100644 --- a/python/src/unknown/unknown_6.cpp +++ b/python/src/unknown/unknown_6.cpp @@ -24,7 +24,7 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:96 +// mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:20 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS { using mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::Message_NV_OEM6_RXSTATUS; @@ -69,7 +69,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gns } }; -// mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:102 +// mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:26 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM { using mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::Message_NV_OEM6_RAWEPHEM; @@ -159,7 +159,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION : public mrpt::obs::gnss } }; -// mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:108 +// mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:32 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS { using mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::Message_NV_OEM6_RAWIMUS; @@ -204,7 +204,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss } }; -// mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:114 +// mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:38 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss::Message_NV_OEM6_MARKPOS { using mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::Message_NV_OEM6_MARKPOS; @@ -251,7 +251,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss void bind_unknown_unknown_6(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:96 + { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:20 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RXSTATUS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(o); } ) ); @@ -289,7 +289,7 @@ void bind_unknown_unknown_6(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:102 + { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:26 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWEPHEM", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(o); } ) ); @@ -332,7 +332,7 @@ void bind_unknown_unknown_6(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:108 + { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:32 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWIMUS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(o); } ) ); @@ -361,7 +361,7 @@ void bind_unknown_unknown_6(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:114 + { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:38 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKPOS", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(o); } ) ); diff --git a/python/src/unknown/unknown_7.cpp b/python/src/unknown/unknown_7.cpp index 8457faa794..2ad12ef86e 100644 --- a/python/src/unknown/unknown_7.cpp +++ b/python/src/unknown/unknown_7.cpp @@ -24,7 +24,7 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:120 +// mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:44 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME : public mrpt::obs::gnss::Message_NV_OEM6_MARKTIME { using mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::Message_NV_OEM6_MARKTIME; @@ -69,7 +69,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME : public mrpt::obs::gns } }; -// mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:126 +// mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:50 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME : public mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME { using mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::Message_NV_OEM6_MARK2TIME; @@ -114,7 +114,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME : public mrpt::obs::gn } }; -// mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:132 +// mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:56 struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC : public mrpt::obs::gnss::Message_NV_OEM6_IONUTC { using mrpt::obs::gnss::Message_NV_OEM6_IONUTC::Message_NV_OEM6_IONUTC; @@ -251,7 +251,7 @@ struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS : public mrpt::obs::gnss::Me void bind_unknown_unknown_7(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:120 + { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:44 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKTIME", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(o); } ) ); @@ -277,7 +277,7 @@ void bind_unknown_unknown_7(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:126 + { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:50 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARK2TIME", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(o); } ) ); @@ -303,7 +303,7 @@ void bind_unknown_unknown_7(std::function< pybind11::module &(std::string const } } - { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:132 + { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:56 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_IONUTC", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(o); } ) ); diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/img.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/img.pyi index 5a96f87418..3878a62268 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/img.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/img.pyi @@ -716,11 +716,11 @@ class TStereoCamera(mrpt.pymrpt.mrpt.serialization.CSerializable): rightCamera: TCamera rightCameraPose: mrpt.pymrpt.mrpt.math.TPose3DQuat @overload - def __init__(self, arg0: TStereoCamera) -> None: ... + def __init__(self) -> None: ... @overload def __init__(self, arg0: TStereoCamera) -> None: ... @overload - def __init__(self) -> None: ... + def __init__(self, arg0: TStereoCamera) -> None: ... def CreateObject(self, *args, **kwargs) -> Any: ... def GetRuntimeClass(self) -> mrpt.pymrpt.mrpt.rtti.TRuntimeClassId: ... def GetRuntimeClassIdStatic(self, *args, **kwargs) -> Any: ... diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/math.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/math.pyi index 36640898d7..ff43583a6e 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/math.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/math.pyi @@ -1251,10 +1251,7 @@ class CPolygon(mrpt.pymrpt.mrpt.serialization.CSerializable, TPolygon2D): def verticesCount() -> size_t: ... class CProbabilityDensityFunction_mrpt_poses_CPoint2D_2UL_t: - @overload def __init__(self) -> None: ... - @overload - def __init__(self, arg0: CProbabilityDensityFunction_mrpt_poses_CPoint2D_2UL_t) -> None: ... def assign(self) -> CProbabilityDensityFunction_mrpt_poses_CPoint2D_2UL_t: ... @overload def drawSingleSample(self, outPart) -> None: ... diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi index b793557213..5f092ee7bf 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/poses/__init__.pyi @@ -57,10 +57,7 @@ class CPoint2D(CPoint_mrpt_poses_CPoint2D_2UL_t, mrpt.pymrpt.mrpt.serialization. def __sub__(self, other) -> Any: ... class CPoint2DPDF(mrpt.pymrpt.mrpt.serialization.CSerializable, mrpt.pymrpt.mrpt.math.CProbabilityDensityFunction_mrpt_poses_CPoint2D_2UL_t): - @overload def __init__(self) -> None: ... - @overload - def __init__(self, arg0: CPoint2DPDF) -> None: ... def GetRuntimeClass(self) -> mrpt.pymrpt.mrpt.rtti.TRuntimeClassId: ... def GetRuntimeClassIdStatic(self, *args, **kwargs) -> Any: ... def assign(self) -> CPoint2DPDF: ... diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/rtti/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/rtti/__init__.pyi index 26e0cb8ef8..5f1722c0fe 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/rtti/__init__.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/rtti/__init__.pyi @@ -122,12 +122,7 @@ class CObject: def duplicateGetSmartPtr(self) -> CObject: ... class TRuntimeClassId: - ptrCreateObject: Any - @overload def __init__(self) -> None: ... - @overload - def __init__(self, arg0: TRuntimeClassId) -> None: ... - def assign(self) -> TRuntimeClassId: ... def createObject(self, *args, **kwargs) -> Any: ... @overload def derivedFrom(self, pBaseClass: TRuntimeClassId) -> bool: ... diff --git a/samples/rtti_example1/test.cpp b/samples/rtti_example1/test.cpp index a00132d0be..da73e486fc 100644 --- a/samples/rtti_example1/test.cpp +++ b/samples/rtti_example1/test.cpp @@ -29,7 +29,7 @@ class BarBase : public mrpt::rtti::CObject { public: BarBase() {} - DEFINE_VIRTUAL_MRPT_OBJECT(BarBase) + DEFINE_VIRTUAL_MRPT_OBJECT(BarBase, MyNS) virtual void printName() { std::cout << "printName: BarBase" << std::endl; } }; diff --git a/version_prefix.txt b/version_prefix.txt index 72dc324ab1..eb11d714d8 100644 --- a/version_prefix.txt +++ b/version_prefix.txt @@ -1,4 +1,4 @@ -2.13.8 +2.14.0 # 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