From a60ca9d71cdd6e1efb7816e07a0c5dbbec6cca99 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Thu, 19 Jan 2023 17:01:17 -0800 Subject: [PATCH] [examples] Update AprilTag field load API usage (#4975) --- .../examples/differentialdriveposeestimator/Drivetrain.java | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) 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 e1b36fc067..2392daf87d 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 @@ -4,7 +4,6 @@ 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; @@ -133,9 +132,7 @@ public class Drivetrain { try { m_objectInField = - AprilTagFieldLayout.loadFromResource(AprilTagFields.k2022RapidReact.m_resourceFile) - .getTagPose(0) - .get(); + AprilTagFields.k2022RapidReact.loadAprilTagLayoutField().getTagPose(0).get(); } catch (IOException e) { e.printStackTrace(); throw new RuntimeException();