diff --git a/wpilibc/src/main/native/cpp/apriltag/AprilTagFieldLayout.cpp b/wpilibc/src/main/native/cpp/apriltag/AprilTagFieldLayout.cpp index 9efc586fea..3af133157a 100644 --- a/wpilibc/src/main/native/cpp/apriltag/AprilTagFieldLayout.cpp +++ b/wpilibc/src/main/native/cpp/apriltag/AprilTagFieldLayout.cpp @@ -4,7 +4,6 @@ #include "frc/apriltag/AprilTagFieldLayout.h" -#include #include #include @@ -26,7 +25,9 @@ AprilTagFieldLayout::AprilTagFieldLayout(std::string_view path) { wpi::json json; input >> json; - m_apriltags = json.at("tags").get>(); + for (const auto& tag : json.at("tags").get>()) { + m_apriltags[tag.ID] = tag; + } m_fieldWidth = units::meter_t{json.at("field").at("width").get()}; m_fieldLength = units::meter_t{json.at("field").at("height").get()}; } @@ -34,28 +35,28 @@ AprilTagFieldLayout::AprilTagFieldLayout(std::string_view path) { AprilTagFieldLayout::AprilTagFieldLayout(std::vector apriltags, units::meter_t fieldLength, units::meter_t fieldWidth) - : m_apriltags(std::move(apriltags)), - m_fieldLength(std::move(fieldLength)), - m_fieldWidth(std::move(fieldWidth)) {} + : m_fieldLength(std::move(fieldLength)), + m_fieldWidth(std::move(fieldWidth)) { + for (const auto& tag : apriltags) { + m_apriltags[tag.ID] = tag; + } +} void AprilTagFieldLayout::SetAlliance(DriverStation::Alliance alliance) { m_mirror = alliance == DriverStation::Alliance::kRed; } std::optional AprilTagFieldLayout::GetTagPose(int ID) const { - Pose3d returnPose; - auto it = std::find_if(m_apriltags.begin(), m_apriltags.end(), - [=](const auto& tag) { return tag.ID == ID; }); - if (it != m_apriltags.end()) { - returnPose = it->pose; - } else { - return std::optional(); + const auto& it = m_apriltags.find(ID); + if (it == m_apriltags.end()) { + return std::nullopt; } + Pose3d returnPose = it->second.pose; if (m_mirror) { returnPose = returnPose.RelativeTo(Pose3d{ m_fieldLength, m_fieldWidth, 0_m, Rotation3d{0_deg, 0_deg, 180_deg}}); } - return std::make_optional(returnPose); + return returnPose; } void AprilTagFieldLayout::Serialize(std::string_view path) { @@ -82,14 +83,24 @@ bool AprilTagFieldLayout::operator!=(const AprilTagFieldLayout& other) const { } void frc::to_json(wpi::json& json, const AprilTagFieldLayout& layout) { + std::vector tagVector; + tagVector.reserve(layout.m_apriltags.size()); + for (const auto& pair : layout.m_apriltags) { + tagVector.push_back(pair.second); + } + json = wpi::json{{"field", {{"length", layout.m_fieldLength.value()}, {"width", layout.m_fieldWidth.value()}}}, - {"tags", layout.m_apriltags}}; + {"tags", tagVector}}; } void frc::from_json(const wpi::json& json, AprilTagFieldLayout& layout) { - layout.m_apriltags = json.at("tags").get>(); + layout.m_apriltags.clear(); + for (const auto& tag : json.at("tags").get>()) { + layout.m_apriltags[tag.ID] = tag; + } + layout.m_fieldLength = units::meter_t{json.at("field").at("length").get()}; layout.m_fieldWidth = diff --git a/wpilibc/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h b/wpilibc/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h index 535bc51b36..69a6b51846 100644 --- a/wpilibc/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h +++ b/wpilibc/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h @@ -6,6 +6,7 @@ #include #include +#include #include #include @@ -101,7 +102,7 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout { bool operator!=(const AprilTagFieldLayout& other) const; private: - std::vector m_apriltags; + std::unordered_map m_apriltags; units::meter_t m_fieldLength; units::meter_t m_fieldWidth; bool m_mirror = false; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/apriltag/AprilTagFieldLayout.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/apriltag/AprilTagFieldLayout.java index 93397228ac..1659e9082b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/apriltag/AprilTagFieldLayout.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/apriltag/AprilTagFieldLayout.java @@ -16,7 +16,9 @@ import edu.wpi.first.wpilibj.DriverStation; import java.io.IOException; import java.nio.file.Path; import java.util.ArrayList; +import java.util.HashMap; import java.util.List; +import java.util.Map; import java.util.Objects; import java.util.Optional; @@ -38,8 +40,7 @@ import java.util.Optional; @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) public class AprilTagFieldLayout { - @JsonProperty(value = "tags") - private final List m_apriltags = new ArrayList<>(); + private final Map m_apriltags = new HashMap<>(); @JsonProperty(value = "field") private FieldDimensions m_fieldDimensions; @@ -65,7 +66,7 @@ public class AprilTagFieldLayout { public AprilTagFieldLayout(Path path) throws IOException { AprilTagFieldLayout layout = new ObjectMapper().readValue(path.toFile(), AprilTagFieldLayout.class); - m_apriltags.addAll(layout.m_apriltags); + m_apriltags.putAll(layout.m_apriltags); m_fieldDimensions = layout.m_fieldDimensions; } @@ -85,10 +86,17 @@ public class AprilTagFieldLayout { @JsonProperty(required = true, value = "tags") List apriltags, @JsonProperty(required = true, value = "field") FieldDimensions fieldDimensions) { // To ensure the underlying semantics don't change with what kind of list is passed in - m_apriltags.addAll(apriltags); + for (AprilTag tag : apriltags) { + m_apriltags.put(tag.ID, tag); + } m_fieldDimensions = fieldDimensions; } + @JsonProperty("tags") + public List getTags() { + return new ArrayList<>(m_apriltags.values()); + } + /** * Set the alliance that your team is on. * @@ -110,16 +118,11 @@ public class AprilTagFieldLayout { */ @SuppressWarnings("ParameterName") public Optional getTagPose(int ID) { - Pose3d pose = null; - for (AprilTag apriltag : m_apriltags) { - if (apriltag.ID == ID) { - pose = apriltag.pose; - break; - } - } - if (pose == null) { + AprilTag tag = m_apriltags.get(ID); + if (tag == null) { return Optional.empty(); } + Pose3d pose = tag.pose; if (m_mirror) { pose = pose.relativeTo(