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 2392daf87d0..ceceaf32676 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 @@ -38,7 +38,6 @@ import edu.wpi.first.wpilibj.simulation.EncoderSim; import edu.wpi.first.wpilibj.smartdashboard.Field2d; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import java.io.IOException; /** Represents a differential drive style drivetrain. */ public class Drivetrain { @@ -130,13 +129,7 @@ public Drivetrain(DoubleArrayTopic cameraToObjectTopic) { m_cameraToObjectEntry = cameraToObjectTopic.getEntry(m_defaultVal); - try { - m_objectInField = - AprilTagFields.k2022RapidReact.loadAprilTagLayoutField().getTagPose(0).get(); - } catch (IOException e) { - e.printStackTrace(); - throw new RuntimeException(); - } + m_objectInField = AprilTagFields.k2022RapidReact.loadAprilTagLayoutField().getTagPose(0).get(); SmartDashboard.putData("Field", m_fieldSim); SmartDashboard.putData("FieldEstimation", m_fieldApproximation);