From 07c373c68e120430a48737f363f3bdb8ed2ee364 Mon Sep 17 00:00:00 2001 From: redvinaa Date: Fri, 3 Jan 2025 11:59:18 +0100 Subject: [PATCH] Throw nav2_core exceptions Signed-off-by: redvinaa --- nav2_mppi_controller/src/path_handler.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nav2_mppi_controller/src/path_handler.cpp b/nav2_mppi_controller/src/path_handler.cpp index 4bc19b26cdf..adcab180b00 100644 --- a/nav2_mppi_controller/src/path_handler.cpp +++ b/nav2_mppi_controller/src/path_handler.cpp @@ -191,11 +191,11 @@ geometry_msgs::msg::PoseStamped PathHandler::getTransformedGoal() auto goal = global_plan_.poses.back(); goal.header.stamp = global_plan_.header.stamp; if (goal.header.frame_id.empty()) { - throw std::runtime_error("Goal pose has an empty frame_id"); + throw nav2_core::ControllerTFError("Goal pose has an empty frame_id"); } geometry_msgs::msg::PoseStamped transformed_goal; if (!transformPose(costmap_->getGlobalFrameID(), goal, transformed_goal)) { - throw std::runtime_error("Unable to transform goal pose into costmap frame"); + throw nav2_core::ControllerTFError("Unable to transform goal pose into costmap frame"); } return transformed_goal; }