Skip to content

Commit

Permalink
fix issue (#180) that localization mode may terminate unexpectedly wi…
Browse files Browse the repository at this point in the history
…th 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
  • Loading branch information
WLwind authored Apr 28, 2021
1 parent 749a3b1 commit 2f869c0
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 12 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ project(slam_toolbox)

set(CMAKE_BUILD_TYPE Release) #None, Debug, Release, RelWithDebInfo, MinSizeRel
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD 17)
endif()
cmake_policy(SET CMP0077 NEW)

Expand Down
2 changes: 1 addition & 1 deletion include/slam_toolbox/visualization_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ inline visualization_msgs::msg::Marker toMarker(
marker.color.b = 0.0;
marker.color.a = 1.;
marker.action = visualization_msgs::msg::Marker::ADD;
marker.lifetime = rclcpp::Duration::from_nanoseconds(0);
marker.lifetime = rclcpp::Duration::from_seconds(0);

return marker;
}
Expand Down
2 changes: 1 addition & 1 deletion lib/karto_sdk/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5)
project(karto_sdk)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD 17)
endif()
set(CMAKE_BUILD_TYPE Release) #None, Debug, Release, RelWithDebInfo, MinSizeRel
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -ftemplate-backtrace-limit=0")
Expand Down
19 changes: 10 additions & 9 deletions lib/karto_sdk/include/karto_sdk/Karto.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@
#include <iomanip>
#include <sstream>
#include <stdexcept>
#include <shared_mutex>

#ifdef USE_POCO
#include <Poco/Mutex.h>
Expand Down Expand Up @@ -5434,7 +5435,7 @@ class LocalizedRangeScan : public LaserRangeScan
}

private:
mutable boost::shared_mutex m_Lock;
mutable std::shared_mutex m_Lock;

public:
/**
Expand Down Expand Up @@ -5495,11 +5496,11 @@ class LocalizedRangeScan : public LaserRangeScan
*/
inline const Pose2 & GetBarycenterPose() const
{
boost::shared_lock<boost::shared_mutex> lock(m_Lock);
std::shared_lock<std::shared_mutex> lock(m_Lock);
if (m_IsDirty) {
// throw away constness and do an update!
lock.unlock();
boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
std::unique_lock<std::shared_mutex> uniqueLock(m_Lock);
const_cast<LocalizedRangeScan *>(this)->Update();
}

Expand All @@ -5518,11 +5519,11 @@ class LocalizedRangeScan : public LaserRangeScan
*/
inline Pose2 GetReferencePose(kt_bool useBarycenter) const
{
boost::shared_lock<boost::shared_mutex> lock(m_Lock);
std::shared_lock<std::shared_mutex> lock(m_Lock);
if (m_IsDirty) {
// throw away constness and do an update!
lock.unlock();
boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
std::unique_lock<std::shared_mutex> uniqueLock(m_Lock);
const_cast<LocalizedRangeScan *>(this)->Update();
}

Expand Down Expand Up @@ -5589,11 +5590,11 @@ class LocalizedRangeScan : public LaserRangeScan
*/
inline const BoundingBox2 & GetBoundingBox() const
{
boost::shared_lock<boost::shared_mutex> lock(m_Lock);
std::shared_lock<std::shared_mutex> lock(m_Lock);
if (m_IsDirty) {
// throw away constness and do an update!
lock.unlock();
boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
std::unique_lock<std::shared_mutex> uniqueLock(m_Lock);
const_cast<LocalizedRangeScan *>(this)->Update();
}

Expand All @@ -5610,11 +5611,11 @@ class LocalizedRangeScan : public LaserRangeScan
*/
inline const PointVectorDouble & GetPointReadings(kt_bool wantFiltered = false) const
{
boost::shared_lock<boost::shared_mutex> lock(m_Lock);
std::shared_lock<std::shared_mutex> lock(m_Lock);
if (m_IsDirty) {
// throw away constness and do an update!
lock.unlock();
boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
std::unique_lock<std::shared_mutex> uniqueLock(m_Lock);
const_cast<LocalizedRangeScan *>(this)->Update();
}

Expand Down

0 comments on commit 2f869c0

Please sign in to comment.