Skip to content

Commit

Permalink
switched back to current machine
Browse files Browse the repository at this point in the history
  • Loading branch information
catr1xLiu committed Dec 31, 2024
1 parent 1299071 commit 373f714
Show file tree
Hide file tree
Showing 2 changed files with 125 additions and 125 deletions.
125 changes: 63 additions & 62 deletions src/main/java/frc/robot/generated/TunerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import com.ctre.phoenix6.swerve.SwerveModuleConstants.SteerFeedbackType;
import com.ctre.phoenix6.swerve.SwerveModuleConstantsFactory;
import edu.wpi.first.units.measure.*;
import frc.robot.constants.DriveTrainConstants;

// Generated by the Tuner X Swerve Project Generator
// https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html
Expand All @@ -23,88 +24,88 @@
*
* <p>TODO: you MUST delete the last two lines of this file
*
* <p>TODO: you should also change the numbers in {@link frc.robot.constants.DriveTrainConstants}
* <p>TODO: you should also change the numbers in {@link DriveTrainConstants}
*/
public class TunerConstants {
// Both sets of gains need to be tuned to your individual robot.

// 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(100)
public static final Slot0Configs steerGains = new Slot0Configs()
.withKP(100.0)
.withKI(0)
.withKD(0.5)
.withKS(0.1)
.withKV(2.33)
.withKD(1.0)
.withKS(0.08)
.withKV(2.66)
.withKA(0)
.withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign);
// 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(0.1).withKI(0).withKD(0).withKS(0).withKV(0.124);
public static final Slot0Configs driveGains =
new Slot0Configs().withKP(0.08).withKI(0).withKD(0).withKS(0.05).withKV(0.124);

// The closed-loop output type to use for the steer motors;
// This affects the PID/FF gains for the steer motors
private static final ClosedLoopOutputType kSteerClosedLoopOutput = ClosedLoopOutputType.Voltage;
public static final ClosedLoopOutputType kSteerClosedLoopOutput = ClosedLoopOutputType.Voltage;
// The closed-loop output type to use for the drive motors;
// This affects the PID/FF gains for the drive motors
private static final ClosedLoopOutputType kDriveClosedLoopOutput = ClosedLoopOutputType.Voltage;
public static final ClosedLoopOutputType kDriveClosedLoopOutput = ClosedLoopOutputType.Voltage;

// The remote sensor feedback type to use for the steer motors;
// When not Pro-licensed, FusedCANcoder/SyncCANcoder automatically fall back to RemoteCANcoder
private static final SteerFeedbackType kSteerFeedbackType = SteerFeedbackType.FusedCANcoder;
public static final SteerFeedbackType kSteerFeedbackType = SteerFeedbackType.FusedCANcoder;

// The stator current at which the wheels start to slip;
// This needs to be tuned to your individual robot
private static final Current kSlipCurrent = Amps.of(120.0);
public static final Current kSlipCurrent = Amps.of(120.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()
public static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration();
public 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(Amps.of(60))
.withStatorCurrentLimitEnable(true));
private static final CANcoderConfiguration cancoderInitialConfigs = new CANcoderConfiguration();
public 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;
public static final Pigeon2Configuration pigeonConfigs = null;

// CAN bus that the devices are located on;
// All swerve devices must share the same CAN bus
public static final CANBus kCANBus = new CANBus("ChassisCanivore", "./logs/example.hoot");

// Theoretical free speed (m/s) at 12 V applied output;
// This needs to be tuned to your individual robot
public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(5.41);
public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(4.73);

// 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;
public static final double kCoupleRatio = 3.5714285714285716;

private static final double kDriveGearRatio = 5.902777777777778;
private static final double kSteerGearRatio = 18.75;
private static final Distance kWheelRadius = Inches.of(2);
public static final double kDriveGearRatio = 5.9;
public static final double kSteerGearRatio = 12.8;
public static final Distance kWheelRadius = Inches.of(2);

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

private static final int kPigeonId = 0;
public static final int kPigeonId = 0;

// These are only used for simulation
private static final MomentOfInertia kSteerInertia = KilogramSquareMeters.of(0.01);
private static final MomentOfInertia kDriveInertia = KilogramSquareMeters.of(0.01);
public static final double kSteerInertia = 0.01;
public static final double kDriveInertia = 0.01;
// Simulated voltage necessary to overcome friction
private static final Voltage kSteerFrictionVoltage = Volts.of(0.2);
private static final Voltage kDriveFrictionVoltage = Volts.of(0.2);
public static final Voltage kSteerFrictionVoltage = Volts.of(0.05);
public static final Voltage kDriveFrictionVoltage = Volts.of(0.05);

public static final SwerveDrivetrainConstants DrivetrainConstants = new SwerveDrivetrainConstants()
.withCANBusName(kCANBus.getName())
.withPigeon2Id(kPigeonId)
.withPigeon2Configs(pigeonConfigs);

private static final SwerveModuleConstantsFactory ConstantCreator = new SwerveModuleConstantsFactory()
public static final SwerveModuleConstantsFactory ConstantCreator = new SwerveModuleConstantsFactory()
.withDriveMotorGearRatio(kDriveGearRatio)
.withSteerMotorGearRatio(kSteerGearRatio)
.withCouplingGearRatio(kCoupleRatio)
Expand All @@ -125,48 +126,48 @@ public class TunerConstants {
.withDriveFrictionVoltage(kDriveFrictionVoltage);

// Front Left
private static final int kFrontLeftDriveMotorId = 5;
private static final int kFrontLeftSteerMotorId = 6;
private static final int kFrontLeftEncoderId = 11;
private static final Angle kFrontLeftEncoderOffset = Rotations.of(-0.031005859375);
private static final boolean kFrontLeftSteerMotorInverted = true;
private static final boolean kFrontLeftCANcoderInverted = false;
public static final int kFrontLeftDriveMotorId = 1;
public static final int kFrontLeftSteerMotorId = 2;
public static final int kFrontLeftEncoderId = 1;
public static final Angle kFrontLeftEncoderOffset = Rotations.of(0.30322265625);
public static final boolean kFrontLeftSteerMotorInverted = true;
public static final boolean kFrontLeftCANcoderInverted = false;

private static final Distance kFrontLeftXPos = Inches.of(10.5);
private static final Distance kFrontLeftYPos = Inches.of(10.5);
public static final Distance kFrontLeftXPos = Inches.of(10);
public static final Distance kFrontLeftYPos = Inches.of(10);

// Front Right
private static final int kFrontRightDriveMotorId = 7;
private static final int kFrontRightSteerMotorId = 8;
private static final int kFrontRightEncoderId = 12;
private static final Angle kFrontRightEncoderOffset = Rotations.of(-0.094482421875);
private static final boolean kFrontRightSteerMotorInverted = true;
private static final boolean kFrontRightCANcoderInverted = false;
public static final int kFrontRightDriveMotorId = 3;
public static final int kFrontRightSteerMotorId = 4;
public static final int kFrontRightEncoderId = 2;
public static final Angle kFrontRightEncoderOffset = Rotations.of(-0.230712890625);
public static final boolean kFrontRightSteerMotorInverted = true;
public static final boolean kFrontRightCANcoderInverted = false;

private static final Distance kFrontRightXPos = Inches.of(10.5);
private static final Distance kFrontRightYPos = Inches.of(-10.5);
public static final Distance kFrontRightXPos = Inches.of(10);
public static final Distance kFrontRightYPos = Inches.of(-10);

// Back Left
private static final int kBackLeftDriveMotorId = 1;
private static final int kBackLeftSteerMotorId = 2;
private static final int kBackLeftEncoderId = 10;
private static final Angle kBackLeftEncoderOffset = Rotations.of(-0.178955078125);
private static final boolean kBackLeftSteerMotorInverted = true;
private static final boolean kBackLeftCANcoderInverted = false;
public static final int kBackLeftDriveMotorId = 5;
public static final int kBackLeftSteerMotorId = 6;
public static final int kBackLeftEncoderId = 3;
public static final Angle kBackLeftEncoderOffset = Rotations.of(-0.221435546875);
public static final boolean kBackLeftSteerMotorInverted = true;
public static final boolean kBackLeftCANcoderInverted = false;

private static final Distance kBackLeftXPos = Inches.of(-10.5);
private static final Distance kBackLeftYPos = Inches.of(10.5);
public static final Distance kBackLeftXPos = Inches.of(-10);
public static final Distance kBackLeftYPos = Inches.of(10);

// Back Right
private static final int kBackRightDriveMotorId = 3;
private static final int kBackRightSteerMotorId = 4;
private static final int kBackRightEncoderId = 9;
private static final Angle kBackRightEncoderOffset = Rotations.of(0.48681640625);
private static final boolean kBackRightSteerMotorInverted = true;
private static final boolean kBackRightCANcoderInverted = false;
public static final int kBackRightDriveMotorId = 7;
public static final int kBackRightSteerMotorId = 8;
public static final int kBackRightEncoderId = 4;
public static final Angle kBackRightEncoderOffset = Rotations.of(-0.05419921875);
public static final boolean kBackRightSteerMotorInverted = true;
public static final boolean kBackRightCANcoderInverted = false;

private static final Distance kBackRightXPos = Inches.of(-10.5);
private static final Distance kBackRightYPos = Inches.of(-10.5);
public static final Distance kBackRightXPos = Inches.of(-10);
public static final Distance kBackRightYPos = Inches.of(-10);

public static final SwerveModuleConstants FrontLeft = ConstantCreator.createModuleConstants(
kFrontLeftSteerMotorId,
Expand Down Expand Up @@ -209,7 +210,7 @@ public class TunerConstants {
kBackRightSteerMotorInverted,
kBackRightCANcoderInverted);

// These lines must be removed:
// These must be removed:
// public static CommandSwerveDrivetrain createDrivetrain() {
// return new CommandSwerveDrivetrain(
// DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight
Expand Down
Loading

0 comments on commit 373f714

Please sign in to comment.