diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp index e252d9c889d..4f50614876c 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp @@ -56,10 +56,6 @@ class CostmapSubscriber * @brief Get current costmap */ std::shared_ptr getCostmap(); - /** - * @brief Get the timestamp of the last costmap update - */ - rclcpp::Time getTimestampLastCostmapUpdate(); /** * @brief Callback for the costmap topic */ diff --git a/nav2_costmap_2d/src/costmap_subscriber.cpp b/nav2_costmap_2d/src/costmap_subscriber.cpp index f401b1eec43..0426b87be30 100644 --- a/nav2_costmap_2d/src/costmap_subscriber.cpp +++ b/nav2_costmap_2d/src/costmap_subscriber.cpp @@ -68,18 +68,6 @@ std::shared_ptr CostmapSubscriber::getCostmap() return costmap_; } -rclcpp::Time CostmapSubscriber::getTimestampLastCostmapUpdate() -{ - if (!isCostmapReceived()) { - throw std::runtime_error("Costmap is not available"); - } - - std::lock_guard lock(costmap_msg_mutex_); - auto stamp = costmap_msg_->header.stamp; - - return stamp; -} - void CostmapSubscriber::costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg) { {