Skip to content

Commit

Permalink
upgraded phoenix version to 2025
Browse files Browse the repository at this point in the history
  • Loading branch information
catr1xLiu committed Nov 28, 2024
1 parent d6ddcff commit 80d56cf
Show file tree
Hide file tree
Showing 2 changed files with 105 additions and 77 deletions.
105 changes: 58 additions & 47 deletions src/main/java/frc/robot/constants/TunerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
import com.ctre.phoenix6.configs.Pigeon2Configuration;
import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.signals.StaticFeedforwardSignValue;
import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants;
import com.ctre.phoenix6.swerve.SwerveModuleConstants;
import com.ctre.phoenix6.swerve.SwerveModuleConstants.ClosedLoopOutputType;
Expand All @@ -25,8 +26,8 @@
/**
* For CTRE Chassis, generate this file using the Tuner
*
* <p>TODO: after generated, you MUST replace all "public" labels with "public" (do it with the replace function of your
* IDE)
* <p>TODO: after generated, you MUST replace all "private" labels with "public" (do it with the replace function of
* your IDE)
*
* <p>TODO: you MUST delete the last two lines of this file
*
Expand All @@ -38,16 +39,17 @@ public class TunerConstants {
// The steer motor uses any SwerveModule.SteerRequestType control request with the
// output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput
public static final Slot0Configs steerGains = new Slot0Configs()
.withKP(100)
.withKP(100.0)
.withKI(0)
.withKD(2.0)
.withKS(0.2)
.withKV(1.5)
.withKA(0);
.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
public static final Slot0Configs driveGains =
new Slot0Configs().withKP(0.1).withKI(0).withKD(0).withKS(0).withKV(0.12);
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
Expand Down Expand Up @@ -77,23 +79,26 @@ public class TunerConstants {
// Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs
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(4.70);
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
public static final double kCoupleRatio = 3.5;
public static final double kCoupleRatio = 3.5714285714285716;

public static final double kDriveGearRatio = 7.363636364;
public static final double kSteerGearRatio = 12.8;
public static final Distance kWheelRadius = Inches.of(2.167);
public static final double kDriveGearRatio = 6.746031746031747;
public static final double kSteerGearRatio = 21.428571428571427;
public static final Distance kWheelRadius = Inches.of(2);

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

public static final CANBus kCANBus = new CANBus("rio", "./logs/example.hoot");
public static final int kPigeonId = 1;
public static final int kPigeonId = 0;

// These are only used for simulation
public static final double kSteerInertia = 0.01;
Expand Down Expand Up @@ -128,44 +133,48 @@ public class TunerConstants {
.withDriveFrictionVoltage(kDriveFrictionVoltage);

// Front Left
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.305419921875);
public static final int kFrontLeftDriveMotorId = 3;
public static final int kFrontLeftSteerMotorId = 4;
public static final int kFrontLeftEncoderId = 10;
public static final Angle kFrontLeftEncoderOffset = Rotations.of(0.4677734375);
public static final boolean kFrontLeftSteerMotorInverted = true;
public static final boolean kFrontLeftCANcoderInverted = false;

public static final Distance kFrontLeftXPos = Inches.of(10.5);
public 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
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 int kFrontRightDriveMotorId = 6;
public static final int kFrontRightSteerMotorId = 5;
public static final int kFrontRightEncoderId = 11;
public static final Angle kFrontRightEncoderOffset = Rotations.of(-0.792724609375);
public static final boolean kFrontRightSteerMotorInverted = true;
public static final boolean kFrontRightCANcoderInverted = false;

public static final Distance kFrontRightXPos = Inches.of(10.5);
public 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
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 int kBackLeftDriveMotorId = 1;
public static final int kBackLeftSteerMotorId = 2;
public static final int kBackLeftEncoderId = 9;
public static final Angle kBackLeftEncoderOffset = Rotations.of(-0.047607421875);
public static final boolean kBackLeftSteerMotorInverted = true;
public static final boolean kBackLeftCANcoderInverted = false;

public static final Distance kBackLeftXPos = Inches.of(-10.5);
public 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
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 int kBackRightDriveMotorId = 8;
public static final int kBackRightSteerMotorId = 7;
public static final int kBackRightEncoderId = 12;
public static final Angle kBackRightEncoderOffset = Rotations.of(-0.513671875);
public static final boolean kBackRightSteerMotorInverted = true;
public static final boolean kBackRightCANcoderInverted = false;

public static final Distance kBackRightXPos = Inches.of(-10.5);
public 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 All @@ -175,7 +184,8 @@ public class TunerConstants {
kFrontLeftXPos,
kFrontLeftYPos,
kInvertLeftSide,
kFrontLeftSteerMotorInverted);
kFrontLeftSteerMotorInverted,
kFrontLeftCANcoderInverted);
public static final SwerveModuleConstants FrontRight = ConstantCreator.createModuleConstants(
kFrontRightSteerMotorId,
kFrontRightDriveMotorId,
Expand All @@ -184,7 +194,8 @@ public class TunerConstants {
kFrontRightXPos,
kFrontRightYPos,
kInvertRightSide,
kFrontRightSteerMotorInverted);
kFrontRightSteerMotorInverted,
kFrontRightCANcoderInverted);
public static final SwerveModuleConstants BackLeft = ConstantCreator.createModuleConstants(
kBackLeftSteerMotorId,
kBackLeftDriveMotorId,
Expand All @@ -193,7 +204,8 @@ public class TunerConstants {
kBackLeftXPos,
kBackLeftYPos,
kInvertLeftSide,
kBackLeftSteerMotorInverted);
kBackLeftSteerMotorInverted,
kBackLeftCANcoderInverted);
public static final SwerveModuleConstants BackRight = ConstantCreator.createModuleConstants(
kBackRightSteerMotorId,
kBackRightDriveMotorId,
Expand All @@ -202,12 +214,11 @@ public class TunerConstants {
kBackRightXPos,
kBackRightYPos,
kInvertRightSide,
kBackRightSteerMotorInverted);
kBackRightSteerMotorInverted,
kBackRightCANcoderInverted);

// These must be removed:
// TODO: these two lines should be removed:
// public static CommandSwerveDrivetrain createDrivetrain() {
// return new CommandSwerveDrivetrain(
// DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight
// );
// return new CommandSwerveDrivetrain(DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight);
// }
}
Loading

0 comments on commit 80d56cf

Please sign in to comment.