Skip to content

Commit

Permalink
Deprecate AprilTagFields.loadAprilTagLayoutField() and LoadAprilTagLa…
Browse files Browse the repository at this point in the history
…youtField()
  • Loading branch information
KangarooKoala committed Feb 2, 2024
1 parent 21bdc4f commit 7137325
Show file tree
Hide file tree
Showing 6 changed files with 11 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 =
Expand Down
4 changes: 2 additions & 2 deletions apriltag/src/test/native/cpp/LoadConfigTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ std::vector<AprilTagField> GetAllFields() {

TEST(AprilTagFieldsTest, TestLoad2022RapidReact) {
AprilTagFieldLayout layout =
LoadAprilTagLayoutField(AprilTagField::k2022RapidReact);
AprilTagFieldLayout::LoadField(AprilTagField::k2022RapidReact);

// Blue Hangar Truss - Hub
auto expectedPose =
Expand Down Expand Up @@ -54,7 +54,7 @@ class AllFieldsFixtureTest : public ::testing::TestWithParam<AprilTagField> {};

TEST_P(AllFieldsFixtureTest, CheckEntireEnum) {
AprilTagField field = GetParam();
EXPECT_NO_THROW(LoadAprilTagLayoutField(field));
EXPECT_NO_THROW(AprilTagFieldLayout::LoadField(field));
}

INSTANTIATE_TEST_SUITE_P(ValuesEnumTestInstTests, AllFieldsFixtureTest,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down

0 comments on commit 7137325

Please sign in to comment.