From: moo Date: Tue, 14 Apr 2026 16:55:36 +0000 (-0700) Subject: typo X-Git-Url: https://git.taranathan.com/?a=commitdiff_plain;h=beb79a88f7580dc98032414523dcc61173dc062b;p=FRC2026.git typo --- diff --git a/src/main/java/frc/robot/subsystems/drivetrain/GyroIOPigeon2.java b/src/main/java/frc/robot/subsystems/drivetrain/GyroIOPigeon2.java index 9980f96..e999f75 100644 --- a/src/main/java/frc/robot/subsystems/drivetrain/GyroIOPigeon2.java +++ b/src/main/java/frc/robot/subsystems/drivetrain/GyroIOPigeon2.java @@ -36,8 +36,8 @@ public class GyroIOPigeon2 implements GyroIO { IdConstants.PIGEON, DriveConstants.PIGEON_CAN); private final StatusSignal yaw = pigeon.getYaw(); - private final StatusSignal accelrationx = pigeon.getAccelerationX(); - private final StatusSignal accelrationy = pigeon.getAccelerationY(); + private final StatusSignal accelerationx = pigeon.getAccelerationX(); + private final StatusSignal accelerationy = pigeon.getAccelerationY(); private final Queue yawPositionQueue; private final Queue yawTimestampQueue; private final StatusSignal yawVelocity = pigeon.getAngularVelocityZWorld(); @@ -56,11 +56,11 @@ public class GyroIOPigeon2 implements GyroIO { @Override public void updateInputs(GyroIOInputs inputs) { - inputs.connected = BaseStatusSignal.refreshAll(yaw, yawVelocity, accelrationx, accelrationy).equals(StatusCode.OK); + inputs.connected = BaseStatusSignal.refreshAll(yaw, yawVelocity, accelerationx, accelerationy).equals(StatusCode.OK); inputs.yawPosition = Rotation2d.fromDegrees(yaw.getValueAsDouble()); inputs.yawVelocityRadPerSec = Units.degreesToRadians(yawVelocity.getValueAsDouble()); - inputs.accelerationX = accelrationx.getValueAsDouble(); - inputs.accelerationY = accelrationy.getValueAsDouble(); + inputs.accelerationX = accelerationx.getValueAsDouble(); + inputs.accelerationY = accelerationy.getValueAsDouble(); inputs.odometryYawTimestamps = yawTimestampQueue.stream().mapToDouble((Double value) -> value).toArray();