Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[apriltag] Add AprilTagFieldLayout.loadField() and migrate to it #6377

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import java.io.IOException;
import java.io.InputStream;
import java.io.InputStreamReader;
import java.io.UncheckedIOException;
import java.nio.file.Path;
import java.util.ArrayList;
import java.util.HashMap;
Expand Down Expand Up @@ -221,6 +222,22 @@ public void serialize(Path path) throws IOException {
new ObjectMapper().writeValue(path.toFile(), this);
}

/**
* Get an official {@link AprilTagFieldLayout}.
*
* @param field The loadable AprilTag field layout.
* @return AprilTagFieldLayout of the field.
* @throws UncheckedIOException If the layout does not exist.
*/
public static AprilTagFieldLayout loadField(AprilTagFields field) {
try {
return loadFromResource(field.m_resourceFile);
} catch (IOException e) {
throw new UncheckedIOException(
"Could not load AprilTagFieldLayout from " + field.m_resourceFile, e);
}
}

/**
* Deserializes a field layout from a resource within a internal jar file.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@

package edu.wpi.first.apriltag;

import java.io.IOException;
import java.io.UncheckedIOException;

/** Loadable AprilTag field layouts. */
Expand Down Expand Up @@ -36,11 +35,6 @@ public enum AprilTagFields {
* @throws UncheckedIOException If the layout does not exist
*/
public AprilTagFieldLayout loadAprilTagLayoutField() {
try {
return AprilTagFieldLayout.loadFromResource(m_resourceFile);
} catch (IOException e) {
throw new UncheckedIOException(
"Could not load AprilTagFieldLayout from " + m_resourceFile, e);
}
return AprilTagFieldLayout.loadField(this);
}
}
34 changes: 34 additions & 0 deletions apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,3 +125,37 @@ void frc::from_json(const wpi::json& json, AprilTagFieldLayout& layout) {
layout.m_fieldWidth =
units::meter_t{json.at("field").at("width").get<double>()};
}

// Use namespace declaration for forward declaration
namespace frc {

// C++ generated from resource files
std::string_view GetResource_2022_rapidreact_json();
std::string_view GetResource_2023_chargedup_json();
std::string_view GetResource_2024_crescendo_json();

} // namespace frc

AprilTagFieldLayout AprilTagFieldLayout::LoadField(AprilTagField field) {
std::string_view fieldString;
switch (field) {
case AprilTagField::k2022RapidReact:
fieldString = GetResource_2022_rapidreact_json();
break;
case AprilTagField::k2023ChargedUp:
fieldString = GetResource_2023_chargedup_json();
break;
case AprilTagField::k2024Crescendo:
fieldString = GetResource_2024_crescendo_json();
break;
case AprilTagField::kNumFields:
throw std::invalid_argument("Invalid Field");
}

wpi::json json = wpi::json::parse(fieldString);
return json.get<AprilTagFieldLayout>();
}

AprilTagFieldLayout frc::LoadAprilTagLayoutField(AprilTagField field) {
return AprilTagFieldLayout::LoadField(field);
}
36 changes: 0 additions & 36 deletions apriltag/src/main/native/cpp/AprilTagFields.cpp

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include <wpi/json_fwd.h>

#include "frc/apriltag/AprilTag.h"
#include "frc/apriltag/AprilTagFields.h"
#include "frc/geometry/Pose3d.h"

namespace frc {
Expand Down Expand Up @@ -48,6 +49,14 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout {
kRedAllianceWallRightSide,
};

/**
* Loads an AprilTagFieldLayout from a predefined field
*
* @param field The predefined field
* @return AprilTagFieldLayout of the field
*/
static AprilTagFieldLayout LoadField(AprilTagField field);

AprilTagFieldLayout() = default;

/**
Expand Down Expand Up @@ -152,4 +161,13 @@ void to_json(wpi::json& json, const AprilTagFieldLayout& layout);
WPILIB_DLLEXPORT
void from_json(const wpi::json& json, AprilTagFieldLayout& layout);

/**
* Loads an AprilTagFieldLayout from a predefined field
*
* @param field The predefined field
* @return AprilTagFieldLayout of the field
*/
WPILIB_DLLEXPORT AprilTagFieldLayout
LoadAprilTagLayoutField(AprilTagField field);

} // namespace frc
10 changes: 0 additions & 10 deletions apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,6 @@

#include <wpi/SymbolExports.h>

#include "frc/apriltag/AprilTagFieldLayout.h"

namespace frc {

/**
Expand All @@ -28,12 +26,4 @@ enum class AprilTagField {
kNumFields,
};

/**
* Loads an AprilTagFieldLayout from a predefined field
*
* @param field The predefined field
*/
WPILIB_DLLEXPORT AprilTagFieldLayout
LoadAprilTagLayoutField(AprilTagField field);

} // namespace frc
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
5 changes: 3 additions & 2 deletions apriltag/src/test/native/cpp/LoadConfigTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

#include <gtest/gtest.h>

#include "frc/apriltag/AprilTagFieldLayout.h"
#include "frc/apriltag/AprilTagFields.h"

namespace frc {
Expand All @@ -20,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 @@ -53,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::k2024Crescendo)};
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 @@ -4,6 +4,7 @@

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

import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.math.ComputerVisionUtil;
import edu.wpi.first.math.VecBuilder;
Expand Down Expand Up @@ -125,7 +126,8 @@ public Drivetrain(DoubleArrayTopic cameraToObjectTopic) {

m_cameraToObjectEntry = cameraToObjectTopic.getEntry(m_defaultVal);

m_objectInField = AprilTagFields.k2022RapidReact.loadAprilTagLayoutField().getTagPose(0).get();
m_objectInField =
AprilTagFieldLayout.loadField(AprilTagFields.k2024Crescendo).getTagPose(0).get();

SmartDashboard.putData("Field", m_fieldSim);
SmartDashboard.putData("FieldEstimation", m_fieldApproximation);
Expand Down
Loading