Skip to content

Commit 2f869c0

Browse files
authored
fix issue (#180) that localization mode may terminate unexpectedly with exception about pthread_mutex_lock (#388)
* fix issue (#180) that localization mode may terminate unexpectedly with exception about pthread_mutex_lock * set c++17 standard for the whole project, use from_second insteads of incorrect from_nanoseconds
1 parent 749a3b1 commit 2f869c0

File tree

4 files changed

+13
-12
lines changed

4 files changed

+13
-12
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ project(slam_toolbox)
33

44
set(CMAKE_BUILD_TYPE Release) #None, Debug, Release, RelWithDebInfo, MinSizeRel
55
if(NOT CMAKE_CXX_STANDARD)
6-
set(CMAKE_CXX_STANDARD 14)
6+
set(CMAKE_CXX_STANDARD 17)
77
endif()
88
cmake_policy(SET CMP0077 NEW)
99

include/slam_toolbox/visualization_utils.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ inline visualization_msgs::msg::Marker toMarker(
5050
marker.color.b = 0.0;
5151
marker.color.a = 1.;
5252
marker.action = visualization_msgs::msg::Marker::ADD;
53-
marker.lifetime = rclcpp::Duration::from_nanoseconds(0);
53+
marker.lifetime = rclcpp::Duration::from_seconds(0);
5454

5555
return marker;
5656
}

lib/karto_sdk/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5)
22
project(karto_sdk)
33

44
if(NOT CMAKE_CXX_STANDARD)
5-
set(CMAKE_CXX_STANDARD 14)
5+
set(CMAKE_CXX_STANDARD 17)
66
endif()
77
set(CMAKE_BUILD_TYPE Release) #None, Debug, Release, RelWithDebInfo, MinSizeRel
88
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -ftemplate-backtrace-limit=0")

lib/karto_sdk/include/karto_sdk/Karto.h

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@
4949
#include <iomanip>
5050
#include <sstream>
5151
#include <stdexcept>
52+
#include <shared_mutex>
5253

5354
#ifdef USE_POCO
5455
#include <Poco/Mutex.h>
@@ -5434,7 +5435,7 @@ class LocalizedRangeScan : public LaserRangeScan
54345435
}
54355436

54365437
private:
5437-
mutable boost::shared_mutex m_Lock;
5438+
mutable std::shared_mutex m_Lock;
54385439

54395440
public:
54405441
/**
@@ -5495,11 +5496,11 @@ class LocalizedRangeScan : public LaserRangeScan
54955496
*/
54965497
inline const Pose2 & GetBarycenterPose() const
54975498
{
5498-
boost::shared_lock<boost::shared_mutex> lock(m_Lock);
5499+
std::shared_lock<std::shared_mutex> lock(m_Lock);
54995500
if (m_IsDirty) {
55005501
// throw away constness and do an update!
55015502
lock.unlock();
5502-
boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
5503+
std::unique_lock<std::shared_mutex> uniqueLock(m_Lock);
55035504
const_cast<LocalizedRangeScan *>(this)->Update();
55045505
}
55055506

@@ -5518,11 +5519,11 @@ class LocalizedRangeScan : public LaserRangeScan
55185519
*/
55195520
inline Pose2 GetReferencePose(kt_bool useBarycenter) const
55205521
{
5521-
boost::shared_lock<boost::shared_mutex> lock(m_Lock);
5522+
std::shared_lock<std::shared_mutex> lock(m_Lock);
55225523
if (m_IsDirty) {
55235524
// throw away constness and do an update!
55245525
lock.unlock();
5525-
boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
5526+
std::unique_lock<std::shared_mutex> uniqueLock(m_Lock);
55265527
const_cast<LocalizedRangeScan *>(this)->Update();
55275528
}
55285529

@@ -5589,11 +5590,11 @@ class LocalizedRangeScan : public LaserRangeScan
55895590
*/
55905591
inline const BoundingBox2 & GetBoundingBox() const
55915592
{
5592-
boost::shared_lock<boost::shared_mutex> lock(m_Lock);
5593+
std::shared_lock<std::shared_mutex> lock(m_Lock);
55935594
if (m_IsDirty) {
55945595
// throw away constness and do an update!
55955596
lock.unlock();
5596-
boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
5597+
std::unique_lock<std::shared_mutex> uniqueLock(m_Lock);
55975598
const_cast<LocalizedRangeScan *>(this)->Update();
55985599
}
55995600

@@ -5610,11 +5611,11 @@ class LocalizedRangeScan : public LaserRangeScan
56105611
*/
56115612
inline const PointVectorDouble & GetPointReadings(kt_bool wantFiltered = false) const
56125613
{
5613-
boost::shared_lock<boost::shared_mutex> lock(m_Lock);
5614+
std::shared_lock<std::shared_mutex> lock(m_Lock);
56145615
if (m_IsDirty) {
56155616
// throw away constness and do an update!
56165617
lock.unlock();
5617-
boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
5618+
std::unique_lock<std::shared_mutex> uniqueLock(m_Lock);
56185619
const_cast<LocalizedRangeScan *>(this)->Update();
56195620
}
56205621

0 commit comments

Comments
 (0)