Skip to content

Commit e18fc30

Browse files
committed
Remove unused API function.
Signed-off-by: schupf2 <katrin.schupfer@knapp.com>
1 parent 5aeb921 commit e18fc30

File tree

2 files changed

+0
-16
lines changed

2 files changed

+0
-16
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -56,10 +56,6 @@ class CostmapSubscriber
5656
* @brief Get current costmap
5757
*/
5858
std::shared_ptr<Costmap2D> getCostmap();
59-
/**
60-
* @brief Get the timestamp of the last costmap update
61-
*/
62-
rclcpp::Time getTimestampLastCostmapUpdate();
6359
/**
6460
* @brief Callback for the costmap topic
6561
*/

nav2_costmap_2d/src/costmap_subscriber.cpp

Lines changed: 0 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -68,18 +68,6 @@ std::shared_ptr<Costmap2D> CostmapSubscriber::getCostmap()
6868
return costmap_;
6969
}
7070

71-
rclcpp::Time CostmapSubscriber::getTimestampLastCostmapUpdate()
72-
{
73-
if (!isCostmapReceived()) {
74-
throw std::runtime_error("Costmap is not available");
75-
}
76-
77-
std::lock_guard<std::mutex> lock(costmap_msg_mutex_);
78-
auto stamp = costmap_msg_->header.stamp;
79-
80-
return stamp;
81-
}
82-
8371
void CostmapSubscriber::costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg)
8472
{
8573
{

0 commit comments

Comments
 (0)