Skip to content

Commit

Permalink
fix building
Browse files Browse the repository at this point in the history
Signed-off-by: Tony Najjar <[email protected]>
  • Loading branch information
tonynajjar committed Sep 16, 2024
1 parent d30a05c commit 2260a7b
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions nav2_rviz_plugins/src/costmap_cost_tool.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,15 +123,15 @@ void CostmapCostTool::handleLocalCostResponse(
{
rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
auto response = future.get();
RCLCPP_INFO(node_->get_logger(), "Local costmap cost: %.1f", response->costs[0]);
RCLCPP_INFO(node->get_logger(), "Local costmap cost: %.1f", response->costs[0]);
}

void CostmapCostTool::handleGlobalCostResponse(
rclcpp::Client<nav2_msgs::srv::GetCosts>::SharedFuture future)
{
rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
auto response = future.get();
RCLCPP_INFO(node_->get_logger(), "Global costmap cost: %.1f", response->costs[0]);
RCLCPP_INFO(node->get_logger(), "Global costmap cost: %.1f", response->costs[0]);
}
} // namespace nav2_rviz_plugins

Expand Down

0 comments on commit 2260a7b

Please sign in to comment.