meillieur subsytem swerve (pas tent)

This commit is contained in:
Antoine PerreaultE
2025-12-08 19:23:02 -05:00
parent 0f9a71c375
commit 5e9f2f5244
5 changed files with 146 additions and 100 deletions

View File

@@ -4,6 +4,11 @@
"visible": false "visible": false
} }
}, },
"System Joysticks": {
"window": {
"enabled": false
}
},
"keyboardJoysticks": [ "keyboardJoysticks": [
{ {
"axisConfig": [ "axisConfig": [

View File

@@ -11,7 +11,7 @@
"x": 4.699180327868851, "x": 4.699180327868851,
"y": 2.1728995901639334 "y": 2.1728995901639334
}, },
"isLocked": false, "isLocked": true,
"linkedName": null "linkedName": null
}, },
{ {
@@ -27,7 +27,7 @@
"x": 2.853313965378558, "x": 2.853313965378558,
"y": 1.5363479888253109 "y": 1.5363479888253109
}, },
"isLocked": false, "isLocked": true,
"linkedName": null "linkedName": null
}, },
{ {
@@ -40,7 +40,7 @@
"y": 1.3902362024139756 "y": 1.3902362024139756
}, },
"nextControl": null, "nextControl": null,
"isLocked": false, "isLocked": true,
"linkedName": null "linkedName": null
} }
], ],

View File

@@ -14,7 +14,6 @@ import com.pathplanner.lib.auto.AutoBuilder;
import edu.wpi.first.cameraserver.CameraServer; import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.networktables.GenericEntry; import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts; import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
@@ -23,12 +22,9 @@ import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.RunCommand; import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.TunerConstants.TunerConstants; import frc.robot.TunerConstants.TunerConstants;
import frc.robot.commands.RainBow;
import frc.robot.commands.reset; import frc.robot.commands.reset;
import frc.robot.commands.Elevateur.Depart; import frc.robot.commands.Elevateur.Depart;
import frc.robot.commands.Elevateur.ElevateurManuel; import frc.robot.commands.Elevateur.ElevateurManuel;
@@ -96,7 +92,6 @@ public class RobotContainer {
Bougie bougie = new Bougie(); Bougie bougie = new Bougie();
Limelight3G limelight3g = new Limelight3G(); Limelight3G limelight3g = new Limelight3G();
Limelight3 limelight3 = new Limelight3(); Limelight3 limelight3 = new Limelight3();
Pose2d pose = new Pose2d();
Requin requin = new Requin(); Requin requin = new Requin();
CorailAspir corailAspir = new CorailAspir(pince, bougie); CorailAspir corailAspir = new CorailAspir(pince, bougie);
public RobotContainer() { public RobotContainer() {

View File

@@ -1,12 +1,9 @@
package frc.robot.subsystems; package frc.robot.subsystems;
import static edu.wpi.first.units.Units.MetersPerSecond;
import java.util.function.Supplier; import java.util.function.Supplier;
import com.ctre.phoenix6.Utils; import com.ctre.phoenix6.Utils;
import com.ctre.phoenix6.hardware.Pigeon2;
import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants; import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants;
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
import com.ctre.phoenix6.swerve.SwerveModuleConstants; import com.ctre.phoenix6.swerve.SwerveModuleConstants;
import com.ctre.phoenix6.swerve.SwerveRequest; import com.ctre.phoenix6.swerve.SwerveRequest;
import com.pathplanner.lib.auto.AutoBuilder; import com.pathplanner.lib.auto.AutoBuilder;
@@ -14,14 +11,9 @@ import com.pathplanner.lib.config.PIDConstants;
import com.pathplanner.lib.config.RobotConfig; import com.pathplanner.lib.config.RobotConfig;
import com.pathplanner.lib.controllers.PPHolonomicDriveController; import com.pathplanner.lib.controllers.PPHolonomicDriveController;
import edu.wpi.first.math.Matrix; import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3; import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation;
@@ -30,7 +22,6 @@ import edu.wpi.first.wpilibj.Notifier;
import edu.wpi.first.wpilibj.RobotController; import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Subsystem; import edu.wpi.first.wpilibj2.command.Subsystem;
import frc.robot.TunerConstants.TunerConstants;
import frc.robot.TunerConstants.TunerConstants.TunerSwerveDrivetrain; import frc.robot.TunerConstants.TunerConstants.TunerSwerveDrivetrain;
/** /**
@@ -42,33 +33,64 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
private static final double kSimLoopPeriod = 0.005; // 5 ms private static final double kSimLoopPeriod = 0.005; // 5 ms
private Notifier m_simNotifier = null; private Notifier m_simNotifier = null;
private double m_lastSimTime; private double m_lastSimTime;
private Pigeon2 pigeon2 = new Pigeon2(13);
/* Blue alliance sees forward as 0 degrees (toward red alliance wall) */ /* Blue alliance sees forward as 0 degrees (toward red alliance wall) */
private static final Rotation2d kBlueAlliancePerspectiveRotation = Rotation2d.kZero; private static final Rotation2d kBlueAlliancePerspectiveRotation = Rotation2d.kZero;
/* Red alliance sees forward as 180 degrees (toward blue alliance wall) */ /* Red alliance sees forward as 180 degrees (toward blue alliance wall) */
private static final Rotation2d kRedAlliancePerspectiveRotation = Rotation2d.k180deg; private static final Rotation2d kRedAlliancePerspectiveRotation = Rotation2d.k180deg;
/* Keep track if we've ever applied the operator perspective before or not */ /* Keep track if we've ever applied the operator perspective before or not */
private boolean m_hasAppliedOperatorPerspective = false; private boolean m_hasAppliedOperatorPerspective = false;
private SwerveDriveOdometry odometry;
private SwerveDrivePoseEstimator poseEstimator;
private final SwerveRequest.ApplyRobotSpeeds m_pathApplyRobotSpeeds = new SwerveRequest.ApplyRobotSpeeds(); private final SwerveRequest.ApplyRobotSpeeds m_pathApplyRobotSpeeds = new SwerveRequest.ApplyRobotSpeeds();
// Position des modules par rapport au centre du robot // Position des modules par rapport au centre du robot
Translation2d frontLeftLocation = new Translation2d(+0.3, +0.3); Translation2d frontLeftLocation = new Translation2d(+0.3, +0.3);
Translation2d frontRightLocation = new Translation2d(+0.3, -0.3); Translation2d frontRightLocation = new Translation2d(+0.3, -0.3);
Translation2d backLeftLocation = new Translation2d(-0.3, +0.3); Translation2d backLeftLocation = new Translation2d(-0.3, +0.3);
Translation2d backRightLocation = new Translation2d(-0.3, -0.3); Translation2d backRightLocation = new Translation2d(-0.3, -0.3);
private final SwerveDriveKinematics kinematics =
new SwerveDriveKinematics(
frontLeftLocation,
frontRightLocation,
backLeftLocation,
backRightLocation
);
/* SysId routine for characterizing translation. This is used to find PID gains for the drive motors. */ /* SysId routine for characterizing translation. This is used to find PID gains for the drive motors. */
private final SwerveRequest.SysIdSwerveTranslation m_translationCharacterization = new SwerveRequest.SysIdSwerveTranslation(); private void configureAutoBuilder() {
private final SwerveRequest.SysIdSwerveSteerGains m_steerCharacterization = new SwerveRequest.SysIdSwerveSteerGains(); RobotConfig config;
private final SwerveRequest.SysIdSwerveRotation m_rotationCharacterization = new SwerveRequest.SysIdSwerveRotation(); System.out.println("avant le mode auto est genere");
// private void configureAutoBuilder() { try{
config = RobotConfig.fromGUISettings();
// Configure AutoBuilder last
AutoBuilder.configure(
() -> getState().Pose, // Robot pose supplier
(pose) -> {
System.out.println("reset Pose " + pose.getX() + " " + pose.getY());
this.resetPose(pose);
this.resetPose(pose);
}, // Method to reset odometry (will be called if your auto has a starting pose)
() -> getState().Speeds,
(speeds, feedforwards) -> setControl(
m_pathApplyRobotSpeeds.withSpeeds(ChassisSpeeds.discretize(speeds, 0.020))
.withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesXNewtons())
.withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesYNewtons())
), // ChassisSpeeds supplier. MUST BE ROBOT RELATIVE
//(speeds, feedforwards) -> this.applyRequest(()-> driveAuto.withSpeeds(speeds)), // Method that will drive the robot given ROBOT RELATIVE ChassisSpeeds. Also optionally outputs individual module feedforwards
new PPHolonomicDriveController( // PPHolonomicController is the built in path following controller for holonomic drive trains
new PIDConstants(5.0, 0.0, 0.0), // Translation PID constants
new PIDConstants(5.0, 0.0, 0.0) // Rotation PID constants
),
config, // The robot configuration
() -> {
// Boolean supplier that controls when the path will be mirrored for the red alliance
// This will flip the path being followed to the red side of the field.
// THE ORIGIN WILL REMAIN ON THE BLUE SIDE
var alliance = DriverStation.getAlliance();
if (alliance.isPresent()) {
return alliance.get() == DriverStation.Alliance.Red;
}
return false;
},
this // Reference to this subsystem to set requirements
);
System.out.println("le mode auto est genere");
}
catch (Exception e) {
// Handle exception as needed
e.printStackTrace();
System.out.println("le mode auto ne marche pas");
}
// try { // try {
// var config = RobotConfig.fromGUISettings(); // var config = RobotConfig.fromGUISettings();
// AutoBuilder.configure( // AutoBuilder.configure(
@@ -102,7 +124,7 @@ private final SwerveDriveKinematics kinematics =
// PPHolonomicDriveController.overrideRotationFeedback(()->{ // PPHolonomicDriveController.overrideRotationFeedback(()->{
// return 0; // return 0;
// }); // });
// } }
// public void driveRobotRelative(ChassisSpeeds speeds) { // public void driveRobotRelative(ChassisSpeeds speeds) {
// // Convertir robot-relative ChassisSpeeds → SwerveModuleStates // // Convertir robot-relative ChassisSpeeds → SwerveModuleStates
@@ -135,43 +157,7 @@ private final SwerveDriveKinematics kinematics =
if (Utils.isSimulation()) { if (Utils.isSimulation()) {
startSimThread(); startSimThread();
} }
RobotConfig config; configureAutoBuilder();
System.out.println("avant le mode auto est genere");
try{
config = RobotConfig.fromGUISettings();
SwerveRequest.ApplyRobotSpeeds driveAuto = new SwerveRequest.ApplyRobotSpeeds().withDriveRequestType(DriveRequestType.OpenLoopVoltage);
// Configure AutoBuilder last
AutoBuilder.configure(
() -> getState().Pose, // Robot pose supplier
this::resetPose, // Method to reset odometry (will be called if your auto has a starting pose)
() -> getState().Speeds, // ChassisSpeeds supplier. MUST BE ROBOT RELATIVE
(speeds, feedforwards) -> this.applyRequest(()-> driveAuto.withSpeeds(speeds)), // Method that will drive the robot given ROBOT RELATIVE ChassisSpeeds. Also optionally outputs individual module feedforwards
new PPHolonomicDriveController( // PPHolonomicController is the built in path following controller for holonomic drive trains
new PIDConstants(5.0, 0.0, 0.0), // Translation PID constants
new PIDConstants(5.0, 0.0, 0.0) // Rotation PID constants
),
config, // The robot configuration
() -> {
// Boolean supplier that controls when the path will be mirrored for the red alliance
// This will flip the path being followed to the red side of the field.
// THE ORIGIN WILL REMAIN ON THE BLUE SIDE
var alliance = DriverStation.getAlliance();
if (alliance.isPresent()) {
return alliance.get() == DriverStation.Alliance.Red;
}
return false;
},
this // Reference to this subsystem to set requirements
);
System.out.println("le mode auto est genere");
}
catch (Exception e) {
// Handle exception as needed
e.printStackTrace();
System.out.println("le mode auto ne marche pas");
}
// configureAutoBuilder();
} }
/** /**
* Constructs a CTRE SwerveDrivetrain using the specified constants. * Constructs a CTRE SwerveDrivetrain using the specified constants.
@@ -195,7 +181,7 @@ private final SwerveDriveKinematics kinematics =
if (Utils.isSimulation()) { if (Utils.isSimulation()) {
startSimThread(); startSimThread();
} }
// configureAutoBuilder(); configureAutoBuilder();
} }
/** /**
@@ -228,7 +214,7 @@ private final SwerveDriveKinematics kinematics =
if (Utils.isSimulation()) { if (Utils.isSimulation()) {
startSimThread(); startSimThread();
} }
// configureAutoBuilder(); configureAutoBuilder();
} }

View File

@@ -1,7 +1,7 @@
{ {
"fileName": "Phoenix6-25.2.2.json", "fileName": "Phoenix6-frc2025-latest.json",
"name": "CTRE-Phoenix (v6)", "name": "CTRE-Phoenix (v6)",
"version": "25.2.2", "version": "25.4.0",
"frcYear": "2025", "frcYear": "2025",
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
"mavenUrls": [ "mavenUrls": [
@@ -19,14 +19,14 @@
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-java", "artifactId": "wpiapi-java",
"version": "25.2.2" "version": "25.4.0"
} }
], ],
"jniDependencies": [ "jniDependencies": [
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "api-cpp", "artifactId": "api-cpp",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -40,7 +40,7 @@
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "tools", "artifactId": "tools",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -54,7 +54,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "api-cpp-sim", "artifactId": "api-cpp-sim",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -68,7 +68,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim", "artifactId": "tools-sim",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -82,7 +82,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX", "artifactId": "simTalonSRX",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -96,7 +96,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX", "artifactId": "simVictorSPX",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -110,7 +110,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU", "artifactId": "simPigeonIMU",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -124,7 +124,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simCANCoder", "artifactId": "simCANCoder",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -138,7 +138,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX", "artifactId": "simProTalonFX",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -152,7 +152,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFXS", "artifactId": "simProTalonFXS",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -166,7 +166,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder", "artifactId": "simProCANcoder",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -180,7 +180,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2", "artifactId": "simProPigeon2",
"version": "25.2.2", "version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -194,7 +194,35 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange", "artifactId": "simProCANrange",
"version": "25.2.2", "version": "25.4.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdi",
"version": "25.4.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdle",
"version": "25.4.0",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -210,7 +238,7 @@
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-cpp", "artifactId": "wpiapi-cpp",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_Phoenix6_WPI", "libName": "CTRE_Phoenix6_WPI",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -226,7 +254,7 @@
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "tools", "artifactId": "tools",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_PhoenixTools", "libName": "CTRE_PhoenixTools",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -242,7 +270,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "wpiapi-cpp-sim", "artifactId": "wpiapi-cpp-sim",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_Phoenix6_WPISim", "libName": "CTRE_Phoenix6_WPISim",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -258,7 +286,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim", "artifactId": "tools-sim",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_PhoenixTools_Sim", "libName": "CTRE_PhoenixTools_Sim",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -274,7 +302,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX", "artifactId": "simTalonSRX",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_SimTalonSRX", "libName": "CTRE_SimTalonSRX",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -290,7 +318,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX", "artifactId": "simVictorSPX",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_SimVictorSPX", "libName": "CTRE_SimVictorSPX",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -306,7 +334,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU", "artifactId": "simPigeonIMU",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_SimPigeonIMU", "libName": "CTRE_SimPigeonIMU",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -322,7 +350,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simCANCoder", "artifactId": "simCANCoder",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_SimCANCoder", "libName": "CTRE_SimCANCoder",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -338,7 +366,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX", "artifactId": "simProTalonFX",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_SimProTalonFX", "libName": "CTRE_SimProTalonFX",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -354,7 +382,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFXS", "artifactId": "simProTalonFXS",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_SimProTalonFXS", "libName": "CTRE_SimProTalonFXS",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -370,7 +398,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder", "artifactId": "simProCANcoder",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_SimProCANcoder", "libName": "CTRE_SimProCANcoder",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -386,7 +414,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2", "artifactId": "simProPigeon2",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_SimProPigeon2", "libName": "CTRE_SimProPigeon2",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -402,7 +430,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange", "artifactId": "simProCANrange",
"version": "25.2.2", "version": "25.4.0",
"libName": "CTRE_SimProCANrange", "libName": "CTRE_SimProCANrange",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -414,6 +442,38 @@
"osxuniversal" "osxuniversal"
], ],
"simMode": "swsim" "simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdi",
"version": "25.4.0",
"libName": "CTRE_SimProCANdi",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANdle",
"version": "25.4.0",
"libName": "CTRE_SimProCANdle",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
} }
] ]
} }