Skip to content

Commit

Permalink
Remove unused API function.
Browse files Browse the repository at this point in the history
Signed-off-by: schupf2 <[email protected]>
  • Loading branch information
schupf2 committed Dec 18, 2024
1 parent 92d1aab commit 6401f3c
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -56,10 +56,6 @@ class CostmapSubscriber
* @brief Get current costmap
*/
std::shared_ptr<Costmap2D> getCostmap();
/**
* @brief Get the timestamp of the last costmap update
*/
rclcpp::Time getTimestampLastCostmapUpdate();
/**
* @brief Callback for the costmap topic
*/
Expand Down
12 changes: 0 additions & 12 deletions nav2_costmap_2d/src/costmap_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,18 +68,6 @@ std::shared_ptr<Costmap2D> CostmapSubscriber::getCostmap()
return costmap_;
}

rclcpp::Time CostmapSubscriber::getTimestampLastCostmapUpdate()
{
if (!isCostmapReceived()) {
throw std::runtime_error("Costmap is not available");
}

std::lock_guard<std::mutex> lock(costmap_msg_mutex_);
auto stamp = costmap_msg_->header.stamp;

return stamp;
}

void CostmapSubscriber::costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg)
{
{
Expand Down

0 comments on commit 6401f3c

Please sign in to comment.