Skip to content

Commit

Permalink
added javadocs for maple sim drivetrain
Browse files Browse the repository at this point in the history
  • Loading branch information
catr1xLiu committed Jan 12, 2025
1 parent b27243d commit 5cb5d00
Show file tree
Hide file tree
Showing 2 changed files with 72 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
Original file line number Diff line number Diff line change
@@ -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.*;

Expand All @@ -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;
Expand All @@ -33,13 +32,35 @@
import org.ironmaple.simulation.motorsims.SimulatedBattery;
import org.ironmaple.simulation.motorsims.SimulatedMotorController;

/**
* <h2>Injects Maple-Sim simulation data into a CTRE swerve drivetrain.</h2>
*
* <p>This class retrieves simulation data from Maple-Sim and injects it into the CTRE {@link com.ctre.phoenix6.swerve.SwerveDrivetrain} instance.</p>
*
* <p>It replaces the {@link com.ctre.phoenix6.swerve.SimSwerveDrivetrain} class.</p>
*/
public class MapleSimSwerveDrivetrain {
private final Pigeon2SimState pigeonSim;
private final SimSwerveModule[] simModules;
public final SwerveDriveSimulation mapleSimDrive;

/**
* <h2>Constructs a drivetrain simulation using the specified parameters.</h2>
*
* @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 <code>DCMotor.getKrakenX60Foc()</code>
* @param steerMotorModel the {@link DCMotor} model for the steer motor, typically <code>DCMotor.getKrakenX60Foc()</code>
* @param wheelCOF the coefficient of friction of the drive wheels
* @param moduleLocations the locations of the swerve modules on the robot, in the order <code>FL, FR, BL, BR</code>
* @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,
Expand Down Expand Up @@ -74,23 +95,27 @@ 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.
* <h2>Update the simulation.</h2>
*
* <p>This performs a simulation update on all the simulated devices
* <p>Updates the Maple-Sim simulation and injects the results into the simulated CTRE devices,
* including motors and the IMU.</p>
*/
public final void update() {
public void update() {
SimulatedArena.getInstance().simulationPeriodic();
pigeonSim.setRawYaw(
mapleSimDrive.getSimulatedDriveTrainPose().getRotation().getMeasure());
pigeonSim.setAngularVelocityZ(RadiansPerSecond.of(
mapleSimDrive.getDriveTrainSimulatedChassisSpeedsRobotRelative().omegaRadiansPerSecond));
}

/**
* <h1>Represents the simulation of a single {@link SwerveModule}.</h1>
*/
protected static class SimSwerveModule {
public final SwerveModuleConstants<TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration>
moduleConstant;
Expand All @@ -108,6 +133,7 @@ public SimSwerveModule(
}
}

// Static utils classes
public static class TalonFXMotorControllerSim implements SimulatedMotorController {
public final int id;

Expand Down Expand Up @@ -157,6 +183,14 @@ public Voltage updateControlSignal(
}
}

/**
* <h2>Regulates all {@link SwerveModuleConstants} for a drivetrain simulation.</h2>
*
* <p>This method processes an array of {@link SwerveModuleConstants} to apply necessary adjustments
* for simulation purposes, ensuring compatibility and avoiding known bugs.</p>
*
* @see #regulateModuleConstantForSimulation(SwerveModuleConstants)
*/
public static SwerveModuleConstants<?, ?, ?>[] regulateModuleConstantsForSimulation(
SwerveModuleConstants<?, ?, ?>[] moduleConstants) {
for (SwerveModuleConstants<?, ?, ?> moduleConstant : moduleConstants)
Expand All @@ -165,17 +199,42 @@ public Voltage updateControlSignal(
return moduleConstants;
}

/**
* <h2>Regulates the {@link SwerveModuleConstants} for a single module.</h2>
*
* <p>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:</p>
*
* <ul>
* <li><strong>Inverted Drive Motors:</strong> Prevents drive PID issues caused by inverted configurations.</li>
* <li><strong>Non-zero CanCoder Offsets:</strong> Fixes potential module state optimization issues.</li>
* <li><strong>Steer Motor PID:</strong> Adjusts PID values tuned for real robots to improve simulation performance.</li>
* </ul>
*
* <h4>Note:This function is skipped when running on a real robot, ensuring no impact on constants used on real robot hardware.</h4>
*/
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));
}

}

0 comments on commit 5cb5d00

Please sign in to comment.