Skip to content

Commit 025fdb2

Browse files
authored
Merge branch 'develop' into dependabot/pip/doc/urllib3-2.5.0
2 parents 2d01c53 + b494563 commit 025fdb2

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

43 files changed

+849
-187
lines changed

appveyor.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
# version format
2-
version: 2.14.10-{branch}-build{build}
2+
version: 2.14.16-{branch}-build{build}
33

44
os: Visual Studio 2019
55

doc/source/doxygen-docs/changelog.md

Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,37 @@
11
\page changelog Change Log
22

3+
# Version 2.14.16: Released Oct 15th, 2025
4+
- Changes in libraries:
5+
- \ref mrpt_rtti_grp
6+
- More informative error message when calling clone() on a class without copy constructor.
7+
- BUG FIXES:
8+
- Fix build building deprecated warnings in WorkerThreadsPool.
9+
- Fix mrpt::opengl::CPointCloudColoured throwing if the source cloud map may have color and color/intensity channels are actually empty.
10+
11+
# Version 2.14.15: Released Sep 29th, 2025
12+
- BUG FIXES:
13+
- Fix regression in OpenGL application crashing after last update.
14+
15+
# Version 2.14.14: Released Sep 27th, 2025
16+
- BUG FIXES:
17+
- Fix missing backported fix to build mrpt::lockHelper() on modern gcc
18+
- Fix OpenGL crashes under specific build flags: OpenGL Buffers and VBO changed so they are initialized after constructor.
19+
20+
# Version 2.14.13: Released Sep 27th, 2025
21+
- Changes in libraries:
22+
- \ref mrpt_math_grp
23+
- New classes mrpt::math::TOrientedBox, mrpt::math::TOrientedBoxf
24+
- BUG FIXES:
25+
- Fix mrpt::opengl::CEllipsoid3D wrong direction.
26+
- Fix potential race conditions in TBB-parallel particle filters with 2D gridmap.
27+
- Harden opengl unit tests against crashes on non-GPU runners.
28+
- Fix build against ffmpeg 8.0 (Debian bug #1115064)
29+
30+
# Version 2.14.12: Released Aug 31rd, 2025
31+
- Changes in libraries:
32+
- \ref mrpt_opengl_grp
33+
- New method mrpt::opengl::CPointCloudColoured::setAllPointsAlpha().
34+
335
# Version 2.14.11: Released May 31rd, 2025
436
- BUG FIXES:
537
- Fix build against all tf2 versions in all active ROS 2 distributions.

libs/containers/include/mrpt/containers/NonCopiableData.h

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,20 @@ class NonCopiableData
3030

3131
T data;
3232

33+
NonCopiableData& operator=(const T& value)
34+
{
35+
data = value;
36+
return *this;
37+
}
38+
39+
NonCopiableData(T&& value) : data(std::move(value)) {}
40+
NonCopiableData(const T& value) : data(value) {}
41+
42+
T& operator*() { return data; }
43+
const T& operator*() const { return data; }
44+
T* operator->() { return &data; }
45+
const T* operator->() const { return &data; }
46+
3347
NonCopiableData(const NonCopiableData&) {}
3448
NonCopiableData& operator=(const NonCopiableData&) { return *this; }
3549

libs/core/include/mrpt/core/WorkerThreadsPool.h

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -82,11 +82,11 @@ class WorkerThreadsPool
8282
* available. */
8383
template <class F, class... Args>
8484
[[nodiscard]] auto enqueue(F&& f, Args&&... args)
85-
-> std::future<typename std::result_of<F(Args...)>::type>;
85+
-> std::future<std::invoke_result_t<F, Args...>>;
8686

8787
/** Returns the number of enqueued tasks, currently waiting for a free
8888
* working thread to process them. */
89-
std::size_t pendingTasks() const noexcept;
89+
[[nodiscard]] std::size_t pendingTasks() const noexcept;
9090

9191
/** Sets the private thread names of threads in this pool.
9292
* Names can be seen from debuggers, profilers, etc. and will follow
@@ -96,7 +96,7 @@ class WorkerThreadsPool
9696
void name(const std::string& name);
9797

9898
/** Returns the base name of threads in this pool */
99-
std::string name() const { return name_; }
99+
[[nodiscard]] std::string name() const { return name_; }
100100

101101
private:
102102
std::vector<std::thread> threads_;
@@ -110,16 +110,16 @@ class WorkerThreadsPool
110110

111111
template <class F, class... Args>
112112
auto WorkerThreadsPool::enqueue(F&& f, Args&&... args)
113-
-> std::future<typename std::result_of<F(Args...)>::type>
113+
-> std::future<std::invoke_result_t<F, Args...>>
114114
{
115-
using return_type = typename std::result_of<F(Args...)>::type;
115+
using return_type = std::invoke_result_t<F, Args...>;
116116

117117
auto task = std::make_shared<std::packaged_task<return_type()>>(
118118
std::bind(std::forward<F>(f), std::forward<Args>(args)...));
119119

120120
std::future<return_type> res = task->get_future();
121121
{
122-
std::unique_lock<std::mutex> lock(queue_mutex_);
122+
const std::unique_lock<std::mutex> lock(queue_mutex_);
123123

124124
// don't allow enqueueing after stopping the pool
125125
if (do_stop_) throw std::runtime_error("enqueue on stopped ThreadPool");

libs/core/include/mrpt/core/lock_helper.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -31,11 +31,11 @@ class LockHelper
3131
LockHelper(const LockHelper& o) = delete;
3232
LockHelper& operator=(const LockHelper& o) = delete;
3333

34-
LockHelper(LockHelper&& o) : l_{o.l} { o.l = nullptr; }
34+
LockHelper(LockHelper&& o) : l_{o.l_} { o.l_ = nullptr; }
3535
LockHelper& operator=(LockHelper&& o)
3636
{
37-
l_ = o.l;
38-
o.l = nullptr;
37+
l_ = o.l_;
38+
o.l_ = nullptr;
3939
return *this;
4040
}
4141

libs/hwdrivers/src/CFFMPEG_InputStream.cpp

Lines changed: 18 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -135,7 +135,7 @@ bool CFFMPEG_InputStream::openURL(
135135
if (avformat_open_input(&ctx->pFormatCtx, url.c_str(), nullptr, &options) != 0)
136136
{
137137
ctx->pFormatCtx = nullptr;
138-
std::cerr << "[CFFMPEG_InputStream::openURL] Cannot open video: " << url << std::endl;
138+
std::cerr << "[CFFMPEG_InputStream::openURL] Cannot open video: " << url << "\n";
139139
return false;
140140
}
141141

@@ -144,7 +144,7 @@ bool CFFMPEG_InputStream::openURL(
144144
{
145145
std::cerr << "[CFFMPEG_InputStream::openURL] Couldn't find stream "
146146
"information: "
147-
<< url << std::endl;
147+
<< url << "\n";
148148
return false;
149149
}
150150

@@ -171,7 +171,7 @@ bool CFFMPEG_InputStream::openURL(
171171
}
172172
if (ctx->videoStream == -1)
173173
{
174-
std::cerr << "[CFFMPEG_InputStream::openURL] Didn't find a video stream: " << url << std::endl;
174+
std::cerr << "[CFFMPEG_InputStream::openURL] Didn't find a video stream: " << url << "\n";
175175
return false;
176176
}
177177

@@ -187,7 +187,7 @@ bool CFFMPEG_InputStream::openURL(
187187
#endif
188188
if (codec == nullptr)
189189
{
190-
std::cerr << "[CFFMPEG_InputStream::openURL] Codec not found: " << url << std::endl;
190+
std::cerr << "[CFFMPEG_InputStream::openURL] Codec not found: " << url << "\n";
191191
return false;
192192
}
193193

@@ -197,7 +197,7 @@ bool CFFMPEG_InputStream::openURL(
197197
{
198198
std::cerr << "[CFFMPEG_InputStream::openURL] Cannot alloc avcodec "
199199
"context for: "
200-
<< url << std::endl;
200+
<< url << "\n";
201201
return false;
202202
}
203203

@@ -207,7 +207,7 @@ bool CFFMPEG_InputStream::openURL(
207207
{
208208
std::cerr << "[CFFMPEG_InputStream::openURL] Failed "
209209
"avcodec_parameters_to_context() for: "
210-
<< url << std::endl;
210+
<< url << "\n";
211211
return false;
212212
}
213213

@@ -218,7 +218,7 @@ bool CFFMPEG_InputStream::openURL(
218218
// Open codec
219219
if (avcodec_open2(ctx->pCodecCtx, codec, nullptr) < 0)
220220
{
221-
std::cerr << "[CFFMPEG_InputStream::openURL] avcodec_open2() failed for: " << url << std::endl;
221+
std::cerr << "[CFFMPEG_InputStream::openURL] avcodec_open2() failed for: " << url << "\n";
222222
return false;
223223
}
224224

@@ -231,7 +231,7 @@ bool CFFMPEG_InputStream::openURL(
231231
{
232232
std::cerr << "[CFFMPEG_InputStream::openURL] Could not alloc memory "
233233
"for frame buffers: "
234-
<< url << std::endl;
234+
<< url << "\n";
235235
return false;
236236
}
237237

@@ -247,7 +247,7 @@ bool CFFMPEG_InputStream::openURL(
247247
{
248248
std::cerr << "[CFFMPEG_InputStream::openURL] av_image_get_buffer_size "
249249
"error code: "
250-
<< numBytes << std::endl;
250+
<< numBytes << "\n";
251251
return false;
252252
}
253253

@@ -278,8 +278,7 @@ void CFFMPEG_InputStream::close()
278278
// Close the codec
279279
if (ctx->pCodecCtx)
280280
{
281-
avcodec_close(ctx->pCodecCtx);
282-
ctx->pCodecCtx = nullptr;
281+
avcodec_free_context(&ctx->pCodecCtx);
283282
}
284283

285284
// Close the video file
@@ -356,9 +355,9 @@ bool CFFMPEG_InputStream::retrieveFrame(mrpt::img::CImage& out_img, int64_t& out
356355
int ret = avcodec_send_packet(ctx->pCodecCtx, &packet);
357356
if (ret < 0)
358357
{
359-
std::cerr << std::endl
360-
<< "[CFFMPEG_InputStream] avcodec_send_packet error code=" << ret << std::endl
361-
<< std::endl;
358+
std::cerr << "\n"
359+
<< "[CFFMPEG_InputStream] avcodec_send_packet error code=" << ret << "\n"
360+
<< "\n";
362361
return false;
363362
}
364363
while (ret >= 0)
@@ -370,11 +369,11 @@ bool CFFMPEG_InputStream::retrieveFrame(mrpt::img::CImage& out_img, int64_t& out
370369
return false;
371370
else if (ret < 0)
372371
{
373-
std::cerr << std::endl
372+
std::cerr << "\n"
374373
<< "[CFFMPEG_InputStream] avcodec_receive_frame "
375374
"error code="
376-
<< ret << std::endl
377-
<< std::endl;
375+
<< ret << "\n"
376+
<< "\n";
378377
return false;
379378
}
380379

@@ -401,8 +400,8 @@ bool CFFMPEG_InputStream::retrieveFrame(mrpt::img::CImage& out_img, int64_t& out
401400

402401
// std::cout << "[retrieveFrame] Generating image: " <<
403402
// ctx->pCodecPars->width << "x" << ctx->pCodecPars->height
404-
// << std::endl; std::cout << " linsize: " <<
405-
// ctx->pFrameRGB->linesize[0] << std::endl;
403+
// << "\n"; std::cout << " linsize: " <<
404+
// ctx->pFrameRGB->linesize[0] << "\n";
406405

407406
if (ctx->pFrameRGB->linesize[0] != ((m_grab_as_grayscale ? 1 : 3) * width))
408407
THROW_EXCEPTION("FIXME: linesize!=width case not handled yet.");

libs/maps/include/mrpt/maps/COccupancyGridMap2D.h

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010

1111
#include <mrpt/config/CLoadableOptions.h>
1212
#include <mrpt/containers/CDynamicGrid.h>
13+
#include <mrpt/containers/NonCopiableData.h>
1314
#include <mrpt/core/safe_pointers.h>
1415
#include <mrpt/img/CImage.h>
1516
#include <mrpt/maps/CLogOddsGridMap2D.h>
@@ -25,6 +26,9 @@
2526
#include <mrpt/tfest/TMatchingPair.h>
2627
#include <mrpt/typemeta/TEnumType.h>
2728

29+
#include <atomic>
30+
#include <mutex>
31+
2832
namespace mrpt::maps
2933
{
3034
/** A class for storing an occupancy grid map.
@@ -92,8 +96,10 @@ class COccupancyGridMap2D :
9296
/** Auxiliary variables to speed up the computation of observation
9397
* likelihood values for LF method among others, at a high cost in memory
9498
* (see TLikelihoodOptions::enableLikelihoodCache). */
95-
mutable std::vector<double> m_precomputedLikelihood;
99+
mutable mrpt::containers::NonCopiableData<std::vector<std::atomic<double>>>
100+
m_precomputedLikelihood;
96101
mutable bool m_likelihoodCacheOutDated{true};
102+
mutable mrpt::containers::NonCopiableData<std::mutex> m_precomputedLikelihood_mtx;
97103

98104
/** Used for Voronoi calculation.Same struct as "map", but contains a "0" if
99105
* not a basis point. */

libs/maps/include/mrpt/maps/CPointsMapXYZI.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -163,8 +163,10 @@ class CPointsMapXYZI : public CPointsMap
163163
/** Like \c getPointColor but without checking for out-of-index errors */
164164
inline float getPointIntensity_fast(size_t index) const { return m_intensity[index]; }
165165

166+
bool hasIntensityField() const { return !m_intensity.empty(); }
167+
166168
/** Returns true if the point map has a color field for each point */
167-
bool hasColorPoints() const override { return true; }
169+
bool hasColorPoints() const override { return hasIntensityField(); }
168170

169171
/** Override of the default 3D scene builder to account for the individual
170172
* points' color.

libs/maps/include/mrpt/maps/CPointsMapXYZIRT.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -224,7 +224,7 @@ class CPointsMapXYZIRT : public CPointsMap
224224
inline float getPointIntensity_fast(size_t index) const { return m_intensity[index]; }
225225

226226
/** Returns true if the point map has a color field for each point */
227-
bool hasColorPoints() const override { return true; }
227+
bool hasColorPoints() const override { return hasIntensityField(); }
228228

229229
/** Override of the default 3D scene builder to account for the individual
230230
* points' color.

libs/maps/src/maps/CColouredOctoMap.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,7 @@ void CColouredOctoMap::serializeTo(mrpt::serialization::CArchive& out) const
9090
out << genericMapParams; // v2
9191

9292
// v2->v3: remove CMemoryChunk
93-
std::stringstream ss;
93+
std::stringstream ss(std::ios::in | std::ios::out | std::ios::binary);
9494
m_impl->m_octomap.writeBinaryConst(ss);
9595
const std::string& buf = ss.str();
9696
out << buf;
@@ -122,7 +122,7 @@ void CColouredOctoMap::serializeFrom(mrpt::serialization::CArchive& in, uint8_t
122122

123123
if (!buf.empty())
124124
{
125-
std::stringstream ss;
125+
std::stringstream ss(std::ios::in | std::ios::out | std::ios::binary);
126126
ss.str(buf);
127127
ss.seekg(0);
128128
m_impl->m_octomap.readBinary(ss);

0 commit comments

Comments
 (0)