Skip to content

Commit

Permalink
tune swerve
Browse files Browse the repository at this point in the history
  • Loading branch information
Owen756 committed Oct 2, 2024
1 parent 14dfcdc commit ff7da64
Showing 1 changed file with 76 additions and 67 deletions.
143 changes: 76 additions & 67 deletions src/main/java/frc/robot/generated/TunerConstants.java
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
package frc.robot.generated;

import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.configs.Pigeon2Configuration;
import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.configs.TorqueCurrentConfigs;
import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrainConstants;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModule.ClosedLoopOutputType;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants;
Expand All @@ -19,11 +20,11 @@ public class TunerConstants {
// The steer motor uses any SwerveModule.SteerRequestType control request with the
// output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput
private static final Slot0Configs steerGains =
new Slot0Configs().withKP(110).withKI(0).withKD(0.2).withKS(0).withKV(1.5).withKA(0);
new Slot0Configs().withKP(100).withKI(0).withKD(0.2).withKS(0).withKV(1.5).withKA(0);
// When using closed-loop control, the drive motor uses the control
// output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput
private static final Slot0Configs driveGains =
new Slot0Configs().withKP(3.5).withKI(0).withKD(0).withKS(0).withKV(0).withKA(0);
new Slot0Configs().withKP(3).withKI(0).withKD(0).withKS(0).withKV(0).withKA(0);

// The closed-loop output type to use for the steer motors;
// This affects the PID/FF gains for the steer motors
Expand All @@ -35,26 +36,41 @@ public class TunerConstants {

// The stator current at which the wheels start to slip;
// This needs to be tuned to your individual robot
private static final double kSlipCurrentA = 300.0;
private static final double kSlipCurrentA = 150.0;

// Initial configs for the drive and steer motors and the CANcoder; these cannot be null.
// Some configs will be overwritten; check the `with*InitialConfigs()` API documentation.
private static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration();
private static final TalonFXConfiguration steerInitialConfigs =
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
// Swerve azimuth does not require much torque output, so we can set a relatively
// low
// stator current limit to help avoid brownouts without impacting performance.
.withStatorCurrentLimit(60)
.withStatorCurrentLimitEnable(true));
private static final CANcoderConfiguration cancoderInitialConfigs = new CANcoderConfiguration();
// Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs
private static final Pigeon2Configuration pigeonConfigs = null;

// Theoretical free speed (m/s) at 12v applied output;
// This needs to be tuned to your individual robot
public static final double kSpeedAt12VoltsMps = 5.96;
public static final double kSpeedAt12VoltsMps = 5.21;

// Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns;
// This may need to be tuned to your individual robot
private static final double kCoupleRatio = 3.125;
private static final double kCoupleRatio = 3.5714285714285716;

private static final double kDriveGearRatio = (50.0 / 14.0) / (28.0 / 16.0) / (15.0 / 45.0);
private static final double kDriveGearRatio = 6.122448979591837;
private static final double kSteerGearRatio = 21.428571428571427;
private static final double kWheelRadiusInches = 2;

private static final boolean kSteerMotorReversed = true;
private static final boolean kInvertLeftSide = false;
private static final boolean kInvertRightSide = true;
private static final boolean kInvertLeftSide = true;
private static final boolean kInvertRightSide = false;

public static final String kCANbusName = "581CANivore";
public static final int kPigeonId = 1;
private static final String kCANbusName = "581CANivore";
private static final int kPigeonId = 1;

// These are only used for simulation
private static final double kSteerInertia = 0.00001;
Expand All @@ -63,31 +79,14 @@ public class TunerConstants {
private static final double kSteerFrictionVoltage = 0.25;
private static final double kDriveFrictionVoltage = 0.25;

public static final SwerveDrivetrainConstants DrivetrainConstants =
new SwerveDrivetrainConstants().withPigeon2Id(kPigeonId).withCANbusName(kCANbusName);
private static final SwerveDrivetrainConstants DrivetrainConstants =
new SwerveDrivetrainConstants()
.withCANbusName(kCANbusName)
.withPigeon2Id(kPigeonId)
.withPigeon2Configs(pigeonConfigs);

private static final SwerveModuleConstantsFactory ConstantCreator =
new SwerveModuleConstantsFactory()
.withDriveMotorInitialConfigs(
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(100)
.withStatorCurrentLimit(60)
.withSupplyCurrentLimitEnable(true)
.withStatorCurrentLimitEnable(true))
.withTorqueCurrent(
new TorqueCurrentConfigs()
.withPeakForwardTorqueCurrent(80)
.withPeakReverseTorqueCurrent(-80)))
.withSteerMotorInitialConfigs(
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(20)
.withStatorCurrentLimit(70)
.withSupplyCurrentLimitEnable(true)
.withStatorCurrentLimitEnable(true)))
.withDriveMotorGearRatio(kDriveGearRatio)
.withSteerMotorGearRatio(kSteerGearRatio)
.withWheelRadius(kWheelRadiusInches)
Expand All @@ -103,13 +102,16 @@ public class TunerConstants {
.withDriveFrictionVoltage(kDriveFrictionVoltage)
.withFeedbackSource(SteerFeedbackType.FusedCANcoder)
.withCouplingGearRatio(kCoupleRatio)
.withSteerMotorInverted(kSteerMotorReversed);
.withDriveMotorInitialConfigs(driveInitialConfigs)
.withSteerMotorInitialConfigs(steerInitialConfigs)
.withCANcoderInitialConfigs(cancoderInitialConfigs);

// Front Left
private static final int kFrontLeftDriveMotorId = 2;
private static final int kFrontLeftSteerMotorId = 3;
private static final int kFrontLeftEncoderId = 10;
private static final double kFrontLeftEncoderOffset = -0.486083984375;
private static final double kFrontLeftEncoderOffset = 0.067626953125;
private static final boolean kFrontLeftSteerInvert = true;

private static final double kFrontLeftXPosInches = 10.125;
private static final double kFrontLeftYPosInches = 11.375;
Expand All @@ -118,7 +120,8 @@ public class TunerConstants {
private static final int kFrontRightDriveMotorId = 4;
private static final int kFrontRightSteerMotorId = 5;
private static final int kFrontRightEncoderId = 11;
private static final double kFrontRightEncoderOffset = -0.27734375;
private static final double kFrontRightEncoderOffset = 0.155029296875;
private static final boolean kFrontRightSteerInvert = true;

private static final double kFrontRightXPosInches = 10.125;
private static final double kFrontRightYPosInches = -11.375;
Expand All @@ -127,7 +130,8 @@ public class TunerConstants {
private static final int kBackLeftDriveMotorId = 6;
private static final int kBackLeftSteerMotorId = 7;
private static final int kBackLeftEncoderId = 12;
private static final double kBackLeftEncoderOffset = 0.302978515625;
private static final double kBackLeftEncoderOffset = -0.316162109375;
private static final boolean kBackLeftSteerInvert = true;

private static final double kBackLeftXPosInches = -10.125;
private static final double kBackLeftYPosInches = 11.375;
Expand All @@ -136,45 +140,50 @@ public class TunerConstants {
private static final int kBackRightDriveMotorId = 8;
private static final int kBackRightSteerMotorId = 9;
private static final int kBackRightEncoderId = 13;
private static final double kBackRightEncoderOffset = -0.19287109375;
private static final double kBackRightEncoderOffset = 0.17578125;
private static final boolean kBackRightSteerInvert = true;

private static final double kBackRightXPosInches = -10.125;
private static final double kBackRightYPosInches = -11.375;

public static final SwerveModuleConstants FrontLeft =
ConstantCreator.createModuleConstants(
kFrontLeftSteerMotorId,
kFrontLeftDriveMotorId,
kFrontLeftEncoderId,
kFrontLeftEncoderOffset,
Units.inchesToMeters(kFrontLeftXPosInches),
Units.inchesToMeters(kFrontLeftYPosInches),
kInvertLeftSide);
kFrontLeftSteerMotorId,
kFrontLeftDriveMotorId,
kFrontLeftEncoderId,
kFrontLeftEncoderOffset,
Units.inchesToMeters(kFrontLeftXPosInches),
Units.inchesToMeters(kFrontLeftYPosInches),
kInvertLeftSide)
.withSteerMotorInverted(kFrontLeftSteerInvert);
public static final SwerveModuleConstants FrontRight =
ConstantCreator.createModuleConstants(
kFrontRightSteerMotorId,
kFrontRightDriveMotorId,
kFrontRightEncoderId,
kFrontRightEncoderOffset,
Units.inchesToMeters(kFrontRightXPosInches),
Units.inchesToMeters(kFrontRightYPosInches),
kInvertRightSide);
kFrontRightSteerMotorId,
kFrontRightDriveMotorId,
kFrontRightEncoderId,
kFrontRightEncoderOffset,
Units.inchesToMeters(kFrontRightXPosInches),
Units.inchesToMeters(kFrontRightYPosInches),
kInvertRightSide)
.withSteerMotorInverted(kFrontRightSteerInvert);
public static final SwerveModuleConstants BackLeft =
ConstantCreator.createModuleConstants(
kBackLeftSteerMotorId,
kBackLeftDriveMotorId,
kBackLeftEncoderId,
kBackLeftEncoderOffset,
Units.inchesToMeters(kBackLeftXPosInches),
Units.inchesToMeters(kBackLeftYPosInches),
kInvertLeftSide);
kBackLeftSteerMotorId,
kBackLeftDriveMotorId,
kBackLeftEncoderId,
kBackLeftEncoderOffset,
Units.inchesToMeters(kBackLeftXPosInches),
Units.inchesToMeters(kBackLeftYPosInches),
kInvertLeftSide)
.withSteerMotorInverted(kBackLeftSteerInvert);
public static final SwerveModuleConstants BackRight =
ConstantCreator.createModuleConstants(
kBackRightSteerMotorId,
kBackRightDriveMotorId,
kBackRightEncoderId,
kBackRightEncoderOffset,
Units.inchesToMeters(kBackRightXPosInches),
Units.inchesToMeters(kBackRightYPosInches),
kInvertRightSide);
kBackRightSteerMotorId,
kBackRightDriveMotorId,
kBackRightEncoderId,
kBackRightEncoderOffset,
Units.inchesToMeters(kBackRightXPosInches),
Units.inchesToMeters(kBackRightYPosInches),
kInvertRightSide)
.withSteerMotorInverted(kBackRightSteerInvert);
}

0 comments on commit ff7da64

Please sign in to comment.