From e76cbed9248e3f71072af5a8212a979e439ac9a2 Mon Sep 17 00:00:00 2001 From: matlabbe Date: Tue, 8 Oct 2024 20:03:14 -0700 Subject: [PATCH] Fixed build with RTAB-Map 0.21.8 (and grid_map_core dep) --- rtabmap_util/src/MapsManager.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/rtabmap_util/src/MapsManager.cpp b/rtabmap_util/src/MapsManager.cpp index 414906f75..be51792a5 100644 --- a/rtabmap_util/src/MapsManager.cpp +++ b/rtabmap_util/src/MapsManager.cpp @@ -1362,7 +1362,11 @@ void MapsManager::publishMaps( (elevationMapPub_->get_subscription_count() && !latched_.at(&elevationMapPub_))) { grid_map_msgs::msg::GridMap::UniquePtr msg; +#if RTABMAP_VERSION_MAJOR>0 || (RTABMAP_VERSION_MAJOR==0 && RTABMAP_VERSION_MINOR>21) || (RTABMAP_VERSION_MAJOR==0 && RTABMAP_VERSION_MINOR==21 && RTABMAP_VERSION_MINOR>=8) + msg = grid_map::GridMapRosConverter::toMessage(*elevationMap_->gridMap()); +#else msg = grid_map::GridMapRosConverter::toMessage(elevationMap_->gridMap()); +#endif msg->header.frame_id = mapFrameId; msg->header.stamp = stamp; elevationMapPub_->publish(std::move(msg));