Skip to content

Commit

Permalink
feat: swerve code from swerve-base
Browse files Browse the repository at this point in the history
mebrahimaleem committed Jan 6, 2024
1 parent 3be069e commit c677ac3
Showing 7 changed files with 1,014 additions and 1 deletion.
93 changes: 93 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,93 @@
// 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 edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;

/**
* 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.
*
* <p>
* It is advised to statically import this class (or one of its inner classes)
* wherever the
* constants are needed, to reduce verbosity.
*/
public final class Constants {

/**
* Input/Output constants
*/
public static class IOConstants {
public static final int kDriverControllerPort = 0;

public static final double kControllerDeadband = 0.2;
public static final double kSlowModeScalar = 0.8;
}

public static final class DriveConstants {
// TODO: set motor and encoder constants
public static final int kFrontLeftDriveMotorPort = 1;
public static final int kRearLeftDriveMotorPort = 3;
public static final int kFrontRightDriveMotorPort = 5;
public static final int kRearRightDriveMotorPort = 7;

public static final int kFrontLeftTurningMotorPort = 2;
public static final int kRearLeftTurningMotorPort = 4;
public static final int kFrontRightTurningMotorPort = 6;
public static final int kRearRightTurningMotorPort = 8;

public static final int kFrontLeftTurningEncoderPort = 9;
public static final int kRearLeftTurningEncoderPort = 10;
public static final int kFrontRightTurningEncoderPort = 11;
public static final int kRearRightTurningEncoderPort = 12;

public static final double kFrontLeftTurningEncoderOffset = 0;
public static final double kRearLeftTurningEncoderOffset = 0;
public static final double kFrontRightTurningEncoderOffset = 0;
public static final double kRearRightTurningEncoderOffset = 0;

// TODO: Test motor orientations before driving on an actual robot
public static final boolean kFrontLeftDriveMotorReversed = false;
public static final boolean kRearLeftDriveMotorReversed = false;
public static final boolean kFrontRightDriveMotorReversed = true;
public static final boolean kRearRightDriveMotorReversed = true;

/** Distance between centers of right and left wheels on robot (in meters). */
public static final double kTrackWidth = 0.5;

/** Distance between front and back wheels on robot (in meters). */
public static final double kWheelBase = 0.5;

/** Diameter of each wheel in the SDS MK4i swerve module (in meters) */
public static final double kWheelDiameterMeters = 0.1;

/** Gear ratio between the motor and the wheel. */
public static final double kDrivingGearRatio = 8.14; // SDS MK4i's in L1 configuration

// TODO: Tune this PID before running on a robot on the ground
public static final double kPModuleTurningController = -0.3;

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));

/** For a a SDS Mk4i L1 swerve base with Neos */
public static final double kMaxSpeedMetersPerSecond = 3.6576;
/** For a a SDS Mk4i L1 swerve base with Neos */
public static final double kMaxAngularSpeedRadiansPerSecond = 15.24 / 3;

/** Heading Correction */
public static final double kHeadingCorrectionTurningStopTime = 0.2;
// TODO: Tune this PID before running on a robot on the ground
public static final double kPHeadingCorrectionController = 5;
}
}
57 changes: 56 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
@@ -4,15 +4,70 @@

package frc.robot;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import frc.robot.Constants.DriveConstants;
import frc.robot.Constants.IOConstants;
import frc.robot.subsystems.DriveSubsystem;


public class RobotContainer {
// The robot's subsystems and commands are defined here
private final DriveSubsystem m_robotDrive = new DriveSubsystem();

private final XboxController m_driverController = new XboxController(IOConstants.kDriverControllerPort);

/**
* The container for the robot. Contains subsystems, OI devices, and commands.
*/
public RobotContainer() {
// Configure the trigger bindings
configureBindings();

m_robotDrive.setDefaultCommand(
new RunCommand(
() -> m_robotDrive.drive(
MathUtil.applyDeadband(
-m_driverController.getLeftY(),
IOConstants.kControllerDeadband)
* DriveConstants.kMaxSpeedMetersPerSecond
* (1 - m_driverController
.getLeftTriggerAxis()
* IOConstants.kSlowModeScalar)
* 0.8,
MathUtil.applyDeadband(
-m_driverController.getLeftX(),
IOConstants.kControllerDeadband)
* DriveConstants.kMaxSpeedMetersPerSecond
* (1 - m_driverController
.getLeftTriggerAxis()
* IOConstants.kSlowModeScalar)
* 0.8,
MathUtil.applyDeadband(
m_driverController.getRightX(),
IOConstants.kControllerDeadband)
* DriveConstants.kMaxAngularSpeedRadiansPerSecond
* (1 - m_driverController
.getLeftTriggerAxis()
* IOConstants.kSlowModeScalar)
/ 2,
!m_driverController.getRightBumper()),
m_robotDrive));
}

private void configureBindings() {}
/**
* Use this method to define your button->command mappings.
*/
private void configureBindings() {
new JoystickButton(m_driverController, Button.kStart.value)
.onTrue(new InstantCommand(m_robotDrive::zeroHeading, m_robotDrive));
}

public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
226 changes: 226 additions & 0 deletions src/main/java/frc/robot/subsystems/DriveSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,226 @@
// 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.subsystems;

import com.kauailabs.navx.frc.AHRS;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.PIDController;
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.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.DriveConstants;
import frc.robot.Robot;

public class DriveSubsystem extends SubsystemBase {
private final SwerveModule m_frontLeft = new SwerveModule(
DriveConstants.kFrontLeftDriveMotorPort,
DriveConstants.kFrontLeftTurningMotorPort,
DriveConstants.kFrontLeftTurningEncoderPort,
DriveConstants.kFrontLeftDriveMotorReversed,
DriveConstants.kFrontLeftTurningEncoderOffset);

private final SwerveModule m_rearLeft = new SwerveModule(
DriveConstants.kRearLeftDriveMotorPort,
DriveConstants.kRearLeftTurningMotorPort,
DriveConstants.kRearLeftTurningEncoderPort,
DriveConstants.kRearLeftDriveMotorReversed,
DriveConstants.kRearLeftTurningEncoderOffset);

private final SwerveModule m_frontRight = new SwerveModule(
DriveConstants.kFrontRightDriveMotorPort,
DriveConstants.kFrontRightTurningMotorPort,
DriveConstants.kFrontRightTurningEncoderPort,
DriveConstants.kFrontRightDriveMotorReversed,
DriveConstants.kFrontRightTurningEncoderOffset);

private final SwerveModule m_rearRight = new SwerveModule(
DriveConstants.kRearRightDriveMotorPort,
DriveConstants.kRearRightTurningMotorPort,
DriveConstants.kRearRightTurningEncoderPort,
DriveConstants.kRearRightDriveMotorReversed,
DriveConstants.kRearRightTurningEncoderOffset);

private final AHRS m_gyro = new AHRS();
private double m_gyroAngle;

private final Timer m_headingCorrectionTimer = new Timer();
private final PIDController m_headingCorrectionPID = new PIDController(DriveConstants.kPHeadingCorrectionController,
0, 0);
private SwerveModulePosition[] m_swerveModulePositions = new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),
m_rearLeft.getPosition(),
m_rearRight.getPosition()
};

// TODO: Experiment with different std devs in the pose estimator
private final SwerveDrivePoseEstimator m_poseEstimator = new SwerveDrivePoseEstimator(DriveConstants.kDriveKinematics,
m_gyro.getRotation2d(), m_swerveModulePositions, new Pose2d());

private final Field2d m_field = new Field2d();

/** Creates a new DriveSubsystem. */
public DriveSubsystem() {
SmartDashboard.putData("Field", m_field);
m_headingCorrectionTimer.restart();
m_headingCorrectionPID.enableContinuousInput(-Math.PI, Math.PI);
}

@Override
public void periodic() {
// This method will be called once per scheduler run

m_swerveModulePositions = new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),
m_rearLeft.getPosition(),
m_rearRight.getPosition()
};

m_poseEstimator.update(Robot.isReal() ? m_gyro.getRotation2d() : new Rotation2d(m_gyroAngle), m_swerveModulePositions);

m_field.setRobotPose(m_poseEstimator.getEstimatedPosition());

SmartDashboard.putNumber("gyro angle", m_gyro.getAngle());
SmartDashboard.putNumber("odometryX", m_poseEstimator.getEstimatedPosition().getX());
SmartDashboard.putNumber("odometryY", m_poseEstimator.getEstimatedPosition().getY());

// AdvantageScope Logging
double[] logData = {
m_frontLeft.getPosition().angle.getDegrees(), m_frontLeft.driveOutput,
m_frontRight.getPosition().angle.getDegrees(), m_frontRight.driveOutput,
m_rearLeft.getPosition().angle.getDegrees(), m_rearLeft.driveOutput,
m_rearRight.getPosition().angle.getDegrees(), m_rearRight.driveOutput,
};
SmartDashboard.putNumberArray("AdvantageScope Swerve States", logData);
}

/**
* Returns the currently-estimated pose of the robot.
*
* @return The pose.
*/
public Pose2d getPose() {
return m_poseEstimator.getEstimatedPosition();
}

/**
* Method to drive the robot using joystick info.
*
* @param xSpeed Speed of the robot in the x direction (forward).
* @param ySpeed Speed of the robot in the y direction (sideways).
* @param rotation Angular rotation speed of the robot.
* @param fieldRelative Whether the provided x and y speeds are relative to the
* field.
*/
public void drive(double xSpeed, double ySpeed, double rotation, boolean fieldRelative) {
// If we are rotating, reset the timer
if (rotation != 0) {
m_headingCorrectionTimer.reset();
}

/*
* Heading correction helps maintain the same heading and
* prevents rotational drive while our robot is translating
*
* For heading correction we use a timer to ensure that we
* lose all rotational momentum before saving the heading
* that we want to maintain
*/

// TODO: Test heading correction without timer
// TODO: Test heading correction using gyro's rotational velocity (if it is 0
// then set heading instead of timer)

// Save our desired rotation to a variable we can add our heading correction
// adjustments to
double calculatedRotation = rotation;

double currentAngle = MathUtil.angleModulus(m_gyro.getRotation2d().getRadians());

// If we are not translating or if not enough time has passed since the last
// time we rotated
if ((xSpeed == 0 && ySpeed == 0)
|| m_headingCorrectionTimer.get() < DriveConstants.kHeadingCorrectionTurningStopTime) {
// Update our desired angle
m_headingCorrectionPID.setSetpoint(currentAngle);
} else {
// If we are translating or if we have not rotated for a long enough time
// then maintain our desired angle
calculatedRotation = m_headingCorrectionPID.calculate(currentAngle);
}

// Depending on whether the robot is being driven in field relative, calculate
// the desired states for each of the modules
SwerveModuleState[] swerveModuleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates(
fieldRelative
? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeed, ySpeed, calculatedRotation,
Robot.isReal() ? m_gyro.getRotation2d() : new Rotation2d(m_gyroAngle))
: new ChassisSpeeds(xSpeed, ySpeed, calculatedRotation));

setModuleStates(swerveModuleStates);
}

/**
* Resets the odometry to the specified pose.
*
* @param pose The pose to which to set the odometry.
*/
public void resetOdometry(Pose2d pose) {
m_poseEstimator.resetPosition(
Robot.isReal() ? m_gyro.getRotation2d() : new Rotation2d(m_gyroAngle),
new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),
m_rearLeft.getPosition(),
m_rearRight.getPosition()
},
pose);
}

/** Zeroes the heading of the robot. */
public void zeroHeading() {
m_gyro.reset();
m_gyroAngle = 0;
}

/**
* Sets the swerve ModuleStates.
*
* @param desiredStates The desired SwerveModule states.
*/
public void setModuleStates(SwerveModuleState[] desiredStates) {
SwerveDriveKinematics.desaturateWheelSpeeds(
desiredStates, DriveConstants.kMaxSpeedMetersPerSecond);
m_frontLeft.setDesiredState(desiredStates[0]);
m_frontRight.setDesiredState(desiredStates[1]);
m_rearLeft.setDesiredState(desiredStates[2]);
m_rearRight.setDesiredState(desiredStates[3]);

// AdvantageScope Logging
double[] logData = {
desiredStates[0].angle.getDegrees(), desiredStates[0].speedMetersPerSecond,
desiredStates[1].angle.getDegrees(), desiredStates[1].speedMetersPerSecond,
desiredStates[2].angle.getDegrees(), desiredStates[2].speedMetersPerSecond,
desiredStates[3].angle.getDegrees(), desiredStates[3].speedMetersPerSecond,
};
SmartDashboard.putNumberArray("AdvantageScope Swerve Desired States", logData);

// Takes the integral of the rotation speed to find the current angle for the
// simulator
m_gyroAngle += DriveConstants.kDriveKinematics.toChassisSpeeds(desiredStates).omegaRadiansPerSecond
* Robot.kDefaultPeriod;
}

}
104 changes: 104 additions & 0 deletions src/main/java/frc/robot/subsystems/SwerveModule.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
// 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.subsystems;

import com.ctre.phoenix.sensors.CANCoder;
import com.ctre.phoenix.sensors.SensorTimeBase;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMax.IdleMode;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import frc.robot.Constants.DriveConstants;
import frc.robot.Robot;

/** Add your docs here. */
public class SwerveModule {
private final CANSparkMax m_driveMotor;
private final CANSparkMax m_turningMotor;

private final CANCoder m_turningEncoder;

private final PIDController m_turningPIDController = new PIDController(DriveConstants.kPModuleTurningController, 0,
0);

private SwerveModuleState m_state = new SwerveModuleState();
private double m_distance;

public double driveOutput;
public double turnOutput;

/**
* Constructs a {@link SwerveModule}.
*
* @param driveMotorPort The port of the drive motor.
* @param turningMotorPort The port of the turning motor.
* @param turningEncoderPort The port of the turning encoder.
* @param driveMotorReversed Whether the drive motor is reversed.
* @param turningEncoderOffset Offset of the turning encoder.
*/
public SwerveModule(
int driveMotorPort,
int turningMotorPort,
int turningEncoderPort,
boolean driveMotorReversed,
double turningEncoderOffset) {
m_driveMotor = new CANSparkMax(driveMotorPort, MotorType.kBrushless);
m_turningMotor = new CANSparkMax(turningMotorPort, MotorType.kBrushless);
m_turningEncoder = new CANCoder(turningEncoderPort);

// converts default units to meters per second
m_driveMotor.getEncoder().setVelocityConversionFactor(
DriveConstants.kWheelDiameterMeters * Math.PI / 60 / DriveConstants.kDrivingGearRatio);

m_driveMotor.setInverted(driveMotorReversed);

m_turningMotor.setIdleMode(IdleMode.kBrake);

// converts default units of CANCoders to radians
m_turningEncoder.configFeedbackCoefficient(Math.toRadians(0.087890625), "radians", SensorTimeBase.PerSecond);
m_turningEncoder.configMagnetOffset(-turningEncoderOffset);

m_turningPIDController.enableContinuousInput(-Math.PI, Math.PI);
}

/**
* Returns the current position of the module.
*
* @return The current position of the module.
*/
public SwerveModulePosition getPosition() {
m_distance += m_state.speedMetersPerSecond * Robot.kDefaultPeriod;

// If the robot is real, then return the swerve module state by reading from the
// actual encoders
// If the robot is simulated, then return the swerve module state using the
// expected values
return Robot.isReal()
? new SwerveModulePosition(m_driveMotor.getEncoder().getPosition(),
new Rotation2d(m_turningEncoder.getAbsolutePosition()))
: new SwerveModulePosition(m_distance, m_state.angle);
}

/**
* Sets the desired state for the module.
*
* @param desiredState Desired state with speed and angle.
*/
public void setDesiredState(SwerveModuleState desiredState) {
m_state = SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.getAbsolutePosition()));

driveOutput = m_state.speedMetersPerSecond / DriveConstants.kMaxSpeedMetersPerSecond;

turnOutput = m_turningPIDController.calculate(m_turningEncoder.getAbsolutePosition(),
m_state.angle.getRadians());

m_driveMotor.set(driveOutput);
m_turningMotor.set(turnOutput);
}
}
39 changes: 39 additions & 0 deletions vendordeps/NavX.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
{
"fileName": "NavX.json",
"name": "KauaiLabs_navX_FRC",
"version": "2023.0.4",
"uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
"mavenUrls": [
"https://dev.studica.com/maven/release/2023/"
],
"jsonUrl": "https://dev.studica.com/releases/2023/NavX.json",
"javaDependencies": [
{
"groupId": "com.kauailabs.navx.frc",
"artifactId": "navx-frc-java",
"version": "2023.0.4"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.kauailabs.navx.frc",
"artifactId": "navx-frc-cpp",
"version": "2023.0.4",
"headerClassifier": "headers",
"sourcesClassifier": "sources",
"sharedLibrary": false,
"libName": "navx_frc",
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"linuxathena",
"linuxraspbian",
"linuxarm32",
"linuxarm64",
"linuxx86-64",
"osxuniversal",
"windowsx86-64"
]
}
]
}
423 changes: 423 additions & 0 deletions vendordeps/Phoenix.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,423 @@
{
"fileName": "Phoenix.json",
"name": "CTRE-Phoenix (v5)",
"version": "5.31.0+23.2.2",
"frcYear": 2023,
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [
"https://maven.ctr-electronics.com/release/"
],
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2023-latest.json",
"javaDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
"version": "5.31.0"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
"version": "5.31.0"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.31.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxathena"
],
"simMode": "hwsim"
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.31.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6",
"artifactId": "tools",
"version": "23.2.2",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxathena"
],
"simMode": "hwsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim",
"version": "23.2.2",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX",
"version": "23.2.2",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonFX",
"version": "23.2.2",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX",
"version": "23.2.2",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU",
"version": "23.2.2",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simCANCoder",
"version": "23.2.2",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX",
"version": "23.2.2",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder",
"version": "23.2.2",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2",
"version": "23.2.2",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
}
],
"cppDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp",
"version": "5.31.0",
"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.31.0",
"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.31.0",
"libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxathena"
],
"simMode": "hwsim"
},
{
"groupId": "com.ctre.phoenix6",
"artifactId": "tools",
"version": "23.2.2",
"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.31.0",
"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.31.0",
"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.31.0",
"libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim",
"version": "23.2.2",
"libName": "CTRE_PhoenixTools_Sim",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX",
"version": "23.2.2",
"libName": "CTRE_SimTalonSRX",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonFX",
"version": "23.2.2",
"libName": "CTRE_SimTalonFX",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX",
"version": "23.2.2",
"libName": "CTRE_SimVictorSPX",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU",
"version": "23.2.2",
"libName": "CTRE_SimPigeonIMU",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simCANCoder",
"version": "23.2.2",
"libName": "CTRE_SimCANCoder",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX",
"version": "23.2.2",
"libName": "CTRE_SimProTalonFX",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder",
"version": "23.2.2",
"libName": "CTRE_SimProCANcoder",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2",
"version": "23.2.2",
"libName": "CTRE_SimProPigeon2",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
}
]
}
73 changes: 73 additions & 0 deletions vendordeps/REVLib.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
{
"fileName": "REVLib.json",
"name": "REVLib",
"version": "2023.1.3",
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
"mavenUrls": [
"https://maven.revrobotics.com/"
],
"jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2023.json",
"javaDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-java",
"version": "2023.1.3"
}
],
"jniDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2023.1.3",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxarm64",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"osxuniversal"
]
}
],
"cppDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-cpp",
"version": "2023.1.3",
"libName": "REVLib",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxarm64",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"osxuniversal"
]
},
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2023.1.3",
"libName": "REVLibDriver",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxarm64",
"linuxx86-64",
"linuxathena",
"linuxarm32",
"osxuniversal"
]
}
]
}

0 comments on commit c677ac3

Please sign in to comment.