diff --git a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp index 2d47c7acb9801..c434635ff1401 100644 --- a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp @@ -91,7 +91,7 @@ geometry_msgs::msg::Pose local2global( double PlannerWaypoints::compute_length() const { if (waypoints.empty()) { - std::runtime_error("cannot compute cost because waypoint has size 0"); + throw std::runtime_error("cannot compute cost because waypoint has size 0"); } double total_cost = 0.0; for (size_t i = 0; i < waypoints.size() - 1; ++i) {