|
| 1 | +package frc.robot.generated; |
| 2 | + |
| 3 | +import com.ctre.phoenix6.configs.Slot0Configs; |
| 4 | +import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrainConstants; |
| 5 | +import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants; |
| 6 | +import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstantsFactory; |
| 7 | +import com.ctre.phoenix6.mechanisms.swerve.SwerveModule.ClosedLoopOutputType; |
| 8 | +import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants.SteerFeedbackType; |
| 9 | + |
| 10 | +import edu.wpi.first.math.util.Units; |
| 11 | +import frc.robot.CommandSwerveDrivetrain; |
| 12 | + |
| 13 | +// Generated by the Tuner X Swerve Project Generator |
| 14 | +// https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html |
| 15 | +public class TunerConstants { |
| 16 | + // Both sets of gains need to be tuned to your individual robot. |
| 17 | + |
| 18 | + // The steer motor uses any SwerveModule.SteerRequestType control request with the |
| 19 | + // output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput |
| 20 | + private static final Slot0Configs steerGains = new Slot0Configs() |
| 21 | + .withKP(100).withKI(0).withKD(0.2) |
| 22 | + .withKS(0).withKV(1.5).withKA(0); |
| 23 | + // When using closed-loop control, the drive motor uses the control |
| 24 | + // output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput |
| 25 | + private static final Slot0Configs driveGains = new Slot0Configs() |
| 26 | + .withKP(3).withKI(0).withKD(0) |
| 27 | + .withKS(0).withKV(0).withKA(0); |
| 28 | + |
| 29 | + // The closed-loop output type to use for the steer motors; |
| 30 | + // This affects the PID/FF gains for the steer motors |
| 31 | + private static final ClosedLoopOutputType steerClosedLoopOutput = ClosedLoopOutputType.Voltage; |
| 32 | + // The closed-loop output type to use for the drive motors; |
| 33 | + // This affects the PID/FF gains for the drive motors |
| 34 | + private static final ClosedLoopOutputType driveClosedLoopOutput = ClosedLoopOutputType.Voltage; |
| 35 | + |
| 36 | + // The stator current at which the wheels start to slip; |
| 37 | + // This needs to be tuned to your individual robot |
| 38 | + private static final double kSlipCurrentA = 300.0; |
| 39 | + |
| 40 | + // Theoretical free speed (m/s) at 12v applied output; |
| 41 | + // This needs to be tuned to your individual robot |
| 42 | + public static final double kSpeedAt12VoltsMps = 6.21; |
| 43 | + |
| 44 | + // Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns; |
| 45 | + // This may need to be tuned to your individual robot |
| 46 | + private static final double kCoupleRatio = 3; |
| 47 | + |
| 48 | + private static final double kDriveGearRatio = 5.142857142857142; |
| 49 | + private static final double kSteerGearRatio = 12.8; |
| 50 | + private static final double kWheelRadiusInches = 2; |
| 51 | + |
| 52 | + private static final boolean kSteerMotorReversed = false; |
| 53 | + private static final boolean kInvertLeftSide = false; |
| 54 | + private static final boolean kInvertRightSide = true; |
| 55 | + |
| 56 | + private static final String kCANbusName = "Upper"; |
| 57 | + private static final int kPigeonId = 0; |
| 58 | + |
| 59 | + |
| 60 | + // These are only used for simulation |
| 61 | + private static final double kSteerInertia = 0.00001; |
| 62 | + private static final double kDriveInertia = 0.001; |
| 63 | + // Simulated voltage necessary to overcome friction |
| 64 | + private static final double kSteerFrictionVoltage = 0.25; |
| 65 | + private static final double kDriveFrictionVoltage = 0.25; |
| 66 | + |
| 67 | + private static final SwerveDrivetrainConstants DrivetrainConstants = new SwerveDrivetrainConstants() |
| 68 | + .withPigeon2Id(kPigeonId) |
| 69 | + .withCANbusName(kCANbusName); |
| 70 | + |
| 71 | + private static final SwerveModuleConstantsFactory ConstantCreator = new SwerveModuleConstantsFactory() |
| 72 | + .withDriveMotorGearRatio(kDriveGearRatio) |
| 73 | + .withSteerMotorGearRatio(kSteerGearRatio) |
| 74 | + .withWheelRadius(kWheelRadiusInches) |
| 75 | + .withSlipCurrent(kSlipCurrentA) |
| 76 | + .withSteerMotorGains(steerGains) |
| 77 | + .withDriveMotorGains(driveGains) |
| 78 | + .withSteerMotorClosedLoopOutput(steerClosedLoopOutput) |
| 79 | + .withDriveMotorClosedLoopOutput(driveClosedLoopOutput) |
| 80 | + .withSpeedAt12VoltsMps(kSpeedAt12VoltsMps) |
| 81 | + .withSteerInertia(kSteerInertia) |
| 82 | + .withDriveInertia(kDriveInertia) |
| 83 | + .withSteerFrictionVoltage(kSteerFrictionVoltage) |
| 84 | + .withDriveFrictionVoltage(kDriveFrictionVoltage) |
| 85 | + .withFeedbackSource(SteerFeedbackType.FusedCANcoder) |
| 86 | + .withCouplingGearRatio(kCoupleRatio) |
| 87 | + .withSteerMotorInverted(kSteerMotorReversed); |
| 88 | + |
| 89 | + |
| 90 | + // Front Left |
| 91 | + private static final int kFrontLeftDriveMotorId = 1; |
| 92 | + private static final int kFrontLeftSteerMotorId = 2; |
| 93 | + private static final int kFrontLeftEncoderId = 2; |
| 94 | + private static final double kFrontLeftEncoderOffset = -0.091796875; |
| 95 | + |
| 96 | + private static final double kFrontLeftXPosInches = 11.875; |
| 97 | + private static final double kFrontLeftYPosInches = 11.875; |
| 98 | + |
| 99 | + // Front Right |
| 100 | + private static final int kFrontRightDriveMotorId = 18; |
| 101 | + private static final int kFrontRightSteerMotorId = 19; |
| 102 | + private static final int kFrontRightEncoderId = 1; |
| 103 | + private static final double kFrontRightEncoderOffset = -0.37890625; |
| 104 | + |
| 105 | + private static final double kFrontRightXPosInches = 11.875; |
| 106 | + private static final double kFrontRightYPosInches = -11.875; |
| 107 | + |
| 108 | + // Back Left |
| 109 | + private static final int kBackLeftDriveMotorId = 8; |
| 110 | + private static final int kBackLeftSteerMotorId = 9; |
| 111 | + private static final int kBackLeftEncoderId = 3; |
| 112 | + private static final double kBackLeftEncoderOffset = -0.063232421875; |
| 113 | + |
| 114 | + private static final double kBackLeftXPosInches = -11.875; |
| 115 | + private static final double kBackLeftYPosInches = 11.875; |
| 116 | + |
| 117 | + // Back Right |
| 118 | + private static final int kBackRightDriveMotorId = 10; |
| 119 | + private static final int kBackRightSteerMotorId = 11; |
| 120 | + private static final int kBackRightEncoderId = 4; |
| 121 | + private static final double kBackRightEncoderOffset = -0.486572265625; |
| 122 | + |
| 123 | + private static final double kBackRightXPosInches = -11.875; |
| 124 | + private static final double kBackRightYPosInches = -11.875; |
| 125 | + |
| 126 | + |
| 127 | + private static final SwerveModuleConstants FrontLeft = ConstantCreator.createModuleConstants( |
| 128 | + kFrontLeftSteerMotorId, kFrontLeftDriveMotorId, kFrontLeftEncoderId, kFrontLeftEncoderOffset, Units.inchesToMeters(kFrontLeftXPosInches), Units.inchesToMeters(kFrontLeftYPosInches), kInvertLeftSide); |
| 129 | + private static final SwerveModuleConstants FrontRight = ConstantCreator.createModuleConstants( |
| 130 | + kFrontRightSteerMotorId, kFrontRightDriveMotorId, kFrontRightEncoderId, kFrontRightEncoderOffset, Units.inchesToMeters(kFrontRightXPosInches), Units.inchesToMeters(kFrontRightYPosInches), kInvertRightSide); |
| 131 | + private static final SwerveModuleConstants BackLeft = ConstantCreator.createModuleConstants( |
| 132 | + kBackLeftSteerMotorId, kBackLeftDriveMotorId, kBackLeftEncoderId, kBackLeftEncoderOffset, Units.inchesToMeters(kBackLeftXPosInches), Units.inchesToMeters(kBackLeftYPosInches), kInvertLeftSide); |
| 133 | + private static final SwerveModuleConstants BackRight = ConstantCreator.createModuleConstants( |
| 134 | + kBackRightSteerMotorId, kBackRightDriveMotorId, kBackRightEncoderId, kBackRightEncoderOffset, Units.inchesToMeters(kBackRightXPosInches), Units.inchesToMeters(kBackRightYPosInches), kInvertRightSide); |
| 135 | + |
| 136 | + public static final CommandSwerveDrivetrain DriveTrain = new CommandSwerveDrivetrain(DrivetrainConstants, FrontLeft, |
| 137 | + FrontRight, BackLeft, BackRight); |
| 138 | +} |
0 commit comments