diff --git a/templates/CTRE Swerve with maple-sim/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java b/templates/CTRE Swerve with maple-sim/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java index bfd8cbb..8e3ee20 100644 --- a/templates/CTRE Swerve with maple-sim/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java +++ b/templates/CTRE Swerve with maple-sim/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java @@ -270,7 +270,7 @@ public void periodic() { private void startSimThread() { mapleSimSwerveDrivetrain = new MapleSimSwerveDrivetrain( - kSimLoopPeriod, + Seconds.of(kSimLoopPeriod), Pounds.of(115), Inches.of(30), Inches.of(30), diff --git a/templates/CTRE Swerve with maple-sim/src/main/java/frc/robot/utils/simulation/MapleSimSwerveDrivetrain.java b/templates/CTRE Swerve with maple-sim/src/main/java/frc/robot/utils/simulation/MapleSimSwerveDrivetrain.java index 5220cde..b847a9b 100644 --- a/templates/CTRE Swerve with maple-sim/src/main/java/frc/robot/utils/simulation/MapleSimSwerveDrivetrain.java +++ b/templates/CTRE Swerve with maple-sim/src/main/java/frc/robot/utils/simulation/MapleSimSwerveDrivetrain.java @@ -1,11 +1,9 @@ package frc.robot.utils.simulation; -/* - * Copyright (C) Cross The Road Electronics.  All rights reserved. - * License information can be found in CTRE_LICENSE.txt - * For support and suggestions contact support@ctr-electronics.com or file - * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases - */ +// Copyright 2021-2025 Iron Maple 5516 +// Original Source: https://github.com/Shenzhen-Robotics-Alliance/maple-sim/blob/main/templates/CTRE%20Swerve%20with%20maple-sim/src/main/java/frc/robot/utils/simulation/MapleSimSwerveDrivetrain.java +// +// This code is licensed under MIT license (see https://mit-license.org/) import static edu.wpi.first.units.Units.*; @@ -17,6 +15,7 @@ import com.ctre.phoenix6.sim.CANcoderSimState; import com.ctre.phoenix6.sim.Pigeon2SimState; import com.ctre.phoenix6.sim.TalonFXSimState; +import com.ctre.phoenix6.swerve.SwerveDrivetrain; import com.ctre.phoenix6.swerve.SwerveModule; import com.ctre.phoenix6.swerve.SwerveModuleConstants; import edu.wpi.first.math.geometry.Pose2d; @@ -33,13 +32,35 @@ import org.ironmaple.simulation.motorsims.SimulatedBattery; import org.ironmaple.simulation.motorsims.SimulatedMotorController; +/** + *

Injects Maple-Sim simulation data into a CTRE swerve drivetrain.

+ * + *

This class retrieves simulation data from Maple-Sim and injects it into the CTRE {@link com.ctre.phoenix6.swerve.SwerveDrivetrain} instance.

+ * + *

It replaces the {@link com.ctre.phoenix6.swerve.SimSwerveDrivetrain} class.

+ */ public class MapleSimSwerveDrivetrain { private final Pigeon2SimState pigeonSim; private final SimSwerveModule[] simModules; public final SwerveDriveSimulation mapleSimDrive; + /** + *

Constructs a drivetrain simulation using the specified parameters.

+ * + * @param simPeriod the time period of the simulation + * @param robotMassWithBumpers the total mass of the robot, including bumpers + * @param bumperLengthX the length of the bumper along the X-axis (influences the collision space of the robot) + * @param bumperWidthY the width of the bumper along the Y-axis (influences the collision space of the robot) + * @param driveMotorModel the {@link DCMotor} model for the drive motor, typically DCMotor.getKrakenX60Foc() + * @param steerMotorModel the {@link DCMotor} model for the steer motor, typically DCMotor.getKrakenX60Foc() + * @param wheelCOF the coefficient of friction of the drive wheels + * @param moduleLocations the locations of the swerve modules on the robot, in the order FL, FR, BL, BR + * @param pigeon the {@link Pigeon2} IMU used in the drivetrain + * @param modules the {@link SwerveModule}s, typically obtained via {@link SwerveDrivetrain#getModules()} + * @param moduleConstants the constants for the swerve modules + */ public MapleSimSwerveDrivetrain( - double simPeriodSeconds, + Time simPeriod, Mass robotMassWithBumpers, Distance bumperLengthX, Distance bumperWidthY, @@ -74,16 +95,17 @@ public MapleSimSwerveDrivetrain( for (int i = 0; i < this.simModules.length; i++) simModules[i] = new SimSwerveModule(moduleConstants[0], moduleSimulations[i], modules[i]); - SimulatedArena.overrideSimulationTimings(Seconds.of(simPeriodSeconds), 1); + SimulatedArena.overrideSimulationTimings(simPeriod, 1); SimulatedArena.getInstance().addDriveTrainSimulation(mapleSimDrive); } /** - * Update this simulation for the time duration. + *

Update the simulation.

* - *

This performs a simulation update on all the simulated devices + *

Updates the Maple-Sim simulation and injects the results into the simulated CTRE devices, + * including motors and the IMU.

*/ - public final void update() { + public void update() { SimulatedArena.getInstance().simulationPeriodic(); pigeonSim.setRawYaw( mapleSimDrive.getSimulatedDriveTrainPose().getRotation().getMeasure()); @@ -91,6 +113,9 @@ public final void update() { mapleSimDrive.getDriveTrainSimulatedChassisSpeedsRobotRelative().omegaRadiansPerSecond)); } + /** + *

Represents the simulation of a single {@link SwerveModule}.

+ */ protected static class SimSwerveModule { public final SwerveModuleConstants moduleConstant; @@ -108,6 +133,7 @@ public SimSwerveModule( } } + // Static utils classes public static class TalonFXMotorControllerSim implements SimulatedMotorController { public final int id; @@ -157,6 +183,14 @@ public Voltage updateControlSignal( } } + /** + *

Regulates all {@link SwerveModuleConstants} for a drivetrain simulation.

+ * + *

This method processes an array of {@link SwerveModuleConstants} to apply necessary adjustments + * for simulation purposes, ensuring compatibility and avoiding known bugs.

+ * + * @see #regulateModuleConstantForSimulation(SwerveModuleConstants) + */ public static SwerveModuleConstants[] regulateModuleConstantsForSimulation( SwerveModuleConstants[] moduleConstants) { for (SwerveModuleConstants moduleConstant : moduleConstants) @@ -165,17 +199,42 @@ public Voltage updateControlSignal( return moduleConstants; } + /** + *

Regulates the {@link SwerveModuleConstants} for a single module.

+ * + *

This method applies specific adjustments to the {@link SwerveModuleConstants} for simulation + * purposes. These changes have no effect on real robot operations and address known simulation bugs:

+ * + * + * + *

Note:This function is skipped when running on a real robot, ensuring no impact on constants used on real robot hardware.

+ */ private static void regulateModuleConstantForSimulation(SwerveModuleConstants moduleConstants) { + // Skip regulation if running on a real robot if (RobotBase.isReal()) return; + // Apply simulation-specific adjustments to module constants moduleConstants + // Disable encoder offsets .withEncoderOffset(0) + // Disable motor inversions for drive and steer motors .withDriveMotorInverted(false) .withSteerMotorInverted(false) + // Disable CanCoder inversion .withEncoderInverted(false) - .withSteerMotorGains(moduleConstants.SteerMotorGains.withKP(70).withKD(4.5)) + // Adjust steer motor PID gains for simulation + .withSteerMotorGains(moduleConstants.SteerMotorGains + .withKP(70) // Proportional gain + .withKD(4.5)) // Derivative gain + // Adjust friction voltages .withDriveFrictionVoltage(Volts.of(0.1)) .withSteerFrictionVoltage(Volts.of(0.15)) + // Adjust steer inertia .withSteerInertia(KilogramSquareMeters.of(0.05)); } + }