Upgrading to 2025.7.0

This commit is contained in:
thenetworkgrinch
2025-02-22 06:15:56 +00:00
parent 62f8236678
commit 4016ee2190
41 changed files with 2237 additions and 557 deletions

View File

@@ -6,6 +6,7 @@ import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import org.ironmaple.simulation.drivesims.SelfControlledSwerveDriveSimulation;
import swervelib.SwerveDrive;
import swervelib.parser.SwerveModulePhysicalCharacteristics;
/**
@@ -14,12 +15,16 @@ import swervelib.parser.SwerveModulePhysicalCharacteristics;
public class SwerveModuleSimulation
{
private SelfControlledSwerveDriveSimulation.SelfControlledModuleSimulation mapleSimModule = null;
/**
* MapleSim module.
*/
public SelfControlledSwerveDriveSimulation.SelfControlledModuleSimulation mapleSimModule = null;
/**
* Configure the maple sim module
*
* @param simModule the {@link org.ironmaple.simulation.drivesims.SwerveModuleSimulation} object for simulation
* @param simModule the {@link org.ironmaple.simulation.drivesims.SwerveModuleSimulation} object for
* simulation
* @param physicalCharacteristics Physical characteristics of the swerve drive from the JSON or built.
*/
public void configureSimModule(org.ironmaple.simulation.drivesims.SwerveModuleSimulation simModule,
@@ -42,6 +47,31 @@ public class SwerveModuleSimulation
mapleSimModule.runModuleState(desiredState);
}
/**
* Runs a drive motor characterization on the sim module. This is called from
* {@link swervelib.SwerveDriveTest#runDriveMotorsCharacterizationOnSimModules(SwerveDrive, double, boolean)} to run
* sysId during simulation
*
* @param desiredFacing the desired facing of the module
* @param volts the voltage to run
*/
public void runDriveMotorCharacterization(Rotation2d desiredFacing, double volts)
{
mapleSimModule.runDriveMotorCharacterization(desiredFacing, volts);
}
/**
* Runs a drive motor characterization on the sim module. This method is called from
* {@link swervelib.SwerveDriveTest#runAngleMotorsCharacterizationOnSimModules(SwerveDrive, double)} to run sysId
* during simulation
*
* @param volts the voltage to run
*/
public void runAngleMotorCharacterization(double volts)
{
mapleSimModule.runSteerMotorCharacterization(volts);
}
/**
* Get the simulated swerve module position.
*