Skip to content

Commit 8639db3

Browse files
committed
Add AprilTagFieldLayout.loadField() and migrate to it
1 parent a8a352e commit 8639db3

File tree

10 files changed

+80
-59
lines changed

10 files changed

+80
-59
lines changed

apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFieldLayout.java

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
import java.io.IOException;
1717
import java.io.InputStream;
1818
import java.io.InputStreamReader;
19+
import java.io.UncheckedIOException;
1920
import java.nio.file.Path;
2021
import java.util.ArrayList;
2122
import java.util.HashMap;
@@ -221,6 +222,22 @@ public void serialize(Path path) throws IOException {
221222
new ObjectMapper().writeValue(path.toFile(), this);
222223
}
223224

225+
/**
226+
* Get an official {@link AprilTagFieldLayout}.
227+
*
228+
* @param field The loadable AprilTag field layout.
229+
* @return AprilTagFieldLayout of the field.
230+
* @throws UncheckedIOException If the layout does not exist.
231+
*/
232+
public static AprilTagFieldLayout loadField(AprilTagFields field) {
233+
try {
234+
return loadFromResource(field.m_resourceFile);
235+
} catch (IOException e) {
236+
throw new UncheckedIOException(
237+
"Could not load AprilTagFieldLayout from " + field.m_resourceFile, e);
238+
}
239+
}
240+
224241
/**
225242
* Deserializes a field layout from a resource within a internal jar file.
226243
*

apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@
44

55
package edu.wpi.first.apriltag;
66

7-
import java.io.IOException;
87
import java.io.UncheckedIOException;
98

109
/** Loadable AprilTag field layouts. */
@@ -36,11 +35,6 @@ public enum AprilTagFields {
3635
* @throws UncheckedIOException If the layout does not exist
3736
*/
3837
public AprilTagFieldLayout loadAprilTagLayoutField() {
39-
try {
40-
return AprilTagFieldLayout.loadFromResource(m_resourceFile);
41-
} catch (IOException e) {
42-
throw new UncheckedIOException(
43-
"Could not load AprilTagFieldLayout from " + m_resourceFile, e);
44-
}
38+
return AprilTagFieldLayout.loadField(this);
4539
}
4640
}

apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp

Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -125,3 +125,37 @@ void frc::from_json(const wpi::json& json, AprilTagFieldLayout& layout) {
125125
layout.m_fieldWidth =
126126
units::meter_t{json.at("field").at("width").get<double>()};
127127
}
128+
129+
// Use namespace declaration for forward declaration
130+
namespace frc {
131+
132+
// C++ generated from resource files
133+
std::string_view GetResource_2022_rapidreact_json();
134+
std::string_view GetResource_2023_chargedup_json();
135+
std::string_view GetResource_2024_crescendo_json();
136+
137+
} // namespace frc
138+
139+
AprilTagFieldLayout AprilTagFieldLayout::LoadField(AprilTagField field) {
140+
std::string_view fieldString;
141+
switch (field) {
142+
case AprilTagField::k2022RapidReact:
143+
fieldString = GetResource_2022_rapidreact_json();
144+
break;
145+
case AprilTagField::k2023ChargedUp:
146+
fieldString = GetResource_2023_chargedup_json();
147+
break;
148+
case AprilTagField::k2024Crescendo:
149+
fieldString = GetResource_2024_crescendo_json();
150+
break;
151+
case AprilTagField::kNumFields:
152+
throw std::invalid_argument("Invalid Field");
153+
}
154+
155+
wpi::json json = wpi::json::parse(fieldString);
156+
return json.get<AprilTagFieldLayout>();
157+
}
158+
159+
AprilTagFieldLayout frc::LoadAprilTagLayoutField(AprilTagField field) {
160+
return AprilTagFieldLayout::LoadField(field);
161+
}

apriltag/src/main/native/cpp/AprilTagFields.cpp

Lines changed: 0 additions & 36 deletions
This file was deleted.

apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
#include <wpi/json_fwd.h>
1515

1616
#include "frc/apriltag/AprilTag.h"
17+
#include "frc/apriltag/AprilTagFields.h"
1718
#include "frc/geometry/Pose3d.h"
1819

1920
namespace frc {
@@ -48,6 +49,14 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout {
4849
kRedAllianceWallRightSide,
4950
};
5051

52+
/**
53+
* Loads an AprilTagFieldLayout from a predefined field
54+
*
55+
* @param field The predefined field
56+
* @return AprilTagFieldLayout of the field
57+
*/
58+
static AprilTagFieldLayout LoadField(AprilTagField field);
59+
5160
AprilTagFieldLayout() = default;
5261

5362
/**
@@ -152,4 +161,13 @@ void to_json(wpi::json& json, const AprilTagFieldLayout& layout);
152161
WPILIB_DLLEXPORT
153162
void from_json(const wpi::json& json, AprilTagFieldLayout& layout);
154163

164+
/**
165+
* Loads an AprilTagFieldLayout from a predefined field
166+
*
167+
* @param field The predefined field
168+
* @return AprilTagFieldLayout of the field
169+
*/
170+
WPILIB_DLLEXPORT AprilTagFieldLayout
171+
LoadAprilTagLayoutField(AprilTagField field);
172+
155173
} // namespace frc

apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h

Lines changed: 0 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,6 @@
88

99
#include <wpi/SymbolExports.h>
1010

11-
#include "frc/apriltag/AprilTagFieldLayout.h"
12-
1311
namespace frc {
1412

1513
/**
@@ -28,12 +26,4 @@ enum class AprilTagField {
2826
kNumFields,
2927
};
3028

31-
/**
32-
* Loads an AprilTagFieldLayout from a predefined field
33-
*
34-
* @param field The predefined field
35-
*/
36-
WPILIB_DLLEXPORT AprilTagFieldLayout
37-
LoadAprilTagLayoutField(AprilTagField field);
38-
3929
} // namespace frc

apriltag/src/test/java/edu/wpi/first/apriltag/LoadConfigTest.java

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,13 +22,14 @@ class LoadConfigTest {
2222
@ParameterizedTest
2323
@EnumSource(AprilTagFields.class)
2424
void testLoad(AprilTagFields field) {
25-
AprilTagFieldLayout layout = Assertions.assertDoesNotThrow(field::loadAprilTagLayoutField);
25+
AprilTagFieldLayout layout =
26+
Assertions.assertDoesNotThrow(() -> AprilTagFieldLayout.loadField(field));
2627
assertNotNull(layout);
2728
}
2829

2930
@Test
3031
void test2022RapidReact() {
31-
AprilTagFieldLayout layout = AprilTagFields.k2022RapidReact.loadAprilTagLayoutField();
32+
AprilTagFieldLayout layout = AprilTagFieldLayout.loadField(AprilTagFields.k2022RapidReact);
3233

3334
// Blue Hangar Truss - Hub
3435
Pose3d expectedPose =

apriltag/src/test/native/cpp/LoadConfigTest.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44

55
#include <gtest/gtest.h>
66

7+
#include "frc/apriltag/AprilTagFieldLayout.h"
78
#include "frc/apriltag/AprilTagFields.h"
89

910
namespace frc {
@@ -20,7 +21,7 @@ std::vector<AprilTagField> GetAllFields() {
2021

2122
TEST(AprilTagFieldsTest, TestLoad2022RapidReact) {
2223
AprilTagFieldLayout layout =
23-
LoadAprilTagLayoutField(AprilTagField::k2022RapidReact);
24+
AprilTagFieldLayout::LoadField(AprilTagField::k2022RapidReact);
2425

2526
// Blue Hangar Truss - Hub
2627
auto expectedPose =
@@ -53,7 +54,7 @@ class AllFieldsFixtureTest : public ::testing::TestWithParam<AprilTagField> {};
5354

5455
TEST_P(AllFieldsFixtureTest, CheckEntireEnum) {
5556
AprilTagField field = GetParam();
56-
EXPECT_NO_THROW(LoadAprilTagLayoutField(field));
57+
EXPECT_NO_THROW(AprilTagFieldLayout::LoadField(field));
5758
}
5859

5960
INSTANTIATE_TEST_SUITE_P(ValuesEnumTestInstTests, AllFieldsFixtureTest,

wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -131,7 +131,7 @@ class Drivetrain {
131131
nt::DoubleArrayEntry& m_cameraToObjectEntryRef = m_cameraToObjectEntry;
132132

133133
frc::AprilTagFieldLayout m_aprilTagFieldLayout{
134-
frc::LoadAprilTagLayoutField(frc::AprilTagField::k2022RapidReact)};
134+
frc::AprilTagFieldLayout::LoadField(frc::AprilTagField::k2022RapidReact)};
135135
frc::Pose3d m_objectInField{m_aprilTagFieldLayout.GetTagPose(0).value()};
136136

137137
frc::PWMSparkMax m_leftLeader{1};

wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44

55
package edu.wpi.first.wpilibj.examples.differentialdriveposeestimator;
66

7+
import edu.wpi.first.apriltag.AprilTagFieldLayout;
78
import edu.wpi.first.apriltag.AprilTagFields;
89
import edu.wpi.first.math.ComputerVisionUtil;
910
import edu.wpi.first.math.VecBuilder;
@@ -125,7 +126,8 @@ public Drivetrain(DoubleArrayTopic cameraToObjectTopic) {
125126

126127
m_cameraToObjectEntry = cameraToObjectTopic.getEntry(m_defaultVal);
127128

128-
m_objectInField = AprilTagFields.k2022RapidReact.loadAprilTagLayoutField().getTagPose(0).get();
129+
m_objectInField =
130+
AprilTagFieldLayout.loadField(AprilTagFields.k2022RapidReact).getTagPose(0).get();
129131

130132
SmartDashboard.putData("Field", m_fieldSim);
131133
SmartDashboard.putData("FieldEstimation", m_fieldApproximation);

0 commit comments

Comments
 (0)