[apriltag] Make loadAprilTagFieldLayout throw an unchecked exception instead (#5629)

This eliminates the need for users to wrap initialization of the fields in a try/catch.
This commit is contained in:
Ryan Blue
2023-09-15 17:25:21 -04:00
committed by GitHub
parent ad4b017321
commit 43a727e868
3 changed files with 19 additions and 13 deletions

View File

@@ -38,7 +38,6 @@ import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
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 class Drivetrain {
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);