Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.ctre.phoenix6.signals.SensorDirectionValue;
import com.ctre.phoenix6.sim.TalonFXSimState.MotorType;
import edu.wpi.first.math.MatBuilder;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.Nat;
Expand Down Expand Up @@ -201,6 +202,16 @@ public ModuleConstants getBackRightModuleConstants() {
return new ModuleConstants(3, "Back Right", 6, 7, 3, Rotation2d.fromRotations(-0.205));
}

@Override
public MotorType getTurnMotorType() {
return MotorType.KrakenX60;
}

@Override
public MotorType getDriveMotorType() {
return MotorType.KrakenX60;
}

@Override
public int getGyroID() {
return 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.Pigeon2Configuration;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.sim.TalonFXSimState.MotorType;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.units.measure.Mass;
import frc.robot.components.camera.Camera.CameraConstants;
Expand Down Expand Up @@ -129,6 +130,16 @@ public TalonFXConfiguration getTurnConfig(int cancoderID) {
throw new UnsupportedOperationException("Unimplemented method 'getTurnConfiguration'");
}

@Override
public MotorType getDriveMotorType() {
return MotorType.KrakenX60;
}

@Override
public MotorType getTurnMotorType() {
return MotorType.KrakenX44;
}

@Override
public CANcoderConfiguration getCancoderConfig(Rotation2d cancoderOffset) {
// TODO Auto-generated method stub
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.ctre.phoenix6.signals.SensorDirectionValue;
import com.ctre.phoenix6.sim.TalonFXSimState.MotorType;
import edu.wpi.first.math.MatBuilder;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.Nat;
Expand Down Expand Up @@ -57,6 +58,16 @@ public int getGyroID() {
return 0;
}

@Override
public MotorType getDriveMotorType() {
return MotorType.KrakenX60;
}

@Override
public MotorType getTurnMotorType() {
return MotorType.KrakenX60;
}

public Pigeon2Configuration getGyroConfig() {
Pigeon2Configuration config = new Pigeon2Configuration();
config.MountPose.MountPosePitch = -0.002175945555791259;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.Pigeon2Configuration;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.sim.TalonFXSimState.MotorType;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.math.geometry.Rotation2d;
Expand Down Expand Up @@ -136,6 +137,20 @@ public double getWheelRadiusMeters() {
*/
public abstract TalonFXConfiguration getTurnConfig(int cancoderID);

/**
* The motor type of the swerve turn motors (i.e. x44 vs x60)
*
* @return
*/
public abstract MotorType getTurnMotorType();

/**
* The motor type of the swerve drive motors (i.e. x44 vs x60)
*
* @return
*/
public abstract MotorType getDriveMotorType();

/**
* The configuration for a swerve-module cancoder
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,12 @@ public ModuleIOSim(
// using Async odo)
this.simulation = simulation;
this.simulation.useDriveMotorController(
new MaplePhoenixUtil.TalonFXMotorControllerSim(driveTalon, true));
new MaplePhoenixUtil.TalonFXMotorControllerSim(
driveTalon, SwerveSubsystem.SWERVE_CONSTANTS.getDriveMotorType(), true));
this.simulation.useSteerMotorController(
new MaplePhoenixUtil.TalonFXMotorControllerWithRemoteCancoderSim(
turnTalon,
SwerveSubsystem.SWERVE_CONSTANTS.getTurnMotorType(),
SwerveSubsystem.SWERVE_CONSTANTS.getTurnMotorInverted(),
cancoder,
false,
Expand Down
7 changes: 5 additions & 2 deletions src/main/java/frc/robot/utils/MaplePhoenixUtil.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
import com.ctre.phoenix6.sim.CANcoderSimState;
import com.ctre.phoenix6.sim.ChassisReference;
import com.ctre.phoenix6.sim.TalonFXSimState;
import com.ctre.phoenix6.sim.TalonFXSimState.MotorType;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.Voltage;
Expand All @@ -36,10 +37,11 @@ public static class TalonFXMotorControllerSim implements SimulatedMotorControlle

private final TalonFXSimState talonFXSimState;

public TalonFXMotorControllerSim(TalonFX talonFX, boolean motorInverted) {
public TalonFXMotorControllerSim(TalonFX talonFX, MotorType motorType, boolean motorInverted) {
this.id = instances++;

this.talonFXSimState = talonFX.getSimState();
this.talonFXSimState.setMotorType(motorType);
talonFXSimState.Orientation =
motorInverted
? ChassisReference.Clockwise_Positive
Expand All @@ -66,11 +68,12 @@ public static class TalonFXMotorControllerWithRemoteCancoderSim

public TalonFXMotorControllerWithRemoteCancoderSim(
TalonFX talonFX,
MotorType motorType,
boolean motorInverted,
CANcoder cancoder,
boolean encoderInverted,
Angle encoderOffset) {
super(talonFX, motorInverted);
super(talonFX, motorType, motorInverted);
this.remoteCancoderSimState = cancoder.getSimState();
this.remoteCancoderSimState.Orientation =
encoderInverted
Expand Down