From 92b876e7b0071620a7cbd41a28755fe712986cb1 Mon Sep 17 00:00:00 2001 From: Antoine PerreaultE Date: Wed, 25 Mar 2026 18:09:31 -0400 Subject: [PATCH] angle --- .vscode/settings.json | 3 ++- .../frc/robot/subsystems/CommandSwerveDrivetrain.java | 9 +++++++++ 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index 612cdd0..1745ba0 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -56,5 +56,6 @@ "edu.wpi.first.math.proto.*", "edu.wpi.first.math.**.proto.*", "edu.wpi.first.math.**.struct.*", - ] + ], + "java.jdt.ls.vmargs": "-XX:+UseParallelGC -XX:GCTimeRatio=4 -XX:AdaptiveSizePolicyWeight=90 -Dsun.zip.disableMemoryMapping=true -Xmx2G -Xms100m -Xlog:disable" } diff --git a/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java b/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java index 264519a..00532cf 100644 --- a/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java +++ b/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java @@ -7,6 +7,7 @@ import java.util.function.Supplier; import com.ctre.phoenix6.SignalLogger; import com.ctre.phoenix6.Utils; +import com.ctre.phoenix6.hardware.Pigeon2; import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants; import com.ctre.phoenix6.swerve.SwerveModuleConstants; import com.ctre.phoenix6.swerve.SwerveRequest; @@ -42,6 +43,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su private static final double kSimLoopPeriod = 0.004; // 4 ms private Notifier m_simNotifier = null; private double m_lastSimTime; + Pigeon2 pigeon2; /* Blue alliance sees forward as 0 degrees (toward red alliance wall) */ private static final Rotation2d kBlueAlliancePerspectiveRotation = Rotation2d.kZero; @@ -246,6 +248,13 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su @Override public void periodic() { + if(pigeon2.getYaw().getValueAsDouble() > 360){ + pigeon2.setYaw(pigeon2.getYaw().getValueAsDouble()-360); + } + else if(pigeon2.getYaw().getValueAsDouble() < 0){ + pigeon2.setYaw(pigeon2.getYaw().getValueAsDouble()+360); + } + /* * Periodically try to apply the operator perspective. * If we haven't applied the operator perspective before, then we should apply it regardless of DS state.