Skip to content

Commit

Permalink
adapted to newest version of maple-sim
Browse files Browse the repository at this point in the history
  • Loading branch information
catr1xLiu committed Nov 19, 2024
1 parent 62e1c1c commit f3c63f9
Show file tree
Hide file tree
Showing 5 changed files with 36 additions and 34 deletions.
16 changes: 8 additions & 8 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@

package frc.robot;

import static edu.wpi.first.units.Units.*;

import com.pathplanner.lib.auto.NamedCommands;
import com.pathplanner.lib.commands.PathPlannerAuto;
import edu.wpi.first.math.geometry.Pose2d;
Expand Down Expand Up @@ -120,14 +118,16 @@ public RobotContainer() {
.withSwerveModule(() -> new SwerveModuleSimulation(
DriveTrainConstants.DRIVE_MOTOR,
DriveTrainConstants.STEER_MOTOR,
DriveTrainConstants.DRIVE_CURRENT_LIMIT.in(Amps),
DriveTrainConstants.DRIVE_GEAR_RATIO,
DriveTrainConstants.STEER_GEAR_RATIO,
DriveTrainConstants.DRIVE_FRICTION_VOLTAGE.in(Volts),
DriveTrainConstants.STEER_FRICTION_VOLTAGE.in(Volts),
DriveTrainConstants.WHEEL_COEFFICIENT_OF_FRICTION,
DriveTrainConstants.WHEEL_RADIUS.in(Meters),
DriveTrainConstants.STEER_INERTIA.in(KilogramSquareMeters))),
DriveTrainConstants.DRIVE_CURRENT_LIMIT,
DriveTrainConstants.STEER_CURRENT_LIMIT,
DriveTrainConstants.DRIVE_FRICTION_VOLTAGE,
DriveTrainConstants.STEER_FRICTION_VOLTAGE,
DriveTrainConstants.WHEEL_RADIUS,
DriveTrainConstants.STEER_INERTIA,
DriveTrainConstants.WHEEL_COEFFICIENT_OF_FRICTION))
.withGyro(DriveTrainConstants.gyroSimulationFactory),
new Pose2d(3, 3, new Rotation2d()));
SimulatedArena.getInstance().addDriveTrainSimulation(driveSimulation);

Expand Down
9 changes: 2 additions & 7 deletions src/main/java/frc/robot/constants/DriveTrainConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
*/
public class DriveTrainConstants {
/** numbers that needs to be changed to fit each robot TODO: change these numbers to match your robot */
public static final double WHEEL_COEFFICIENT_OF_FRICTION = 1.2;
public static final double WHEEL_COEFFICIENT_OF_FRICTION = 1.05;

public static final Mass ROBOT_MASS = Kilograms.of(45); // robot weight with bumpers

Expand All @@ -37,7 +37,7 @@ public class DriveTrainConstants {
public static final MomentOfInertia STEER_INERTIA = KilogramSquareMeters.of(0.025);

/* adjust current limit */
public static final Current DRIVE_CURRENT_LIMIT = Amps.of(60);
public static final Current DRIVE_CURRENT_LIMIT = Amps.of(80);
public static final Current STEER_CURRENT_LIMIT = Amps.of(20);

/** translations of the modules to the robot center, in FL, FR, BL, BR */
Expand Down Expand Up @@ -95,11 +95,6 @@ public class DriveTrainConstants {
* (BUMPER_WIDTH.in(Meters) * BUMPER_WIDTH.in(Meters) + BUMPER_LENGTH.in(Meters) * BUMPER_LENGTH.in(Meters))
/ 12.0);

/* https://en.wikipedia.org/wiki/Friction#Coefficient_of_friction */
public static final double BUMPER_COEFFICIENT_OF_FRICTION = 0.65;
/* https://simple.wikipedia.org/wiki/Coefficient_of_restitution */
public static final double BUMPER_COEFFICIENT_OF_RESTITUTION = 0.08;

public static final Supplier<GyroSimulation> gyroSimulationFactory = GyroSimulation.getPigeon2();

/* dead configs, don't change them */
Expand Down
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/subsystems/drive/IO/GyroIOSim.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
package frc.robot.subsystems.drive.IO;

import static edu.wpi.first.units.Units.RadiansPerSecond;

import org.ironmaple.simulation.drivesims.GyroSimulation;

public class GyroIOSim implements GyroIO {
Expand All @@ -14,6 +16,7 @@ public void updateInputs(GyroIOInputs inputs) {
inputs.connected = true;
inputs.odometryYawPositions = gyroSimulation.getCachedGyroReadings();
inputs.yawPosition = gyroSimulation.getGyroReading();
inputs.yawVelocityRadPerSec = gyroSimulation.getMeasuredAngularVelocityRadPerSec();
inputs.yawVelocityRadPerSec =
gyroSimulation.getMeasuredAngularVelocity().in(RadiansPerSecond);
}
}
28 changes: 16 additions & 12 deletions src/main/java/frc/robot/subsystems/drive/IO/ModuleIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,8 @@

package frc.robot.subsystems.drive.IO;

import static edu.wpi.first.units.Units.Volts;
import static edu.wpi.first.units.Units.*;

import edu.wpi.first.math.util.Units;
import java.util.Arrays;
import org.ironmaple.simulation.drivesims.SwerveModuleSimulation;
import org.ironmaple.simulation.motorsims.ControlRequest;
Expand All @@ -27,21 +26,26 @@ public ModuleIOSim(SwerveModuleSimulation moduleSimulation) {

@Override
public void updateInputs(ModuleIOInputs inputs) {
inputs.driveWheelFinalRevolutions = Units.radiansToRotations(moduleSimulation.getDriveWheelFinalPositionRad());
inputs.driveWheelFinalRevolutions =
moduleSimulation.getDriveWheelFinalPosition().in(Revolutions);
inputs.driveWheelFinalVelocityRevolutionsPerSec =
Units.radiansToRotations(moduleSimulation.getDriveWheelFinalSpeedRadPerSec());
inputs.driveMotorAppliedVolts = moduleSimulation.getDriveMotorAppliedVolts();
inputs.driveMotorCurrentAmps = moduleSimulation.getDriveMotorSupplyCurrentAmps();
moduleSimulation.getDriveWheelFinalSpeed().in(RevolutionsPerSecond);
inputs.driveMotorAppliedVolts =
moduleSimulation.getDriveMotorAppliedVoltage().in(Volts);
inputs.driveMotorCurrentAmps =
moduleSimulation.getDriveMotorStatorCurrent().in(Amps);

inputs.steerFacing = moduleSimulation.getSteerAbsoluteFacing();
inputs.steerVelocityRadPerSec = moduleSimulation.getSteerAbsoluteEncoderSpeedRadPerSec();
inputs.steerMotorAppliedVolts = moduleSimulation.getSteerMotorAppliedVolts();
inputs.steerMotorCurrentAmps = moduleSimulation.getSteerMotorSupplyCurrentAmps();
inputs.steerVelocityRadPerSec =
moduleSimulation.getSteerAbsoluteEncoderSpeed().in(RadiansPerSecond);
inputs.steerMotorAppliedVolts =
moduleSimulation.getSteerMotorAppliedVoltage().in(Volts);
inputs.steerMotorCurrentAmps =
moduleSimulation.getSteerMotorStatorCurrent().in(Amps);

inputs.odometryDriveWheelRevolutions = Arrays.stream(moduleSimulation.getCachedDriveWheelFinalPositionsRad())
.map(Units::radiansToRotations)
inputs.odometryDriveWheelRevolutions = Arrays.stream(moduleSimulation.getCachedDriveWheelFinalPositions())
.mapToDouble(angle -> angle.in(Revolutions))
.toArray();

inputs.odometrySteerPositions = moduleSimulation.getCachedSteerAbsolutePositions();

inputs.hardwareConnected = true;
Expand Down
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/subsystems/drive/IO/ModuleIOTalon.java
Original file line number Diff line number Diff line change
Expand Up @@ -49,15 +49,15 @@ public ModuleIOTalon(
cancoder = new CANcoder(moduleConstants.CANcoderId, drivetrainConstants.CANbusName);

var driveConfig = moduleConstants.DriveMotorInitialConfigs;
driveConfig.CurrentLimits.SupplyCurrentLimit = DRIVE_CURRENT_LIMIT.in(Amps);
driveConfig.CurrentLimits.SupplyCurrentLimitEnable = true;
driveConfig.CurrentLimits.StatorCurrentLimit = DRIVE_CURRENT_LIMIT.in(Amps);
driveConfig.CurrentLimits.StatorCurrentLimitEnable = true;
driveTalon.getConfigurator().apply(driveConfig);
driveTalon.setInverted(moduleConstants.DriveMotorInverted);
setDriveBrake(true);

var steerConfig = moduleConstants.SteerMotorInitialConfigs;
steerConfig.CurrentLimits.SupplyCurrentLimit = STEER_CURRENT_LIMIT.in(Amps);
steerConfig.CurrentLimits.SupplyCurrentLimitEnable = true;
steerConfig.CurrentLimits.StatorCurrentLimit = STEER_CURRENT_LIMIT.in(Amps);
steerConfig.CurrentLimits.StatorCurrentLimitEnable = true;
steerTalon.getConfigurator().apply(steerConfig);
steerTalon.setInverted(moduleConstants.SteerMotorInverted);
setSteerBrake(true);
Expand All @@ -69,12 +69,12 @@ public ModuleIOTalon(
driveEncoderUngearedRevolutions = OdometryThread.registerSignalInput(driveTalon.getPosition());
driveEncoderUngearedRevolutionsPerSecond = driveTalon.getVelocity();
driveMotorAppliedVoltage = driveTalon.getMotorVoltage();
driveMotorCurrent = driveTalon.getSupplyCurrent();
driveMotorCurrent = driveTalon.getStatorCurrent();

steerEncoderAbsolutePositionRevolutions = OdometryThread.registerSignalInput(cancoder.getAbsolutePosition());
steerEncoderVelocityRevolutionsPerSecond = cancoder.getVelocity();
steerMotorAppliedVolts = steerTalon.getMotorVoltage();
steerMotorCurrent = steerTalon.getSupplyCurrent();
steerMotorCurrent = steerTalon.getStatorCurrent();

periodicallyRefreshedSignals = new BaseStatusSignal[] {
driveEncoderUngearedRevolutionsPerSecond,
Expand Down

0 comments on commit f3c63f9

Please sign in to comment.