From 71373258f6a9ec18178fcc5a2520e9c63df270f4 Mon Sep 17 00:00:00 2001 From: Joseph Eng Date: Thu, 1 Feb 2024 21:24:49 -0800 Subject: [PATCH] Deprecate AprilTagFields.loadAprilTagLayoutField() and LoadAprilTagLayoutField() --- .../src/main/java/edu/wpi/first/apriltag/AprilTagFields.java | 2 ++ .../main/native/include/frc/apriltag/AprilTagFieldLayout.h | 2 ++ .../src/test/java/edu/wpi/first/apriltag/LoadConfigTest.java | 5 +++-- apriltag/src/test/native/cpp/LoadConfigTest.cpp | 4 ++-- .../DifferentialDrivePoseEstimator/include/Drivetrain.h | 2 +- .../examples/differentialdriveposeestimator/Drivetrain.java | 2 +- 6 files changed, 11 insertions(+), 6 deletions(-) diff --git a/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java b/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java index 776050c2749..7d9d5bc5a1c 100644 --- a/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java +++ b/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java @@ -33,7 +33,9 @@ public enum AprilTagFields { * * @return AprilTagFieldLayout of the field * @throws UncheckedIOException If the layout does not exist + * @deprecated Use {@link AprilTagFieldLayout#loadField(AprilTagFields)} instead. */ + @Deprecated(forRemoval = true, since = "2024") public AprilTagFieldLayout loadAprilTagLayoutField() { return AprilTagFieldLayout.loadField(this); } diff --git a/apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h b/apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h index 6ba3824ed66..c2e73c78c4d 100644 --- a/apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h +++ b/apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h @@ -166,7 +166,9 @@ void from_json(const wpi::json& json, AprilTagFieldLayout& layout); * * @param field The predefined field * @return AprilTagFieldLayout of the field + * @deprecated Use AprilTagFieldLayout::LoadField() instead */ +[[deprecated("Use AprilTagFieldLayout::LoadField() instead")]] WPILIB_DLLEXPORT AprilTagFieldLayout LoadAprilTagLayoutField(AprilTagField field); diff --git a/apriltag/src/test/java/edu/wpi/first/apriltag/LoadConfigTest.java b/apriltag/src/test/java/edu/wpi/first/apriltag/LoadConfigTest.java index d5deb573af9..e4e4875a194 100644 --- a/apriltag/src/test/java/edu/wpi/first/apriltag/LoadConfigTest.java +++ b/apriltag/src/test/java/edu/wpi/first/apriltag/LoadConfigTest.java @@ -22,13 +22,14 @@ class LoadConfigTest { @ParameterizedTest @EnumSource(AprilTagFields.class) void testLoad(AprilTagFields field) { - AprilTagFieldLayout layout = Assertions.assertDoesNotThrow(field::loadAprilTagLayoutField); + AprilTagFieldLayout layout = + Assertions.assertDoesNotThrow(() -> AprilTagFieldLayout.loadField(field)); assertNotNull(layout); } @Test void test2022RapidReact() { - AprilTagFieldLayout layout = AprilTagFields.k2022RapidReact.loadAprilTagLayoutField(); + AprilTagFieldLayout layout = AprilTagFieldLayout.loadField(AprilTagFields.k2022RapidReact); // Blue Hangar Truss - Hub Pose3d expectedPose = diff --git a/apriltag/src/test/native/cpp/LoadConfigTest.cpp b/apriltag/src/test/native/cpp/LoadConfigTest.cpp index bdf1a4af341..ba6fe81ff96 100644 --- a/apriltag/src/test/native/cpp/LoadConfigTest.cpp +++ b/apriltag/src/test/native/cpp/LoadConfigTest.cpp @@ -21,7 +21,7 @@ std::vector GetAllFields() { TEST(AprilTagFieldsTest, TestLoad2022RapidReact) { AprilTagFieldLayout layout = - LoadAprilTagLayoutField(AprilTagField::k2022RapidReact); + AprilTagFieldLayout::LoadField(AprilTagField::k2022RapidReact); // Blue Hangar Truss - Hub auto expectedPose = @@ -54,7 +54,7 @@ class AllFieldsFixtureTest : public ::testing::TestWithParam {}; TEST_P(AllFieldsFixtureTest, CheckEntireEnum) { AprilTagField field = GetParam(); - EXPECT_NO_THROW(LoadAprilTagLayoutField(field)); + EXPECT_NO_THROW(AprilTagFieldLayout::LoadField(field)); } INSTANTIATE_TEST_SUITE_P(ValuesEnumTestInstTests, AllFieldsFixtureTest, diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h index 63a9aea0142..c7d723a1afe 100644 --- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h @@ -131,7 +131,7 @@ class Drivetrain { nt::DoubleArrayEntry& m_cameraToObjectEntryRef = m_cameraToObjectEntry; frc::AprilTagFieldLayout m_aprilTagFieldLayout{ - frc::LoadAprilTagLayoutField(frc::AprilTagField::k2022RapidReact)}; + frc::AprilTagFieldLayout::LoadField(frc::AprilTagField::k2022RapidReact)}; frc::Pose3d m_objectInField{m_aprilTagFieldLayout.GetTagPose(0).value()}; frc::PWMSparkMax m_leftLeader{1}; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java index 9b7ec75b5f8..08d75f54d93 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java @@ -125,7 +125,7 @@ public Drivetrain(DoubleArrayTopic cameraToObjectTopic) { m_cameraToObjectEntry = cameraToObjectTopic.getEntry(m_defaultVal); - m_objectInField = AprilTagFields.k2022RapidReact.loadAprilTagLayoutField().getTagPose(0).get(); + m_objectInField = AprilTagFieldLayout.loadField(AprilTagFields.k2022RapidReact).getTagPose(0).get(); SmartDashboard.putData("Field", m_fieldSim); SmartDashboard.putData("FieldEstimation", m_fieldApproximation);