Skip to content

Commit

Permalink
Merge branch 'develop'
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Sep 15, 2024
2 parents 5ef2732 + e293995 commit 15e0be4
Show file tree
Hide file tree
Showing 53 changed files with 197 additions and 142 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
2 changes: 0 additions & 2 deletions apps/ro-localization/CPosePDFParticlesExtended.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion appveyor.yml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# version format
version: 2.13.8-{branch}-build{build}
version: 2.14.0-{branch}-build{build}

os: Visual Studio 2019

Expand Down
1 change: 1 addition & 0 deletions cmakemodules/script_show_final_summary.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -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 "")
Expand Down
16 changes: 16 additions & 0 deletions cmakemodules/script_tbb.cmake
Original file line number Diff line number Diff line change
@@ -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()
13 changes: 13 additions & 0 deletions doc/source/doxygen-docs/changelog.md
Original file line number Diff line number Diff line change
@@ -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:
Expand Down
2 changes: 1 addition & 1 deletion libs/kinematics/include/mrpt/kinematics/CVehicleVelCmd.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion libs/maps/include/mrpt/maps/CPointsMap.h
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
2 changes: 1 addition & 1 deletion libs/maps/include/mrpt/maps/CRandomFieldGridMap2D.h
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ class CRandomFieldGridMap2D :
{
using BASE = mrpt::containers::CDynamicGrid<TRandomFieldCell>;

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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
4 changes: 3 additions & 1 deletion libs/nav/src/tpspace/CPTG_DiffDrive_CollisionGridBased.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@

#include "nav-precomp.h" // Precomp header
//
#include <mrpt/core/WorkerThreadsPool.h>
#include <mrpt/core/get_env.h>
#include <mrpt/io/CFileGZInputStream.h>
#include <mrpt/io/CFileGZOutputStream.h>
#include <mrpt/kinematics/CVehicleVelCmd_DiffDriven.h>
Expand Down Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion libs/obs/include/mrpt/maps/CMetricMap.h
Original file line number Diff line number Diff line change
Expand Up @@ -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() */
Expand Down
2 changes: 1 addition & 1 deletion libs/obs/include/mrpt/obs/CAction.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion libs/obs/include/mrpt/obs/CObservation.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
8 changes: 8 additions & 0 deletions libs/obs/include/mrpt/obs/CObservation2DRangeScan.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,14 +8,18 @@
+------------------------------------------------------------------------+ */
#pragma once

#include <mrpt/containers/NonCopiableData.h>
#include <mrpt/core/aligned_std_vector.h>
#include <mrpt/core/lock_helper.h>
#include <mrpt/maps/CMetricMap.h>
#include <mrpt/math/CPolygon.h>
#include <mrpt/obs/CObservation.h>
#include <mrpt/obs/T2DScanProperties.h>
#include <mrpt/poses/CPose3D.h>
#include <mrpt/serialization/CSerializable.h>

#include <mutex>

// Add for declaration of mexplus::from template specialization
DECLARE_MEXPLUS_FROM(mrpt::obs::CObservation2DRangeScan)

Expand Down Expand Up @@ -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<std::recursive_mutex> m_cachedMapMtx;
mutable mrpt::maps::CMetricMap::Ptr m_cachedMap;
/** Internal method, used from buildAuxPointsMap() */
void internal_buildAuxPointsMap(const void* options = nullptr) const;
Expand All @@ -183,6 +188,7 @@ class CObservation2DRangeScan : public CObservation
template <class POINTSMAP>
inline const POINTSMAP* getAuxPointsMap() const
{
auto lck = mrpt::lockHelper(m_cachedMapMtx.data);
return static_cast<const POINTSMAP*>(m_cachedMap.get());
}

Expand All @@ -201,6 +207,8 @@ class CObservation2DRangeScan : public CObservation
template <class POINTSMAP>
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<const POINTSMAP*>(m_cachedMap.get());
}
Expand Down
3 changes: 3 additions & 0 deletions libs/obs/src/CObservation2DRangeScan.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}

Expand Down Expand Up @@ -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 "
Expand Down
4 changes: 2 additions & 2 deletions libs/opengl/include/mrpt/opengl/CPointCloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -195,12 +195,12 @@ class CPointCloud :

void insertPoint(const mrpt::math::TPoint3Df& p)
{
std::unique_lock<std::shared_mutex> 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<std::shared_mutex> wfWriteLock(CRenderizableShaderPoints::m_pointsMtx.data);
// lock already hold by insertPoint() below
insertPoint(p.x, p.y, p.z);
}

Expand Down
2 changes: 1 addition & 1 deletion libs/opengl/include/mrpt/opengl/CRenderizable.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion libs/opengl/include/mrpt/opengl/CRenderizableShaderText.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion libs/poses/include/mrpt/poses/CPoint2DPDF.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class CPoint2DPDF :
public mrpt::serialization::CSerializable,
public mrpt::math::CProbabilityDensityFunction<CPoint2D, 2>
{
DEFINE_VIRTUAL_SERIALIZABLE(CPoint2DPDF)
DEFINE_VIRTUAL_SERIALIZABLE(CPoint2DPDF, mrpt::poses)

public:
/** Copy operator, translating if necessary (for example, between particles
Expand Down
2 changes: 1 addition & 1 deletion libs/poses/include/mrpt/poses/CPointPDF.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ class CPointPDF :
public mrpt::serialization::CSerializable,
public mrpt::math::CProbabilityDensityFunction<CPoint3D, 3>
{
DEFINE_VIRTUAL_SERIALIZABLE(CPointPDF)
DEFINE_VIRTUAL_SERIALIZABLE(CPointPDF, mrpt::poses)

public:
/** Copy operator, translating if necessary (for example, between particles
Expand Down
2 changes: 1 addition & 1 deletion libs/poses/include/mrpt/poses/CPose3DPDF.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class CPose3DPDF :
public mrpt::serialization::CSerializable,
public mrpt::math::CProbabilityDensityFunction<CPose3D, 6>
{
DEFINE_VIRTUAL_SERIALIZABLE(CPose3DPDF)
DEFINE_VIRTUAL_SERIALIZABLE(CPose3DPDF, mrpt::poses)

public:
/** Copy operator, translating if necessary (for example, between particles
Expand Down
2 changes: 1 addition & 1 deletion libs/poses/include/mrpt/poses/CPose3DQuatPDF.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class CPose3DQuatPDF :
public mrpt::serialization::CSerializable,
public mrpt::math::CProbabilityDensityFunction<CPose3DQuat, 7>
{
DEFINE_VIRTUAL_SERIALIZABLE(CPose3DQuatPDF)
DEFINE_VIRTUAL_SERIALIZABLE(CPose3DQuatPDF, mrpt::poses)

public:
/** Copy operator, translating if necessary (for example, between particles
Expand Down
2 changes: 1 addition & 1 deletion libs/poses/include/mrpt/poses/CPosePDF.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class CPosePDF :
public mrpt::serialization::CSerializable,
public mrpt::math::CProbabilityDensityFunction<CPose2D, 3>
{
DEFINE_VIRTUAL_SERIALIZABLE(CPosePDF)
DEFINE_VIRTUAL_SERIALIZABLE(CPosePDF, mrpt::poses)

public:
/** Copy operator, translating if necessary (for example, between particles
Expand Down
Loading

0 comments on commit 15e0be4

Please sign in to comment.