diff --git a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp index 805f375af4276..875d44847b40c 100644 --- a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp @@ -48,11 +48,6 @@ double calcReedsSheppDistance(const Pose & p1, const Pose & p2, double radius) return rs_space.distance(pose0, pose1); } -void setYaw(geometry_msgs::msg::Quaternion * orientation, const double yaw) -{ - *orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); -} - Pose calcRelativePose(const Pose & base_pose, const Pose & pose) { tf2::Transform tf_transform;