From 3fec792691dd25a31d69417bb886250c602bcfdd Mon Sep 17 00:00:00 2001 From: Bradley Bickford Date: Sat, 24 Feb 2024 17:48:46 -0500 Subject: [PATCH] Swerve diagnosing --- .../frc/robot/constants/DrivetrainConstants.java | 14 +++++++------- src/main/java/frc/robot/subsystems/Drivetrain.java | 2 +- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/constants/DrivetrainConstants.java b/src/main/java/frc/robot/constants/DrivetrainConstants.java index dfa14e3..28d067a 100644 --- a/src/main/java/frc/robot/constants/DrivetrainConstants.java +++ b/src/main/java/frc/robot/constants/DrivetrainConstants.java @@ -10,9 +10,9 @@ public final class DrivetrainConstants { public static final double kMaxSpeedMetersPerSecond = 4.1; public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second - public static final double kDirectionSlewRate = 2.4; // radians per second - public static final double kMagnitudeSlewRate = 3.2; // percent per second (1 = 100%) - public static final double kRotationalSlewRate = 4.0; // percent per second (1 = 100%) + public static final double kDirectionSlewRate = 4.8; // radians per second + public static final double kMagnitudeSlewRate = 6.4; // percent per second (1 = 100%) + public static final double kRotationalSlewRate = 8.0; // percent per second (1 = 100%) // Chassis configuration public static final double kTrackWidth = Units.inchesToMeters(28-1.75*2); @@ -26,10 +26,10 @@ public final class DrivetrainConstants { new Translation2d(-kWheelBase / 2, -kTrackWidth / 2)); // Angular offsets of the modules relative to the chassis in radians - public static final double kFrontLeftChassisAngularOffset = -Math.PI / 2; - public static final double kFrontRightChassisAngularOffset = 0; - public static final double kBackLeftChassisAngularOffset = Math.PI; - public static final double kBackRightChassisAngularOffset = Math.PI / 2; + public static final double kFrontLeftChassisAngularOffset = Math.PI; + public static final double kFrontRightChassisAngularOffset = -Math.PI / 2; + public static final double kBackLeftChassisAngularOffset = Math.PI / 2; + public static final double kBackRightChassisAngularOffset = 0; // SPARK MAX CAN IDs public static final int kFrontLeftDrivingCanId = 8; diff --git a/src/main/java/frc/robot/subsystems/Drivetrain.java b/src/main/java/frc/robot/subsystems/Drivetrain.java index 661319a..90af572 100644 --- a/src/main/java/frc/robot/subsystems/Drivetrain.java +++ b/src/main/java/frc/robot/subsystems/Drivetrain.java @@ -301,7 +301,7 @@ public class Drivetrain extends SubsystemBase { -MathUtil.applyDeadband(ySpeed.getAsDouble(), deadband), -MathUtil.applyDeadband(rotation.getAsDouble(), deadband), () -> fieldRelativeControl, - false + true ); }); }