diff --git a/networktables.json b/networktables.json
new file mode 100644
index 0000000..fe51488
--- /dev/null
+++ b/networktables.json
@@ -0,0 +1 @@
+[]
diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java
index c50ba05..d73b627 100644
--- a/src/main/java/frc/robot/Constants.java
+++ b/src/main/java/frc/robot/Constants.java
@@ -1,19 +1,191 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
package frc.robot;
-/**
- * The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
- * constants. This class should not be used for any other purpose. All constants should be declared
- * globally (i.e. public static). Do not put anything functional in this class.
- *
- *
It is advised to statically import this class (or one of its inner classes) wherever the
- * constants are needed, to reduce verbosity.
- */
+import com.ctre.phoenixpro.signals.SensorDirectionValue;
+
+import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
+import edu.wpi.first.math.trajectory.TrapezoidProfile;
+import edu.wpi.first.math.util.Units;
+
+public final class Constants {
+ public static final class ModuleConstants {
+ // these constants should be correct for the current 4ki module we are using
+ public static final double kWheelDiameterMeters = Units.inchesToMeters(4);
+ public static final double kDriveMotorGearRatio = 1/6.75;
+ public static final double kTurningMotorGearRatio = 1/21.0;
+ public static final double kDriveEncoderRot2Meter = kDriveMotorGearRatio * Math.PI * kWheelDiameterMeters;
+ public static final double kTurningEncoderRot2Deg = kTurningMotorGearRatio * 360;
+ public static final double kDriveEncoderRPM2MeterPerSec = kDriveEncoderRot2Meter / 60;
+ public static final double kTurningEncoderRPM2DegPerSec = kTurningEncoderRot2Deg / 60;
+
+
+ // We may need to tune this for the PID turning
+
+ // we may need to tune it so this is not set in stone
+ public static final double kPTurning = .01;
+ public static final double kDTurning = 0;
+
+ public static final double kPModuleDriveController = .01;
+ public static final double kDModuleDriveController = 0;
+ }
+
+ public static final class DriveConstants {
+
+ // we need to update this // no longer needs to be updated: I measured from center of axle to center of axle
+ //thse seem to be based off of the base dimensions
+ public static final double kTrackWidth = Units.inchesToMeters(21);
+ public static final double kWheelBase = Units.inchesToMeters(21);
+
+ //PID constants
+ public static final double Ks = 0.10729;
+ public static final double Kv = 0.85456;
+ public static final double Ka = 0.047848;
+
+ public static final double kP = 0.025;
+ public static final double kI = 0;
+ public static final double kD = 0;
+
+ //This should be relative to the center, but still check documentation about how the grid is set up for swerve kinetics
+ //Ive changed it. It looked wrong and I fixed it based on the coordinate system at https://hhs-team670.github.io/MustangLib/frc/team670/robot/utils/math/Translation2d.html
+ public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics(
+ new Translation2d(kWheelBase / 2, kTrackWidth / 2), //front left
+ new Translation2d(kWheelBase / 2, -kTrackWidth / 2), //front right
+ new Translation2d(-kWheelBase / 2, kTrackWidth / 2), //back left
+ new Translation2d(-kWheelBase / 2, -kTrackWidth / 2)); //backright
+
+ //We need to update these motors
+ // frontLeft Module
+ // offsets should be drawn from no offest vaule on x tuner
+ public static final int kFrontLeftDriveMotorPort = 57; //motors updated
+ public static final int kFrontLeftTurningMotorPort = 56; //motors updated
+ public static final boolean kFrontLeftDriveMotorReversed = true; //re updated //updated
+ public static final boolean kFrontLeftTurningMotorReversed = true; //updated
+ public static final int kFrontLeftDriveAbsoluteEncoderPort = 30; //updated
+ public static final boolean kFrontLeftDriveAbsoluteEncoderReversed = false; //updated
+ public static final double kFrontLeftDriveAbsoluteEncoderOffsetDeg = -0.134521; //updated, in degrees // they want this to be the negative of the reported values?
+ public static final SensorDirectionValue kFrontLeftTurningForwardDirection = SensorDirectionValue.CounterClockwise_Positive;
+
+ //we need to updats these motors
+ // frontRight Module
+ // offset -0.266357
+ public static final int kFrontRightDriveMotorPort = 51; //motors updated
+ public static final int kFrontRightTurningMotorPort = 50; //motors updated
+ public static final boolean kFrontRightDriveMotorReversed = false; //updated
+ public static final boolean kFrontRightTurningMotorReversed = true; //updated
+ public static final int kFrontRightDriveAbsoluteEncoderPort = 31; //updated
+ public static final boolean kFrontRightDriveAbsoluteEncoderReversed = false; //updated
+ public static final double kFrontRightDriveAbsoluteEncoderOffsetDeg = -0.281494; //updated, in degrees
+ public static final SensorDirectionValue kFrontRightTurningForwardDirection = SensorDirectionValue.CounterClockwise_Positive;
+
+ //we need to update these motors
+ // backLeft Module
+ // offset -0.480713
+ public static final int kBackLeftDriveMotorPort = 55; //motors updated
+ public static final int kBackLeftTurningMotorPort = 54; //motors updated
+ public static final boolean kBackLeftDriveMotorReversed = true; //updated
+ public static final boolean kBackLeftTurningMotorReversed = true; //updated
+ public static final int kBackLeftDriveAbsoluteEncoderPort = 33; //updated
+ public static final boolean kBackLeftDriveAbsoluteEncoderReversed = false; //updated
+ public static final double kBackLeftDriveAbsoluteEncoderOffsetDeg = -0.027832; //updated, in degrees
+ public static final SensorDirectionValue kBackLeftTurningForwardDirection = SensorDirectionValue.CounterClockwise_Positive;
+
+ //we need to update these motors
+ // backRight Module
+ //0.480957
+ public static final int kBackRightDriveMotorPort = 52; //motors updated
+ public static final int kBackRightTurningMotorPort = 53; //motors updated
+ public static final boolean kBackRightDriveMotorReversed = false; //updated
+ public static final boolean kBackRightTurningMotorReversed = true; //updated
+ public static final int kBackRightDriveAbsoluteEncoderPort = 32; //updated
+ public static final boolean kBackRightDriveAbsoluteEncoderReversed = false; //updated
+ public static final double kBackRightDriveAbsoluteEncoderOffsetDeg = 0.389160; //updated, in degrees
+ public static final SensorDirectionValue kBackRightTurningForwardDirection = SensorDirectionValue.CounterClockwise_Positive;
+
+
+ //NOTE: these are not used in actual code they are just used to define max based on physical contraints
+ //If you want to ignore these then change the limit on the max speeds manually
+ //these seem to be mostly fine but we may need change some things
+ // also we need to change the physical dimensions of our base if we are going to use this
+ public static final double kPhysicalMaxSpeedMetersPerSecond = 5676.0 / 60.0 * ModuleConstants.kDriveEncoderRot2Meter;
+ public static final double kPhysicalMaxAngularSpeedDegreesPerSecond = 360; //2 * Math.PI; //kPhysicalMaxSpeedMetersPerSecond / Math.hypot(DriveConstants.kTrackWidth / 2.0, DriveConstants.kWheelBase / 2.0 * 3);
+
+ //These are the variables that determine the max speeds of our swerve drive
+ public static final double kTeleDriveMaxSpeedMetersPerSecond = kPhysicalMaxSpeedMetersPerSecond / 4;
+ public static final double kTeleDriveMaxAngularSpeedDegreesPerSecond = kPhysicalMaxAngularSpeedDegreesPerSecond / 4;
+
+ public static final double kTeleDriveMaxAccelerationUnitsPerSecond = 3;
+ public static final double kTeleDriveMaxAngularAccelerationUnitsPerSecond = 3;
+ }
+
+ //these we can ignore for now since they are only for autonmous
+ public static final class AutoConstants {
+ public static final double kMaxSpeedMetersPerSecond = DriveConstants.kPhysicalMaxSpeedMetersPerSecond / 4;
+ public static final double kMaxAngularSpeedDegreesPerSecond = DriveConstants.kPhysicalMaxAngularSpeedDegreesPerSecond / 10;
+
+ public static final double kMaxAccelerationMetersPerSecondSquared = 3;
+ public static final double kMaxAngularAccelerationDegreesPerSecondSquared = 45.0;
+ public static final double kPXController = 1.5;
+ public static final double kPYController = 1.5;
+ public static final double kPThetaController = 3;
+
+ public static final TrapezoidProfile.Constraints kThetaControllerConstraints =
+ new TrapezoidProfile.Constraints(
+ kMaxAngularSpeedDegreesPerSecond,
+ kMaxAngularAccelerationDegreesPerSecondSquared);
+ }
+
+ //this is just to set a deadzone so we don't need to move the stick
+ public static final class OIConstants {
+ public static final double kDeadband = 0.05;
+ }
+}
+
+ /**
public final class Constants {
public static class OperatorConstants {
public static final int kDriverControllerPort = 0;
+
+ //these numbers may be incorrect
}
+
+ public static final int kDriverControllerPort = 1;
+
+ public static final double kTrackWidth = Units.inchesToMeters(21);
+ // Distance between right and left wheels
+ public static final double kWheelBase = Units.inchesToMeters(25.5);
+ // Distance between front and back wheels
+
+
+ //please update these with the accurate dimensions for robot
+ public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics(
+ new Translation2d(kWheelBase / 2, -kTrackWidth / 2),
+ new Translation2d(kWheelBase / 2, kTrackWidth / 2),
+ new Translation2d(-kWheelBase / 2, -kTrackWidth / 2),
+ new Translation2d(-kWheelBase / 2, kTrackWidth / 2));
+
+
+
+ public static final double kDriveEncoderRot2Meter = kDriveMotorGearRatio * Math.PI * kWheelDiameterMeters;
+ public static final double kTurningEncoderRot2Rad = kTurningMotorGearRatio * 2 * Math.PI;
+ public static final double kDriveEncoderRPM2MeterPerSec = kDriveEncoderRot2Meter / 60;
+ public static final double kTurningEncoderRPM2RadPerSec = kTurningEncoderRot2Rad / 60;
+ public static final double kPturning = 0.5;
+ public static final double kMaxSpeed = 5;
+ public static final double kTeleDriveMaxAccelerationUnitsPerSecond = 5;
+ public static final double kTeleDriveMaxAngularAccelerationUnitsPerSecond = 5;
+
+ public static final double kPhysicalMaxSpeedMetersPerSecond = 5;
+ public static final double kPhysicalMaxAngularSpeedRadiansPerSecond = 2 * 2 * Math.PI;
+
+ public static final int kDriverYAxis = 1;
+ public static final int kDriverXAxis = 0;
+ public static final int kDriverRotAxis = 4;
+ public static final int kDriverFieldOrientedButtonIdx = 1;
+ public static final double kDeadband = 0.05;
+ public static final double kTeleDriveMaxSpeedMetersPerSecond = kPhysicalMaxSpeedMetersPerSecond / 4;
+ public static final double kMaxAngularAccelerationRadiansPerSecondSquared = Math.PI / 4;
+ public static final double kTeleDriveMaxAngularSpeedRadiansPerSecond = //
+ kPhysicalMaxAngularSpeedRadiansPerSecond / 4;
}
+*/
+
\ No newline at end of file
diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java
index a33249e..5035a15 100644
--- a/src/main/java/frc/robot/RobotContainer.java
+++ b/src/main/java/frc/robot/RobotContainer.java
@@ -1,63 +1,34 @@
-// Copyright (c) FIRST and other WPILib contributors.
-// Open Source Software; you can modify and/or share it under the terms of
-// the WPILib BSD license file in the root directory of this project.
-
package frc.robot;
-import frc.robot.Constants.OperatorConstants;
-import frc.robot.commands.Autos;
-import frc.robot.commands.ExampleCommand;
-import frc.robot.subsystems.ExampleSubsystem;
+import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.Command;
-import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
-import edu.wpi.first.wpilibj2.command.button.Trigger;
-
-/**
- * This class is where the bulk of the robot should be declared. Since Command-based is a
- * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
- * periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
- * subsystems, commands, and trigger mappings) should be declared here.
- */
+import frc.robot.commands.SwerveCommand;
+import frc.robot.subsystems.SwerveSubsystem;
+import frc.robot.Constants;
+import frc.robot.Constants.DriveConstants;
+
public class RobotContainer {
- // The robot's subsystems and commands are defined here...
- private final ExampleSubsystem m_exampleSubsystem = new ExampleSubsystem();
-
- // Replace with CommandPS4Controller or CommandJoystick if needed
- private final CommandXboxController m_driverController =
- new CommandXboxController(OperatorConstants.kDriverControllerPort);
-
- /** The container for the robot. Contains subsystems, OI devices, and commands. */
- public RobotContainer() {
- // Configure the trigger bindings
- configureBindings();
- }
-
- /**
- * Use this method to define your trigger->command mappings. Triggers can be created via the
- * {@link Trigger#Trigger(java.util.function.BooleanSupplier)} constructor with an arbitrary
- * predicate, or via the named factories in {@link
- * edu.wpi.first.wpilibj2.command.button.CommandGenericHID}'s subclasses for {@link
- * CommandXboxController Xbox}/{@link edu.wpi.first.wpilibj2.command.button.CommandPS4Controller
- * PS4} controllers or {@link edu.wpi.first.wpilibj2.command.button.CommandJoystick Flight
- * joysticks}.
- */
- private void configureBindings() {
- // Schedule `ExampleCommand` when `exampleCondition` changes to `true`
- new Trigger(m_exampleSubsystem::exampleCondition)
- .onTrue(new ExampleCommand(m_exampleSubsystem));
-
- // Schedule `exampleMethodCommand` when the Xbox controller's B button is pressed,
- // cancelling on release.
- m_driverController.b().whileTrue(m_exampleSubsystem.exampleMethodCommand());
- }
-
- /**
- * Use this to pass the autonomous command to the main {@link Robot} class.
- *
- * @return the command to run in autonomous
- */
- public Command getAutonomousCommand() {
- // An example command will be run in autonomous
- return Autos.exampleAuto(m_exampleSubsystem);
- }
-}
+
+ private final SwerveSubsystem swerveSubsystem = new SwerveSubsystem();
+ private final XboxController driverOne = new XboxController(0);
+
+ public static final boolean ABSOLUTE_TURNING_MODE = true;
+
+ public RobotContainer() {
+ swerveSubsystem.setDefaultCommand(new SwerveCommand(swerveSubsystem, driverOne));
+ configureButtonBindings();
+ // System.out.println(DriveConstants.kTeleDriveMaxSpeedMetersPerSecond);
+ }
+
+ private void configureButtonBindings() {
+
+ }
+
+ public SwerveSubsystem getSwerve() {
+ return swerveSubsystem;
+ }
+
+ public Command getAutonomousCommand() {
+ return null;
+ }
+}
\ No newline at end of file
diff --git a/src/main/java/frc/robot/commands/SwerveCommand.java b/src/main/java/frc/robot/commands/SwerveCommand.java
index 1ebcb95..9da64a6 100644
--- a/src/main/java/frc/robot/commands/SwerveCommand.java
+++ b/src/main/java/frc/robot/commands/SwerveCommand.java
@@ -1,31 +1,35 @@
package frc.robot.commands;
-import java.util.function.Supplier;
+import com.ctre.phoenix.sensors.CANCoder;
+import com.ctre.phoenixpro.hardware.CANcoder;
+import com.kauailabs.navx.frc.AHRS;
+import com.revrobotics.CANSparkMax;
-import edu.wpi.first.math.filter.SlewRateLimiter;
+import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveModuleState;
+import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.CommandBase;
-import frc.robot.Constants;
+import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
+import frc.robot.RobotContainer;
+import frc.robot.Constants.DriveConstants;
+import frc.robot.Constants.OIConstants;
+import frc.robot.helpers.Crashboard;
import frc.robot.subsystems.SwerveSubsystem;
public class SwerveCommand extends CommandBase {
private final SwerveSubsystem swerveSubsystem;
- private final Supplier xSpdFunction, ySpdFunction, turningSpdFunction;
- private final Supplier fieldOrientedFunction;
- private final SlewRateLimiter xLimiter, yLimiter, turningLimiter;
+ private final XboxController controller;
+ private CANcoder FrontLeftCoder;
+ private CANSparkMax FrontLeftTurnSpark;
- public SwerveCommand(SwerveSubsystem swerveSubsystem, Supplier xSpdFunction, Supplier ySpdFunction, Supplier turningSpdFunction, Supplier fieldOrientedFunction) {
+ public SwerveCommand(SwerveSubsystem swerveSubsystem, XboxController controller) {
this.swerveSubsystem = swerveSubsystem;
- this.xSpdFunction = xSpdFunction;
- this.ySpdFunction = ySpdFunction;
- this.turningSpdFunction = turningSpdFunction;
- this.fieldOrientedFunction = fieldOrientedFunction;
- this.xLimiter = new SlewRateLimiter(Constants.kTeleDriveMaxAccelerationUnitsPerSecond);
- this.yLimiter = new SlewRateLimiter(Constants.kTeleDriveMaxAccelerationUnitsPerSecond);
- this.turningLimiter = new SlewRateLimiter(Constants.kTeleDriveMaxAngularAccelerationUnitsPerSecond);
+ this.controller = controller;
addRequirements(swerveSubsystem);
+ this.FrontLeftCoder = swerveSubsystem.frontLeft.getCANcoder();
+ this.FrontLeftTurnSpark = swerveSubsystem.frontLeft.turningMotor;
}
@Override
@@ -34,38 +38,79 @@ public void initialize() {
@Override
public void execute() {
- // 1. Get real-time joystick inputs
- double xSpeed = xSpdFunction.get();
- double ySpeed = ySpdFunction.get();
- double turningSpeed = turningSpdFunction.get();
-
- // 2. Apply deadband
- xSpeed = Math.abs(xSpeed) > Constants.kDeadband ? xSpeed : 0.0;
- ySpeed = Math.abs(ySpeed) > Constants.kDeadband ? ySpeed : 0.0;
- turningSpeed = Math.abs(turningSpeed) > Constants.kDeadband ? turningSpeed : 0.0;
-
- // 3. Make the driving smoother
- xSpeed = xLimiter.calculate(xSpeed) * Constants.kTeleDriveMaxSpeedMetersPerSecond;
- ySpeed = yLimiter.calculate(ySpeed) * Constants.kTeleDriveMaxSpeedMetersPerSecond;
- turningSpeed = turningLimiter.calculate(turningSpeed)
- * Constants.kTeleDriveMaxAngularSpeedRadiansPerSecond;
-
- // 4. Construct desired chassis speeds
- ChassisSpeeds chassisSpeeds;
- if (fieldOrientedFunction.get()) {
- // Relative to field
- chassisSpeeds = ChassisSpeeds.fromFieldRelativeSpeeds(
- xSpeed, ySpeed, turningSpeed, swerveSubsystem.getRotation2d());
+
+ //testing
+ Crashboard.toDashboard("updatedControllerAngle", getHeadingFromController(controller), "controllerAngle");
+ Crashboard.toDashboard("Rightx", controller.getRightX(), "controllerAngle");
+ Crashboard.toDashboard("Righty", controller.getRightY(), "controllerAngle");
+ Crashboard.toDashboard("Leftx", controller.getLeftX(), "controllerAngle");
+ Crashboard.toDashboard("Lefty", controller.getLeftY(), "controllerAngle");
+ // :3
+
+ //
+ //System.out.println("ANGLE = " + swerveSubsystem.frontLeft.getAbsoluteEncoderDeg() + ", SPEED = " + FrontLeftTurnSpark.get());
+
+ // \:3
+
+ double xSpeed = Math.abs(controller.getLeftY()) > OIConstants.kDeadband ? controller.getLeftY() : 0.0;
+ xSpeed = xSpeed * DriveConstants.kTeleDriveMaxSpeedMetersPerSecond;
+
+ double ySpeed = Math.abs(controller.getLeftX()) > OIConstants.kDeadband ? controller.getLeftX() : 0.0;
+ ySpeed = ySpeed * DriveConstants.kTeleDriveMaxSpeedMetersPerSecond;
+
+ double turningSpeed = Math.abs(controller.getRightX()) > OIConstants.kDeadband ? controller.getRightX() : 0.0;
+ turningSpeed = turningSpeed * DriveConstants.kTeleDriveMaxAngularSpeedDegreesPerSecond;
+ Crashboard.toDashboard("kTeleDriveMaxAngularSpeedDegreesPerSecond", DriveConstants.kTeleDriveMaxAngularSpeedDegreesPerSecond, "navx");
+ //turningSpeed = Math.abs(turningSpeed) > OIConstants.kDeadband ? turningSpeed : 0.0;
+ //turningSpeed = 0;
+ System.out.println("xSpeed: " + xSpeed + " ySpeed: " + ySpeed + " turningSpeed: " + turningSpeed);
+ Crashboard.toDashboard("xSpeed", xSpeed, "Swerve");
+ Crashboard.toDashboard("ySpeed", ySpeed, "Swerve");
+ Crashboard.toDashboard("kTeleDriveMaxSpeedMetersPerSecond", DriveConstants.kTeleDriveMaxSpeedMetersPerSecond, "Swerve");
+
+
+ Rotation2d currentHeading = Rotation2d.fromDegrees(swerveSubsystem.getHeading()); //inverted
+ Rotation2d targetHeading = Rotation2d.fromRadians(getHeadingFromController(controller));
+ double turningSpeedRadiansPerSecond;
+
+ if (RobotContainer.ABSOLUTE_TURNING_MODE) {
+ turningSpeedRadiansPerSecond = 0;
+ double deadzoneRadians = 0.1;
+
+ if (currentHeading.getDegrees() < targetHeading.getDegrees()) turningSpeedRadiansPerSecond = 0.2;
+
+ if (currentHeading.getDegrees() > targetHeading.getDegrees()) turningSpeedRadiansPerSecond = -0.2;
+
+ double offset = currentHeading.getDegrees() - targetHeading.getDegrees();
+
+ if (Math.abs(offset) <= deadzoneRadians) {
+ turningSpeedRadiansPerSecond = 0;
+ }
+
} else {
- // Relative to robot
- chassisSpeeds = new ChassisSpeeds(xSpeed, ySpeed, turningSpeed);
+ turningSpeedRadiansPerSecond = Rotation2d.fromDegrees(turningSpeed).getRadians();
}
- // 5. Convert chassis speeds to individual module states
- SwerveModuleState[] moduleStates = Constants.kDriveKinematics.toSwerveModuleStates(chassisSpeeds);
+
+
+ ChassisSpeeds chassisSpeeds = ChassisSpeeds.fromFieldRelativeSpeeds(xSpeed, ySpeed, turningSpeedRadiansPerSecond, currentHeading);
+
+ Crashboard.toDashboard("Chassisspeed X", chassisSpeeds.vxMetersPerSecond, "Swerve 2");
+ Crashboard.toDashboard("Chassisspeed Y", chassisSpeeds.vyMetersPerSecond, "Swerve 2");
+
+ swerveSubsystem.setModuleStates(DriveConstants.kDriveKinematics.toSwerveModuleStates(chassisSpeeds));
+
+ Crashboard.toDashboard("turningSpeedRadiansPerSecond", turningSpeedRadiansPerSecond, "navx");
+ Crashboard.toDashboard("currentHeading", currentHeading.getRadians(), "navx");
+ //Crashboard.toDashboard("desired states", DriveConstants.kDriveKinematics.toSwerveModuleStates(chassisSpeeds)[0].toString(), "navx");
+ // this.swerveSubsystem.setModuleStates(new SwerveModuleState[] {new SwerveModuleState(0.5, new Rotation2d(0.1)), new SwerveModuleState(0.5, new Rotation2d(0.1)), new SwerveModuleState(0.5, new Rotation2d(0.1)), new SwerveModuleState(.5, new Rotation2d( 0.1))});
+ //for (int i = 0; i < this.swerveSubsystem.getModuleStates().length; i ++) {
+ // System.out.print(this.swerveSubsystem.getModuleStates()[i] + ", " );
+ // }
+ // System.out.print("\n");
+ //
+
- // 6. Output each module states to wheels
- swerveSubsystem.setModuleStates(moduleStates);
}
@Override
@@ -77,4 +122,34 @@ public void end(boolean interrupted) {
public boolean isFinished() {
return false;
}
+
+ private double getHeadingFromController(XboxController c) {
+
+ double deadzone = 0.05;
+
+ double x = c.getRightX();
+ double y = -c.getRightY();
+
+ if (Math.abs(x) < deadzone) {
+ x = 0;
+ }
+ if (Math.abs(y) < deadzone) {
+ y = 0;
+ }
+
+ if (x == 0 && y == 0) return Math.toRadians(swerveSubsystem.getHeading());
+
+
+ int holder = 1;
+
+ double angle = -1 * Math.atan(x/y);
+ if (y < 0) {
+ if (x < 0)
+ {
+ holder = -1;
+ }
+ angle -= holder * Math.PI;
+ }
+ return -angle;
+ }
}
\ No newline at end of file
diff --git a/src/main/java/frc/robot/helpers/Crashboard.java b/src/main/java/frc/robot/helpers/Crashboard.java
new file mode 100644
index 0000000..17df4eb
--- /dev/null
+++ b/src/main/java/frc/robot/helpers/Crashboard.java
@@ -0,0 +1,79 @@
+package frc.robot.helpers;
+
+import java.util.Dictionary;
+import java.util.Hashtable;
+import java.util.Map;
+
+import edu.wpi.first.networktables.GenericEntry;
+import edu.wpi.first.util.sendable.Sendable;
+import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
+import edu.wpi.first.wpilibj.shuffleboard.ComplexWidget;
+import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
+import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
+
+public class Crashboard {
+
+ private static Dictionary DashboardEntries = new Hashtable<>();
+
+ public static GenericEntry toDashboard(String identifier, double value, String tab) {
+ return toDashboardGeneric(identifier, value, tab);
+ }
+
+ private static GenericEntry toDashboardGeneric(String identifier, Object value, String tab) {
+
+ GenericEntry genericEntry = DashboardEntries.get(getKey(identifier, tab));
+ if (genericEntry == null) {
+ genericEntry = Shuffleboard.getTab(tab).add(identifier, value).getEntry();
+ DashboardEntries.put(getKey(identifier, tab), genericEntry);
+ } else {
+ genericEntry.setValue(value);
+ }
+ return genericEntry;
+
+ }
+
+ public static ComplexWidget AddChooser(String identifier, SendableChooser value, String tab, BuiltInWidgets widget) {
+ return Shuffleboard.getTab(tab).add(identifier, value).withWidget(widget);
+ }
+
+ public static GenericEntry AddSlider(String identifier, double value, String tab, double minValue, double maxValue) {
+ GenericEntry genericEntry = DashboardEntries.get(getKey(identifier, tab));
+ if (genericEntry == null) {
+ genericEntry = Shuffleboard.getTab(tab)
+ .add(getKey(identifier, tab), value)
+ .withWidget(BuiltInWidgets.kNumberSlider)
+ .withProperties(Map.of("min", minValue, "max", maxValue)) // specify widget properties here
+ .getEntry();
+ }
+ else
+ {
+ genericEntry.setValue(value);
+ }
+ return genericEntry;
+ }
+
+ private static String getKey(String identifier, String tab) {
+ return identifier + "-" + tab;
+ }
+
+ public static GenericEntry toDashboard(String identifier, boolean value, String tab) {
+ return toDashboardGeneric(identifier, value, tab);
+ }
+
+ public static GenericEntry toDashboard(String identifier, Sendable value, String tab) {
+ return toDashboardGeneric(identifier, value, tab);
+ }
+
+ public static GenericEntry toDashboard(String identifier, String value, String tab) {
+ return toDashboardGeneric(identifier, value, tab);
+ }
+
+
+ public static double clamp(double in, double min, double max) {
+ if (in < min)
+ in = min;
+ if (in > max)
+ in = max;
+ return in;
+ }
+}
\ No newline at end of file
diff --git a/src/main/java/frc/robot/subsystems/SwerveModule.java b/src/main/java/frc/robot/subsystems/SwerveModule.java
index 271cda1..fdb4da4 100644
--- a/src/main/java/frc/robot/subsystems/SwerveModule.java
+++ b/src/main/java/frc/robot/subsystems/SwerveModule.java
@@ -1,101 +1,179 @@
package frc.robot.subsystems;
-import com.revrobotics.CANSparkMax;
+
import com.revrobotics.RelativeEncoder;
+import com.revrobotics.CANSparkMax.IdleMode;
+import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
+import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
+import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Rotation2d;
-import edu.wpi.first.wpilibj.AnalogInput;
-import edu.wpi.first.wpilibj.RobotController;
-import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import frc.robot.Constants;
+import frc.robot.Constants.DriveConstants;
+import frc.robot.Constants.ModuleConstants;
+import frc.robot.helpers.Crashboard;
+
+import com.ctre.phoenix.sensors.AbsoluteSensorRange;
+import com.ctre.phoenix.sensors.CANCoder; //BAD CRINGE
+import com.ctre.phoenix.sensors.CANCoderConfiguration;
+import com.ctre.phoenixpro.configs.CANcoderConfiguration;
+import com.ctre.phoenixpro.hardware.CANcoder;
+import com.ctre.phoenixpro.signals.AbsoluteSensorRangeValue;
+import com.ctre.phoenixpro.signals.SensorDirectionValue;
public class SwerveModule {
- private final CANSparkMax driveMotor;
- private final CANSparkMax turningMotor;
+ public final CANSparkMax driveMotor;
+ public final CANSparkMax turningMotor;
private final RelativeEncoder driveEncoder;
- private final RelativeEncoder turningEncoder;
+ //private final RelativeEncoder turningEncoder;
- private final PIDController turningPIDController;
+ private final SimpleMotorFeedforward driveFeedForward = new SimpleMotorFeedforward(DriveConstants.Ks, DriveConstants.Kv);
- private final AnalogInput absoluteEncoder;
- private final boolean absoluteEncoderReversed;
- private final double absoluteEncoderOffSetRad;
+ private final PIDController drivePIDController = new PIDController(DriveConstants.kP, DriveConstants.kI, DriveConstants.kD);
- public SwerveModule(int driveMotorID, int turningMotorID, boolean driveMotorReversed, boolean turningMotorReversed,
- int absoluteEncoderID, double absoluteEncoderOffset, boolean absoluteEncoderReversed) {
-
- this.absoluteEncoderOffSetRad = absoluteEncoderOffset;
- this.absoluteEncoderReversed = absoluteEncoderReversed;
- absoluteEncoder = new AnalogInput(absoluteEncoderID);
+ private final PIDController turningPidController;
+ private final PIDController drivePidController;
- driveMotor = new CANSparkMax(driveMotorID, MotorType.kBrushless);
- turningMotor = new CANSparkMax(turningMotorID, MotorType.kBrushless);
- driveMotor.setInverted(driveMotorReversed);
- turningMotor.setInverted(turningMotorReversed);
+ private final CANcoder absoluteEncoder;
- driveEncoder = driveMotor.getEncoder();
- turningEncoder = turningMotor.getEncoder();
+ private final String ModuleName;
- driveEncoder.setPositionConversionFactor(Constants.kDriveEncoderRot2Meter);
- driveEncoder.setVelocityConversionFactor(Constants.kDriveEncoderRPM2MeterPerSec);
- turningEncoder.setPositionConversionFactor(Constants.kTurningEncoderRot2Rad);
- turningEncoder.setVelocityConversionFactor(Constants.kTurningEncoderRPM2RadPerSec);
+ public SwerveModule(String ModuleName, int driveMotorId, int turningMotorId, boolean driveMotorReversed, boolean turningMotorReversed,
+ int absoluteEncoderId, double absoluteEncoderOffset, SensorDirectionValue positiveDirection) {
- turningPIDController = new PIDController(Constants.kPturning,0,0);
- turningPIDController.enableContinuousInput(-Math.PI, Math.PI);
+ this.ModuleName = ModuleName;
+ absoluteEncoder = new CANcoder(absoluteEncoderId);
+ CANcoderConfiguration canCoderConfiguration = new CANcoderConfiguration();
+ canCoderConfiguration.MagnetSensor.MagnetOffset = absoluteEncoderOffset;
+ canCoderConfiguration.MagnetSensor.SensorDirection = positiveDirection;
+ canCoderConfiguration.MagnetSensor.AbsoluteSensorRange = AbsoluteSensorRangeValue.Signed_PlusMinusHalf;
+ //absoluteEncoder.configAllSettings(canCoderConfiguration);
+ absoluteEncoder.getConfigurator().apply(canCoderConfiguration);
- resetEncoders();
+ driveMotor = new CANSparkMax(driveMotorId, MotorType.kBrushless);
+ configureMotor(driveMotor, driveMotorReversed);
+ turningMotor = new CANSparkMax(turningMotorId, MotorType.kBrushless);
+ configureMotor(turningMotor, turningMotorReversed);
- }
+ driveEncoder = driveMotor.getEncoder();
+ //turningEncoder = turningMotor.getEncoder();
+
+ //driveEncoder.setPositionConversionFactor(ModuleConstants.kDriveEncoderRot2Meter);
+ //driveEncoder.setVelocityConversionFactor(ModuleConstants.kDriveEncoderRPM2MeterPerSec);
+ //turningEncoder.setPositionConversionFactor(ModuleConstants.kTurningEncoderRot2Deg);
+ //turningEncoder.setVelocityConversionFactor(ModuleConstants.kTurningEncoderRPM2DegPerSec);
+
+ turningPidController = new PIDController(ModuleConstants.kPTurning, 0, ModuleConstants.kDTurning);
+ turningPidController.enableContinuousInput(-180, 180);
- public double getDrivePosition() {
- return 0.0; //driveEncoder.getPosition();
+ this.drivePidController = new PIDController(ModuleConstants.kPModuleDriveController, 0, ModuleConstants.kDModuleDriveController);
+
+ resetEncoders();
}
- public double getTurningPosition(){
- return turningEncoder.getPosition();
+
+ private void configureMotor(CANSparkMax motor, Boolean inverted) {
+ motor.restoreFactoryDefaults();
+ motor.setIdleMode(IdleMode.kCoast);
+ motor.setInverted(inverted);
+ motor.setSmartCurrentLimit(30);
+ motor.burnFlash();
}
- public double getDriveVelocity(){
- return driveEncoder.getVelocity();
+
+ public SwerveModulePosition getPosition() {
+ return new SwerveModulePosition(driveEncoder.getPosition(), Rotation2d.fromDegrees(getAbsoluteEncoderDeg()));
}
- public double getTurningVelocity(){
- return turningEncoder.getVelocity();
+
+ public double getDriveVelocity() {
+ return driveEncoder.getVelocity() * ModuleConstants.kDriveEncoderRPM2MeterPerSec;
}
- public double getAbsoluteEncoderRad(){
- double angle = absoluteEncoder.getVoltage() / RobotController.getCurrent5V();
- angle *= 2 * Math.PI;
- angle -= absoluteEncoderOffSetRad;
- return angle * (absoluteEncoderReversed ? -1.0 : 1.0);
+
+ public double getAbsoluteEncoderDeg() {
+ return (absoluteEncoder.getAbsolutePosition().getValue() * 360);// - absoluteEncoderOffset;
+
+ //should be in degrees???
}
public void resetEncoders() {
driveEncoder.setPosition(0);
- turningEncoder.setPosition(getAbsoluteEncoderRad());
+ //turningEncoder.setPosition(0);
}
-
+
public SwerveModuleState getState() {
- return new SwerveModuleState(getDriveVelocity(), new Rotation2d(getTurningPosition()));
+ return new SwerveModuleState(getDriveVelocity(), Rotation2d.fromDegrees(getAbsoluteEncoderDeg()));
}
public void setDesiredState(SwerveModuleState state) {
+
+ state.speedMetersPerSecond *= state.angle.minus(Rotation2d.fromDegrees(getAbsoluteEncoderDeg())).getCos();
+
+ Crashboard.toDashboard("driveVelocity", getDriveVelocity(), this.ModuleName + " Swerve");
+ Crashboard.toDashboard("driveposition", this.driveEncoder.getPosition(), this.ModuleName + " Swerve");
+
+ double driveOutput = drivePIDController.calculate(driveEncoder.getVelocity(), state.speedMetersPerSecond); // Convert to m/s
+ //Crashboard.toDashboard(this.ModuleName + " driveSpeed", driveSpeed, "Swerve");
+
+ final double driveFeedForwardOutput = driveFeedForward.calculate(state.speedMetersPerSecond);
+
if (Math.abs(state.speedMetersPerSecond) < 0.001) {
stop();
+ return;
}
-
state = SwerveModuleState.optimize(state, getState().angle);
- driveMotor.set(state.speedMetersPerSecond / Constants.kMaxSpeed);
- turningMotor.set(turningPIDController.calculate(getTurningPosition(), state.angle.getRadians()));
- SmartDashboard.putString("Swerve[" + absoluteEncoder.getChannel() + "] state", state.toString());
+
+ // Calculate the drive output from the drive PID controller. ;}
+ double driveSpeed = MathUtil.clamp(state.speedMetersPerSecond / Constants.DriveConstants.kTeleDriveMaxSpeedMetersPerSecond/* / 360*/, -.5 ,.5);
+
+ //driveMotor.set(driveSpeed);
+ Crashboard.toDashboard(this.ModuleName + " driveSpeed", driveSpeed, "Swerve");
+ Crashboard.toDashboard(this.ModuleName + " speed in mps", state.speedMetersPerSecond, "Swerve");
+
+
+ double turnSpeed = (turningPidController.calculate(getAbsoluteEncoderDeg(), state.angle.getDegrees()));
+ //System.out.println("Turn Speed Calculated " + this.ModuleName + ": " + turnSpeed);
+ if (turnSpeed > 0)
+ turnSpeed = Math.min(turnSpeed, .2);
+ else
+ turnSpeed = Math.max(turnSpeed, -.2);
+
+ //System.out.println("Turn Speed Final " + this.ModuleName + ": " + turnSpeed);
+ Crashboard.toDashboard(ModuleName + "Turn Speed Final", turnSpeed, "Swerve");
+
+ turningMotor.set(turnSpeed);
+
+ double outVoltage = driveOutput;// + driveFeedForwardOutput;
+ outVoltage = MathUtil.clamp(outVoltage, -4.0 ,4.0);
+ Crashboard.toDashboard("drive voltage PID", driveOutput, this.ModuleName + " Swerve");
+ Crashboard.toDashboard("drive voltage ff", driveFeedForwardOutput, this.ModuleName + " Swerve");
+ Crashboard.toDashboard(" output voltage", outVoltage, this.ModuleName + " Swerve");
+
+
+ //outVoltage = MathUtil.clamp(outVoltage, -5, 5);
+
+ Crashboard.toDashboard(this.ModuleName + " clamp voltage", outVoltage, "Swerve");
+
+ driveMotor.setVoltage(outVoltage);
+ //System.out.println(ModuleName + "- DriveMotorCommand: " + driveSpeed + " - True Angle: " + getAbsoluteEncoderRad() + " AngleSetPoint: " + state.angle.getDegrees() + " AngleMotorCommand: " + turnSpeed);
}
- public void stop(){
+ public void stop() {
driveMotor.set(0);
turningMotor.set(0);
}
+ public CANcoder getCANcoder() {
+ return this.absoluteEncoder;
+ }
+
+ public void logIt() {
+ Crashboard.toDashboard(ModuleName + " Wheel Angle", this.getAbsoluteEncoderDeg(), "swerve");
-}
+
+
+ }
+}
\ No newline at end of file
diff --git a/src/main/java/frc/robot/subsystems/SwerveSubsystem.java b/src/main/java/frc/robot/subsystems/SwerveSubsystem.java
index a622b11..9b40cff 100644
--- a/src/main/java/frc/robot/subsystems/SwerveSubsystem.java
+++ b/src/main/java/frc/robot/subsystems/SwerveSubsystem.java
@@ -1,32 +1,83 @@
package frc.robot.subsystems;
import com.kauailabs.navx.frc.AHRS;
-
+import edu.wpi.first.wpilibj.SPI;
+import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
+import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
-import edu.wpi.first.wpilibj.SPI;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
-import frc.robot.Constants;
+import frc.robot.Constants.DriveConstants;
+import frc.robot.helpers.Crashboard;
public class SwerveSubsystem extends SubsystemBase {
- private final SwerveModule frontRight = null;
- private final SwerveModule frontLeft = null;
- private final SwerveModule backRight = null;
- private final SwerveModule backLeft = null;
+ public static final double MAX_VOLTAGE = 12.0;
+ public final SwerveModule frontLeft;
+ public final SwerveModule frontRight;
+ public final SwerveModule backLeft;
+ public final SwerveModule backRight;
- private AHRS gyro = new AHRS(SPI.Port.kMXP);
+ private final AHRS gyro = new AHRS(SPI.Port.kMXP);
+
+ private final SwerveDriveOdometry odometer;
public SwerveSubsystem() {
+ frontLeft = new SwerveModule(
+ "Front Left",
+ DriveConstants.kFrontLeftDriveMotorPort,
+ DriveConstants.kFrontLeftTurningMotorPort,
+ DriveConstants.kFrontLeftDriveMotorReversed,
+ DriveConstants.kFrontLeftTurningMotorReversed,
+ DriveConstants.kFrontLeftDriveAbsoluteEncoderPort,
+ DriveConstants.kFrontLeftDriveAbsoluteEncoderOffsetDeg,
+ DriveConstants.kFrontLeftTurningForwardDirection);
+
+ frontRight = new SwerveModule(
+ "Front Right",
+ DriveConstants.kFrontRightDriveMotorPort,
+ DriveConstants.kFrontRightTurningMotorPort,
+ DriveConstants.kFrontRightDriveMotorReversed,
+ DriveConstants.kFrontRightTurningMotorReversed,
+ DriveConstants.kFrontRightDriveAbsoluteEncoderPort,
+ DriveConstants.kFrontRightDriveAbsoluteEncoderOffsetDeg,
+ DriveConstants.kFrontRightTurningForwardDirection);
+
+ backLeft = new SwerveModule(
+ "Back Left",
+ DriveConstants.kBackLeftDriveMotorPort,
+ DriveConstants.kBackLeftTurningMotorPort,
+ DriveConstants.kBackLeftDriveMotorReversed,
+ DriveConstants.kBackLeftTurningMotorReversed,
+ DriveConstants.kBackLeftDriveAbsoluteEncoderPort,
+ DriveConstants.kBackLeftDriveAbsoluteEncoderOffsetDeg,
+ DriveConstants.kBackLeftTurningForwardDirection);
+
+ backRight = new SwerveModule(
+ "Back Right",
+ DriveConstants.kBackRightDriveMotorPort,
+ DriveConstants.kBackRightTurningMotorPort,
+ DriveConstants.kBackRightDriveMotorReversed,
+ DriveConstants.kBackRightTurningMotorReversed,
+ DriveConstants.kBackRightDriveAbsoluteEncoderPort,
+ DriveConstants.kBackRightDriveAbsoluteEncoderOffsetDeg,
+ DriveConstants.kBackRightTurningForwardDirection);
+
+ odometer = new SwerveDriveOdometry(DriveConstants.kDriveKinematics, getRotation2d(), new SwerveModulePosition[] {
+ frontLeft.getPosition(), frontRight.getPosition(), backLeft.getPosition(), backRight.getPosition()});
+
+
+
new Thread(() -> {
try {
- zeroHeading();
Thread.sleep(1000);
- } catch(Exception e) {
+ zeroHeading();
}
+ catch (Exception e) {
+ }
}).start();
-
}
public void zeroHeading() {
@@ -34,31 +85,54 @@ public void zeroHeading() {
}
public double getHeading() {
- return Math.IEEEremainder(gyro.getAngle(),360);
+ return Math.IEEEremainder(gyro.getAngle(), 360);
}
- public Rotation2d getRotation2d(){
+ public Rotation2d getRotation2d() {
return Rotation2d.fromDegrees(getHeading());
}
+ public Pose2d getPose() {
+ return odometer.getPoseMeters();
+ }
+
@Override
- public void periodic(){
- SmartDashboard.putNumber("Robot Heading", getHeading());
+ public void periodic() {
+ odometer.update(getRotation2d(), new SwerveModulePosition[] {
+ frontLeft.getPosition(), frontRight.getPosition(),
+ backLeft.getPosition(), backRight.getPosition()
+ });
+ Crashboard.toDashboard("Robot Heading", getHeading(), "navx");
+ frontLeft.logIt();
+ frontRight.logIt();
+ backLeft.logIt();
+ backRight.logIt();
+ Crashboard.toDashboard("gyro angle", gyro.getAngle(), "navx");
+ //SmartDashboard.putNumber("Front Right Wheel Angle", frontRight.getAbsoluteEncoderDeg());
+ //SmartDashboard.putNumber("Back Left Wheel Angle", backLeft.getAbsoluteEncoderDeg());
+ //SmartDashboard.putNumber("Back Right Wheel Angle", backRight.getAbsoluteEncoderDeg());
+ //SmartDashboard.putString("Robot Location", getPose().getTranslation().toString());
}
public void stopModules() {
+
frontLeft.stop();
frontRight.stop();
backLeft.stop();
backRight.stop();
}
- //Note: the paramater SwerveModuleState must be of length 4
public void setModuleStates(SwerveModuleState[] desiredStates) {
- SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, Constants.kMaxSpeed);
+ SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, DriveConstants.kPhysicalMaxSpeedMetersPerSecond);
frontLeft.setDesiredState(desiredStates[0]);
frontRight.setDesiredState(desiredStates[1]);
backLeft.setDesiredState(desiredStates[2]);
backRight.setDesiredState(desiredStates[3]);
+
+
+ }
+
+ public SwerveModuleState[] getModuleStates() {
+ return new SwerveModuleState[] {frontLeft.getState(), frontLeft.getState(), backLeft.getState(), backRight.getState()};
}
-}
+}
\ No newline at end of file
diff --git a/vendordeps/PhoenixProAnd5.json b/vendordeps/PhoenixProAnd5.json
new file mode 100644
index 0000000..21206b0
--- /dev/null
+++ b/vendordeps/PhoenixProAnd5.json
@@ -0,0 +1,458 @@
+{
+ "fileName": "PhoenixProAnd5.json",
+ "name": "CTRE-Phoenix (Pro And v5)",
+ "version": "23.0.12",
+ "frcYear": 2023,
+ "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a",
+ "mavenUrls": [
+ "https://maven.ctr-electronics.com/release/"
+ ],
+ "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/PhoenixProAnd5-frc2023-latest.json",
+ "javaDependencies": [
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "api-java",
+ "version": "5.30.4"
+ },
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "wpiapi-java",
+ "version": "5.30.4"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro",
+ "artifactId": "wpiapi-java",
+ "version": "23.0.12"
+ }
+ ],
+ "jniDependencies": [
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "cci",
+ "version": "5.30.4",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "cci-sim",
+ "version": "5.30.4",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro",
+ "artifactId": "tools",
+ "version": "23.0.12",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "tools-sim",
+ "version": "23.0.12",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simTalonSRX",
+ "version": "23.0.12",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simTalonFX",
+ "version": "23.0.12",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simVictorSPX",
+ "version": "23.0.12",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simPigeonIMU",
+ "version": "23.0.12",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simCANCoder",
+ "version": "23.0.12",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simProTalonFX",
+ "version": "23.0.12",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simProCANcoder",
+ "version": "23.0.12",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simProPigeon2",
+ "version": "23.0.12",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ }
+ ],
+ "cppDependencies": [
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "wpiapi-cpp",
+ "version": "5.30.4",
+ "libName": "CTRE_Phoenix_WPI",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "api-cpp",
+ "version": "5.30.4",
+ "libName": "CTRE_Phoenix",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "cci",
+ "version": "5.30.4",
+ "libName": "CTRE_PhoenixCCI",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro",
+ "artifactId": "tools",
+ "version": "23.0.12",
+ "libName": "CTRE_PhoenixTools",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "wpiapi-cpp-sim",
+ "version": "5.30.4",
+ "libName": "CTRE_Phoenix_WPISim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "api-cpp-sim",
+ "version": "5.30.4",
+ "libName": "CTRE_PhoenixSim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "cci-sim",
+ "version": "5.30.4",
+ "libName": "CTRE_PhoenixCCISim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "tools-sim",
+ "version": "23.0.12",
+ "libName": "CTRE_PhoenixTools_Sim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simTalonSRX",
+ "version": "23.0.12",
+ "libName": "CTRE_SimTalonSRX",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simTalonFX",
+ "version": "23.0.12",
+ "libName": "CTRE_SimTalonFX",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simVictorSPX",
+ "version": "23.0.12",
+ "libName": "CTRE_SimVictorSPX",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simPigeonIMU",
+ "version": "23.0.12",
+ "libName": "CTRE_SimPigeonIMU",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simCANCoder",
+ "version": "23.0.12",
+ "libName": "CTRE_SimCANCoder",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simProTalonFX",
+ "version": "23.0.12",
+ "libName": "CTRE_SimProTalonFX",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simProCANcoder",
+ "version": "23.0.12",
+ "libName": "CTRE_SimProCANcoder",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "simProPigeon2",
+ "version": "23.0.12",
+ "libName": "CTRE_SimProPigeon2",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro",
+ "artifactId": "wpiapi-cpp",
+ "version": "23.0.12",
+ "libName": "CTRE_PhoenixPro_WPI",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenixpro.sim",
+ "artifactId": "wpiapi-cpp-sim",
+ "version": "23.0.12",
+ "libName": "CTRE_PhoenixPro_WPISim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ }
+ ]
+}
\ No newline at end of file