diff --git a/src/main/java/frc/robot/drivetrain/ImuIOPigeon2.java b/src/main/java/frc/robot/drivetrain/ImuIOPigeon2.java index d2b7967..ca1ca99 100644 --- a/src/main/java/frc/robot/drivetrain/ImuIOPigeon2.java +++ b/src/main/java/frc/robot/drivetrain/ImuIOPigeon2.java @@ -40,7 +40,7 @@ public void updateInputs(ImuIOInputs inputs) { .map(value -> Rotation2d.fromDegrees(value)) .toArray(Rotation2d[]::new); inputs.odometryYawTimestamps = - m_yawTimestampQueue.stream().mapToDouble(Double::doubleValue).toArray(); + m_yawTimestampQueue.stream().mapToDouble(Double::valueOf).toArray(); m_yawPositionQueue.clear(); m_yawTimestampQueue.clear(); } diff --git a/src/main/java/frc/robot/drivetrain/ModuleIOTalonFX.java b/src/main/java/frc/robot/drivetrain/ModuleIOTalonFX.java index fa9a8f4..d57105b 100644 --- a/src/main/java/frc/robot/drivetrain/ModuleIOTalonFX.java +++ b/src/main/java/frc/robot/drivetrain/ModuleIOTalonFX.java @@ -214,8 +214,7 @@ public void updateInputs(ModuleIOInputs inputs) { m_steerPositionQueue.stream() .map((Double value) -> Rotation2d.fromRotations(value)) .toArray(Rotation2d[]::new); - inputs.odometryTimestamps = - m_timestampQueue.stream().mapToDouble(Double::doubleValue).toArray(); + inputs.odometryTimestamps = m_timestampQueue.stream().mapToDouble(Double::valueOf).toArray(); m_drivePositionQueue.clear(); m_steerPositionQueue.clear(); m_timestampQueue.clear();