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; +/** + *
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; + /** + *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.
+ * 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)); } + /** + *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; } + /** + *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:
+ * + *