From b67746aa3c7f1ee8a3abbb966bd5eca4db5f9280 Mon Sep 17 00:00:00 2001 From: MadMath123 Date: Tue, 4 Feb 2025 16:05:40 -0500 Subject: [PATCH] add module as input for krakensim motors. should be the same process for neo; will not be too bad (hopefully) when we get kraken working. --- .../drive/swerve/SwerveModuleKraken.kt | 8 +++- .../drive/swerve/sim/SwerveModuleKrakenSim.kt | 37 +++++++++++-------- 2 files changed, 29 insertions(+), 16 deletions(-) diff --git a/src/main/kotlin/frc/team449/subsystems/drive/swerve/SwerveModuleKraken.kt b/src/main/kotlin/frc/team449/subsystems/drive/swerve/SwerveModuleKraken.kt index f182d85..14a9f00 100644 --- a/src/main/kotlin/frc/team449/subsystems/drive/swerve/SwerveModuleKraken.kt +++ b/src/main/kotlin/frc/team449/subsystems/drive/swerve/SwerveModuleKraken.kt @@ -14,6 +14,8 @@ import frc.team449.system.encoder.AbsoluteEncoder import frc.team449.system.encoder.Encoder import frc.team449.system.motor.createKraken import frc.team449.system.motor.createSparkMax +import frc.team449.subsystems.drive.swerve.sim.SwerveModuleKrakenSim +import frc.team449.subsystems.drive.swerve.sim.SwerveModuleNEOSim import kotlin.math.PI import kotlin.math.abs import kotlin.math.sign @@ -171,7 +173,7 @@ open class SwerveModuleKraken( location ) } else { - return SwerveModuleSimKraken( + return SwerveModuleSimKraken( //what is this?! nvm name, drivingMotor, turnMotor, @@ -184,6 +186,10 @@ open class SwerveModuleKraken( } } + + +/** A "simulated" swerve module. Immediately reaches to its desired state. */ + /** A "simulated" swerve module. Immediately reaches to its desired state. */ class SwerveModuleSimKraken( name: String, diff --git a/src/main/kotlin/frc/team449/subsystems/drive/swerve/sim/SwerveModuleKrakenSim.kt b/src/main/kotlin/frc/team449/subsystems/drive/swerve/sim/SwerveModuleKrakenSim.kt index c4a0432..4c5744d 100644 --- a/src/main/kotlin/frc/team449/subsystems/drive/swerve/sim/SwerveModuleKrakenSim.kt +++ b/src/main/kotlin/frc/team449/subsystems/drive/swerve/sim/SwerveModuleKrakenSim.kt @@ -12,10 +12,9 @@ import org.ironmaple.simulation.drivesims.SwerveModuleSimulation import org.ironmaple.simulation.drivesims.configs.SwerveModuleSimulationConfig import org.ironmaple.simulation.motorsims.SimulatedMotorController -abstract class SwerveModuleKrakenSim: SwerveModule { - - - val module: SwerveModuleSimulation = SwerveModuleSimulation( +class SwerveModuleKrakenSim(name: String, moduleIn: SwerveModuleSimulation, locationIn: Translation2d) : SwerveModule { + override val location: Translation2d = locationIn + public val module: SwerveModuleSimulation = moduleIn/* = SwerveModuleSimulation( SwerveModuleSimulationConfig( DCMotor.getKrakenX60(1), DCMotor.getKrakenX60(1), @@ -27,29 +26,37 @@ abstract class SwerveModuleKrakenSim: SwerveModule { SwerveConstants.STEER_ROTATIONAL_INERTIA, SwerveConstants.WHEEL_COEFFICIENT_OF_FRICTION ) - ) + )*/ - val drive: SimulatedMotorController.GenericMotorController = module - .useGenericMotorControllerForDrive() - .withCurrentLimit(SwerveConstants.DRIVE_FOC_CURRENT_LIMIT) + val drive: SimulatedMotorController.GenericMotorController + val turn: SimulatedMotorController.GenericMotorController - val turn: SimulatedMotorController.GenericMotorController = module - .useGenericControllerForSteer() - .withCurrentLimit(SwerveConstants.STEERING_CURRENT_LIM) + init { + drive = module + .useGenericMotorControllerForDrive() + .withCurrentLimit(SwerveConstants.DRIVE_FOC_CURRENT_LIMIT) + turn = module + .useGenericControllerForSteer() + .withCurrentLimit(SwerveConstants.STEERING_CURRENT_LIM) + } - override val location: Translation2d = Translation2d( + /*override val location: Translation2d = Translation2d( 0.0,0.0 - ) + );*/ override val desiredState: SwerveModuleState = SwerveModuleState( 0.0, Rotation2d() - ) + ); /** The module's [SwerveModuleState], containing speed and angle. */ override var state: SwerveModuleState get() = module.currentState - set(value) {} + set(value) { + module.currentState.angle = value.angle; + module.currentState.speedMetersPerSecond = value.speedMetersPerSecond; + } + /** The module's [SwerveModulePosition], containing distance and angle. */ override val position: SwerveModulePosition