-
Notifications
You must be signed in to change notification settings - Fork 2
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Use Phoenix6 swervedrive for all-CTRE, YAGSL for all else?
modified: src/main/java/frc/robot/RobotContainer.java modified: src/main/java/frc/robot/commands/swervedrive/auto/AutoBalanceCommand.java modified: src/main/java/frc/robot/commands/swervedrive/drivebase/AbsoluteDrive.java modified: src/main/java/frc/robot/commands/swervedrive/drivebase/AbsoluteDriveAdv.java modified: src/main/java/frc/robot/commands/swervedrive/drivebase/AbsoluteFieldDrive.java new file: src/main/java/frc/robot/generated/TunerConstants.java new file: src/main/java/frc/robot/subsystems/swervedrive_phoenix/CommandSwerveDrivetrain.java renamed: src/main/java/frc/robot/subsystems/swervedrive/SwerveSubsystem.java -> src/main/java/frc/robot/subsystems/swervedrive_yagsl/SwerveSubsystem.java modified: src/main/java/frc/robot/util/YAGSL_AzRBSI/README modified: src/main/java/frc/robot/util/YAGSL_AzRBSI/SwerveParser_RBSI.java modified: src/main/java/frc/robot/util/YAGSL_AzRBSI/TalonFXSwerve_RBSI.java
- Loading branch information
Showing
11 changed files
with
435 additions
and
28 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,187 @@ | ||
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.mechanisms.swerve.SwerveDrivetrainConstants; | ||
import com.ctre.phoenix6.mechanisms.swerve.SwerveModule.ClosedLoopOutputType; | ||
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants; | ||
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants.SteerFeedbackType; | ||
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstantsFactory; | ||
import edu.wpi.first.math.util.Units; | ||
import frc.robot.subsystems.swervedrive_phoenix.CommandSwerveDrivetrain; | ||
|
||
// Generated by the Tuner X Swerve Project Generator | ||
// https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html | ||
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).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).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 | ||
private static final ClosedLoopOutputType steerClosedLoopOutput = 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 driveClosedLoopOutput = ClosedLoopOutputType.Voltage; | ||
|
||
// The stator current at which the wheels start to slip; | ||
// This needs to be tuned to your individual robot | ||
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 = 4.70; | ||
|
||
// 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.5; | ||
|
||
private static final double kDriveGearRatio = 7.363636364; | ||
private static final double kSteerGearRatio = 15.42857143; | ||
private static final double kWheelRadiusInches = | ||
2.167; // Estimated at first, then fudge-factored to make odom match record | ||
|
||
private static final boolean kSteerMotorReversed = true; | ||
private static final boolean kInvertLeftSide = false; | ||
private static final boolean kInvertRightSide = true; | ||
|
||
private static final String kCANbusName = "rio"; | ||
private static final int kPigeonId = 1; | ||
|
||
// These are only used for simulation | ||
private static final double kSteerInertia = 0.00001; | ||
private static final double kDriveInertia = 0.001; | ||
// Simulated voltage necessary to overcome friction | ||
private static final double kSteerFrictionVoltage = 0.25; | ||
private static final double kDriveFrictionVoltage = 0.25; | ||
|
||
private static final SwerveDrivetrainConstants DrivetrainConstants = | ||
new SwerveDrivetrainConstants() | ||
.withCANbusName(kCANbusName) | ||
.withPigeon2Id(kPigeonId) | ||
.withPigeon2Configs(pigeonConfigs); | ||
|
||
private static final SwerveModuleConstantsFactory ConstantCreator = | ||
new SwerveModuleConstantsFactory() | ||
.withDriveMotorGearRatio(kDriveGearRatio) | ||
.withSteerMotorGearRatio(kSteerGearRatio) | ||
.withWheelRadius(kWheelRadiusInches) | ||
.withSlipCurrent(kSlipCurrentA) | ||
.withSteerMotorGains(steerGains) | ||
.withDriveMotorGains(driveGains) | ||
.withSteerMotorClosedLoopOutput(steerClosedLoopOutput) | ||
.withDriveMotorClosedLoopOutput(driveClosedLoopOutput) | ||
.withSpeedAt12VoltsMps(kSpeedAt12VoltsMps) | ||
.withSteerInertia(kSteerInertia) | ||
.withDriveInertia(kDriveInertia) | ||
.withSteerFrictionVoltage(kSteerFrictionVoltage) | ||
.withDriveFrictionVoltage(kDriveFrictionVoltage) | ||
.withFeedbackSource(SteerFeedbackType.FusedCANcoder) | ||
.withCouplingGearRatio(kCoupleRatio) | ||
.withSteerMotorInverted(kSteerMotorReversed) | ||
.withDriveMotorInitialConfigs(driveInitialConfigs) | ||
.withSteerMotorInitialConfigs(steerInitialConfigs) | ||
.withCANcoderInitialConfigs(cancoderInitialConfigs); | ||
|
||
// Front Left | ||
private static final int kFrontLeftDriveMotorId = 5; | ||
private static final int kFrontLeftSteerMotorId = 4; | ||
private static final int kFrontLeftEncoderId = 2; | ||
private static final double kFrontLeftEncoderOffset = -0.83544921875; | ||
|
||
private static final double kFrontLeftXPosInches = 10.5; | ||
private static final double kFrontLeftYPosInches = 10.5; | ||
|
||
// Front Right | ||
private static final int kFrontRightDriveMotorId = 7; | ||
private static final int kFrontRightSteerMotorId = 6; | ||
private static final int kFrontRightEncoderId = 3; | ||
private static final double kFrontRightEncoderOffset = -0.15234375; | ||
|
||
private static final double kFrontRightXPosInches = 10.5; | ||
private static final double kFrontRightYPosInches = -10.5; | ||
|
||
// Back Left | ||
private static final int kBackLeftDriveMotorId = 1; | ||
private static final int kBackLeftSteerMotorId = 0; | ||
private static final int kBackLeftEncoderId = 0; | ||
private static final double kBackLeftEncoderOffset = -0.4794921875; | ||
|
||
private static final double kBackLeftXPosInches = -10.5; | ||
private static final double kBackLeftYPosInches = 10.5; | ||
|
||
// Back Right | ||
private static final int kBackRightDriveMotorId = 3; | ||
private static final int kBackRightSteerMotorId = 2; | ||
private static final int kBackRightEncoderId = 1; | ||
private static final double kBackRightEncoderOffset = -0.84130859375; | ||
|
||
private static final double kBackRightXPosInches = -10.5; | ||
private static final double kBackRightYPosInches = -10.5; | ||
|
||
private static final SwerveModuleConstants FrontLeft = | ||
ConstantCreator.createModuleConstants( | ||
kFrontLeftSteerMotorId, | ||
kFrontLeftDriveMotorId, | ||
kFrontLeftEncoderId, | ||
kFrontLeftEncoderOffset, | ||
Units.inchesToMeters(kFrontLeftXPosInches), | ||
Units.inchesToMeters(kFrontLeftYPosInches), | ||
kInvertLeftSide); | ||
private static final SwerveModuleConstants FrontRight = | ||
ConstantCreator.createModuleConstants( | ||
kFrontRightSteerMotorId, | ||
kFrontRightDriveMotorId, | ||
kFrontRightEncoderId, | ||
kFrontRightEncoderOffset, | ||
Units.inchesToMeters(kFrontRightXPosInches), | ||
Units.inchesToMeters(kFrontRightYPosInches), | ||
kInvertRightSide); | ||
private static final SwerveModuleConstants BackLeft = | ||
ConstantCreator.createModuleConstants( | ||
kBackLeftSteerMotorId, | ||
kBackLeftDriveMotorId, | ||
kBackLeftEncoderId, | ||
kBackLeftEncoderOffset, | ||
Units.inchesToMeters(kBackLeftXPosInches), | ||
Units.inchesToMeters(kBackLeftYPosInches), | ||
kInvertLeftSide); | ||
private static final SwerveModuleConstants BackRight = | ||
ConstantCreator.createModuleConstants( | ||
kBackRightSteerMotorId, | ||
kBackRightDriveMotorId, | ||
kBackRightEncoderId, | ||
kBackRightEncoderOffset, | ||
Units.inchesToMeters(kBackRightXPosInches), | ||
Units.inchesToMeters(kBackRightYPosInches), | ||
kInvertRightSide); | ||
|
||
public static final CommandSwerveDrivetrain DriveTrain = | ||
new CommandSwerveDrivetrain(DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight); | ||
} |
Oops, something went wrong.