1+ diff --git a/CMakeLists.txt b/CMakeLists.txt
2+ index f7f476296..0725a05d5 100644
3+ --- a/CMakeLists.txt
4+ +++ b/CMakeLists.txt
5+ @@ -50,6 +50,16 @@ find_package(urdf REQUIRED)
6+ find_package(urdfdom_headers REQUIRED)
7+ find_package(visualization_msgs REQUIRED)
8+
9+ +
10+ + # glog is not linked, however we look for it to detect the glog version
11+ + # and use a different code path if glog >= 0.7.0 is detected
12+ + find_package(glog CONFIG QUIET)
13+ + if(DEFINED glog_VERSION)
14+ + if(NOT glog_VERSION VERSION_LESS 0.7.0)
15+ + add_definitions(-DROS_CARTOGRAPHER_GLOG_GE_070)
16+ + endif()
17+ + endif()
18+ +
19+ include_directories(
20+ include
21+ ${PCL_INCLUDE_DIRS}
22+ diff --git a/src/ros_log_sink.cpp b/src/ros_log_sink.cpp
23+ index 1396381d4..9e189c690 100644
24+ --- a/src/ros_log_sink.cpp
25+ +++ b/src/ros_log_sink.cpp
26+ @@ -33,6 +33,11 @@ const char* GetBasename(const char* filepath) {
27+ return base ? (base + 1) : filepath;
28+ }
29+
30+ + std::chrono::system_clock::time_point ConvertTmToTimePoint(const std::tm& tm) {
31+ + std::time_t timeT = std::mktime(const_cast<std::tm*>(&tm)); // Convert std::tm to time_t
32+ + return std::chrono::system_clock::from_time_t(timeT); // Convert time_t to time_point
33+ + }
34+ +
35+ } // namespace
36+
37+ ScopedRosLogSink::ScopedRosLogSink() : will_die_(false) { AddLogSink(this); }
38+ @@ -46,10 +51,13 @@ void ScopedRosLogSink::send(const ::google::LogSeverity severity,
39+ const size_t message_len) {
40+ (void) base_filename; // TODO: remove unused arg ?
41+
42+ + #if defined(ROS_CARTOGRAPHER_GLOG_GE_070)
43+ + const std::string message_string = ::google::LogSink::ToString(
44+ + severity, GetBasename(filename), line, ::google::LogMessageTime(ConvertTmToTimePoint(*tm_time)), message, message_len);
45+ // Google glog broke the ToString API, but has no way to tell what version it is using.
46+ // To support both newer and older glog versions, use a nasty hack were we infer the
47+ // version based on whether GOOGLE_GLOG_DLL_DECL is defined
48+ - #if defined(GOOGLE_GLOG_DLL_DECL)
49+ + #elif defined(GOOGLE_GLOG_DLL_DECL)
50+ const std::string message_string = ::google::LogSink::ToString(
51+ severity, GetBasename(filename), line, tm_time, message, message_len);
52+ #else
53+
154diff --git a/include/cartographer_ros/map_builder_bridge.h b/include/cartographer_ros/map_builder_bridge.h
2- index b2c00b7..bd91894 100644
55+ index b2c00b7..9c1befd 100644
356--- a/include/cartographer_ros/map_builder_bridge.h
457+++ b/include/cartographer_ros/map_builder_bridge.h
5- @@ -113,7 +113,7 @@ class MapBuilderBridge {
58+ @@ -95,7 +95,7 @@ class MapBuilderBridge {
59+ GetTrajectoryStates();
60+ cartographer_ros_msgs::msg::SubmapList GetSubmapList(rclcpp::Time node_time);
61+ std::unordered_map<int, LocalTrajectoryData> GetLocalTrajectoryData()
62+ - LOCKS_EXCLUDED(mutex_);
63+ + ABSL_LOCKS_EXCLUDED(mutex_);
64+ visualization_msgs::msg::MarkerArray GetTrajectoryNodeList(rclcpp::Time node_time);
65+ visualization_msgs::msg::MarkerArray GetLandmarkPosesList(rclcpp::Time node_time);
66+ visualization_msgs::msg::MarkerArray GetConstraintList(rclcpp::Time node_time);
67+ @@ -107,13 +107,13 @@ class MapBuilderBridge {
68+ const ::cartographer::common::Time time,
69+ const ::cartographer::transform::Rigid3d local_pose,
70+ ::cartographer::sensor::RangeData range_data_in_local)
71+ - LOCKS_EXCLUDED(mutex_);
72+ + ABSL_LOCKS_EXCLUDED(mutex_);
73+
74+ absl::Mutex mutex_;
675 const NodeOptions node_options_;
776 std::unordered_map<int,
877 std::shared_ptr<const LocalTrajectoryData::LocalSlamData>>
@@ -62,10 +131,10 @@ index f3527ca..f9fb9fb 100644
62131 rclcpp::Node::SharedPtr node_;
63132 ::rclcpp::Publisher<::cartographer_ros_msgs::msg::SubmapList>::SharedPtr submap_list_publisher_;
64133diff --git a/src/occupancy_grid_node_main.cpp b/src/occupancy_grid_node_main.cpp
65- index 282b890..6139979 100644
134+ index 324426b..443dac2 100644
66135--- a/src/occupancy_grid_node_main.cpp
67136+++ b/src/occupancy_grid_node_main.cpp
68- @@ -74 ,10 +74 ,10 @@ class Node : public rclcpp::Node
137+ @@ -73 ,10 +73 ,10 @@ class Node : public rclcpp::Node
69138 absl::Mutex mutex_;
70139 rclcpp::CallbackGroup::SharedPtr callback_group_;
71140 rclcpp::executors::SingleThreadedExecutor::SharedPtr callback_group_executor_;
@@ -80,3 +149,4 @@ index 282b890..6139979 100644
80149 rclcpp::TimerBase::SharedPtr occupancy_grid_publisher_timer_;
81150 std::string last_frame_id_;
82151 rclcpp::Time last_timestamp_;
152+
0 commit comments