diff --git a/build.gradle b/build.gradle index 48935bc8..7d3cee78 100644 --- a/build.gradle +++ b/build.gradle @@ -1,6 +1,6 @@ plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2024.1.1" + id "edu.wpi.first.GradleRIO" version "2024.2.1" id "com.peterabeles.gversion" version "1.10" id "org.sonarqube" version "4.4.1.3373" } diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 9e386ac2..7b608403 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -54,7 +54,7 @@ private DriveConstants() { // kP, kI, kD in order protected static final double[] DRIVE_FB_GAINS = new double[]{0.05, 0.0, 0.0}; // kP, kI, kD in order - protected static final double[] TURN_FB_GAINS = new double[]{7.0, 0.0, 0.0}; + protected static final double[] TURN_FB_GAINS = new double[]{0.1, 0.0, 0.0}; public static final ModuleConstants FL_MOD_CONSTANTS = new ModuleConstants( 0, @@ -62,7 +62,7 @@ private DriveConstants() { DRIVE_FF_GAINS, DRIVE_FB_GAINS, TURN_FB_GAINS, - Units.rotationsToDegrees(0.457764), // offset + Units.rotationsToDegrees(-0.017578), // offset 0.457764 true, // inversion ModuleConstants.GearRatios.L3 ); @@ -84,8 +84,8 @@ private DriveConstants() { DRIVE_FF_GAINS, DRIVE_FB_GAINS, TURN_FB_GAINS, - Units.rotationsToDegrees(-0.017578), - false, + Units.rotationsToDegrees(0.457764), + true, ModuleConstants.GearRatios.L3 ); @@ -96,7 +96,7 @@ private DriveConstants() { DRIVE_FB_GAINS, TURN_FB_GAINS, Units.rotationsToDegrees(-0.263916), - false, + true, ModuleConstants.GearRatios.L3 ); } diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index ca8a7510..c08031ca 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -58,7 +58,9 @@ public class RobotContainer { private final LoggedDashboardChooser autoChooser; private final LoggedDashboardNumber wristPower; + private final LoggedDashboardNumber wristPosition; private final LoggedDashboardNumber armPower; + private final LoggedDashboardNumber armPosition; /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { @@ -67,10 +69,10 @@ public RobotContainer() { // Real robot, instantiate hardware IO implementations m_driveSubsystem = new DriveSubsystem( new GyroIOPigeon1(12), - new ModuleIOTalonFX(Constants.DriveConstants.FL_MOD_CONSTANTS), - new ModuleIOTalonFX(Constants.DriveConstants.FR_MOD_CONSTANTS), - new ModuleIOTalonFX(Constants.DriveConstants.BL_MOD_CONSTANTS), - new ModuleIOTalonFX(Constants.DriveConstants.BR_MOD_CONSTANTS)); + new ModuleIOTalonFX(Constants.DriveConstants.FL_MOD_CONSTANTS), + new ModuleIOTalonFX(Constants.DriveConstants.FR_MOD_CONSTANTS), + new ModuleIOTalonFX(Constants.DriveConstants.BL_MOD_CONSTANTS), + new ModuleIOTalonFX(Constants.DriveConstants.BR_MOD_CONSTANTS)); m_shooter = new ShooterSubsystem(new ShooterIOPrototype()); m_armSubsystem = new ArmSubsystem(new ArmIOPrototype()); } @@ -83,7 +85,7 @@ public RobotContainer() { new ModuleIO() {}, new ModuleIO() {}); m_shooter = new ShooterSubsystem(new ShooterIO() {}); - m_armSubsystem = new ArmSubsystem(new ArmIOPrototype()); + m_armSubsystem = new ArmSubsystem(new ArmIOPrototype() {}); } case SIM -> { // Sim robot, instantiate physics sim IO implementations @@ -122,7 +124,9 @@ public RobotContainer() { armPower = new LoggedDashboardNumber("Arm Power", 0.0); + armPosition = new LoggedDashboardNumber("Arm Position", 0.0); wristPower = new LoggedDashboardNumber("Wrist Power", 0.0); + wristPosition = new LoggedDashboardNumber("Wrist Position", 0.0); // Set up feedforward characterization autoChooser.addOption( @@ -146,29 +150,33 @@ private void configureButtonBindings() { m_driveSubsystem.setDefaultCommand( DriveCommands.joystickDrive( m_driveSubsystem, - () -> -controller.getLeftY(), () -> -controller.getLeftX(), + () -> -controller.getLeftY(), () -> -controller.getRightX())); - controller.x().onTrue(Commands.runOnce(m_driveSubsystem::stopWithX, m_driveSubsystem)); - controller - .b() - .onTrue( - Commands.runOnce( - () -> - m_driveSubsystem.setPose( - new Pose2d(m_driveSubsystem.getPose().getTranslation(), new Rotation2d())), - m_driveSubsystem) - .ignoringDisable(true)); +// controller.x().onTrue(Commands.runOnce(m_driveSubsystem::stopWithX, m_driveSubsystem)); +// controller +// .b() +// .onTrue( +// Commands.runOnce( +// () -> +// m_driveSubsystem.setPose( +// new Pose2d(m_driveSubsystem.getPose().getTranslation(), new Rotation2d())), +// m_driveSubsystem) +// .ignoringDisable(true)); controller.a().whileTrue(m_armSubsystem.setShoulderPowerFactory(armPower.get())) .whileFalse(m_armSubsystem.setShoulderPowerFactory(0.0)); controller.y().whileTrue(m_armSubsystem.setShoulderPowerFactory(-armPower.get())) .whileFalse(m_armSubsystem.setShoulderPowerFactory(0.0)); + controller.b().whileTrue(m_armSubsystem.setShoulderPositionFactory(armPosition.get())) + .whileFalse(m_armSubsystem.setShoulderPositionFactory(0.0)); controller.leftBumper().whileTrue(m_armSubsystem.setWristPowerFactory(wristPower.get())) .whileFalse(m_armSubsystem.setWristPowerFactory(0.0)); controller.rightBumper().whileTrue(m_armSubsystem.setWristPowerFactory(-wristPower.get())) .whileFalse(m_armSubsystem.setWristPowerFactory(0.0)); + controller.x().whileTrue(m_armSubsystem.setWristPositionFactory(wristPosition.get())) + .whileFalse(m_armSubsystem.setWristPositionFactory(0.0)); } diff --git a/src/main/java/frc/robot/subsystems/arm/ArmIOPrototype.java b/src/main/java/frc/robot/subsystems/arm/ArmIOPrototype.java index 29e80aed..d9a46e41 100644 --- a/src/main/java/frc/robot/subsystems/arm/ArmIOPrototype.java +++ b/src/main/java/frc/robot/subsystems/arm/ArmIOPrototype.java @@ -1,14 +1,41 @@ package frc.robot.subsystems.arm; +import com.ctre.phoenix6.controls.PositionVoltage; import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.hardware.core.CoreTalonFX; +import lib.properties.phoenix6.Phoenix6PidPropertyBuilder; +import lib.properties.phoenix6.PidPropertyPublic; public class ArmIOPrototype implements ArmIO { private final TalonFX m_shoulder; private final TalonFX m_wrist; + private final PidPropertyPublic m_shoulderPID; + private final PidPropertyPublic m_wristPID; + public ArmIOPrototype() { m_shoulder = new TalonFX(23); m_wrist = new TalonFX(24); + m_shoulderPID = new Phoenix6PidPropertyBuilder( + "Arm/Shoulder PID", + false, + m_shoulder, + 0) + .addP(0.0) + .addI(0.0) + .addD(0.0) + .build(); + + m_wristPID = new Phoenix6PidPropertyBuilder( + "Arm/Wrist PID", + false, + m_wrist, + 0) + .addP(0.0) + .addI(0.0) + .addD(0.0) + .build(); + } @Override @@ -16,8 +43,20 @@ public void setShoulderVoltage(double voltage){ m_shoulder.setVoltage(voltage); } + @Override + public void setShoulderAngle(double degrees) { + final PositionVoltage m_request = new PositionVoltage(0).withSlot(0); + m_shoulder.setControl(m_request.withPosition(degrees / 360.0)); + } + @Override public void setWristVoltage(double voltage){ m_wrist.setVoltage(voltage); } -} \ No newline at end of file + + @Override + public void setWristAngle(double degrees) { + final PositionVoltage m_request = new PositionVoltage(0).withSlot(0); + m_wrist.setControl(m_request.withPosition(degrees / 360.0)); + } +} diff --git a/src/main/java/frc/robot/subsystems/arm/ArmSubsystem.java b/src/main/java/frc/robot/subsystems/arm/ArmSubsystem.java index aaa6de9a..d6d23b9f 100644 --- a/src/main/java/frc/robot/subsystems/arm/ArmSubsystem.java +++ b/src/main/java/frc/robot/subsystems/arm/ArmSubsystem.java @@ -10,19 +10,30 @@ public ArmSubsystem(ArmIO io) { m_io = io; } - public void setShoulderPower(double power){ - m_io.setShoulderVoltage(power * 12.0); - } - public void setWristPower(double power){ - m_io.setWristVoltage(power * 12.0); + public void setShoulderPower(double power) {m_io.setShoulderVoltage(power * 12.0);} + + public void setShoulderPosition(double degrees) {m_io.setShoulderAngle(degrees);} + + public void setWristPower(double power) {m_io.setWristVoltage(power * 12.0);} + + public void setWristPosition(double degrees) { + m_io.setWristAngle(degrees); } public Command setShoulderPowerFactory(double power) { return runOnce(() -> setShoulderPower(power)); } + public Command setShoulderPositionFactory(double degrees) { + return runOnce(() -> setShoulderPosition(degrees)); + } + public Command setWristPowerFactory(double power) { return runOnce(() -> setWristPower(power)); } + + public Command setWristPositionFactory(double degrees) { + return runOnce(() -> setWristPosition(degrees)); + } } diff --git a/src/main/java/frc/robot/subsystems/drive/module/Module.java b/src/main/java/frc/robot/subsystems/drive/module/Module.java index a61511fa..7ecf28b4 100644 --- a/src/main/java/frc/robot/subsystems/drive/module/Module.java +++ b/src/main/java/frc/robot/subsystems/drive/module/Module.java @@ -53,7 +53,7 @@ public Module(ModuleIO io) { case REAL, REPLAY -> { m_driveFeedforward = new SimpleMotorFeedforward(0.1, 0.13); m_driveFeedback = new PIDController(0.05, 0.0, 0.0); - m_turnFeedback = new PIDController(7.0, 0.0, 0.0); + m_turnFeedback = new PIDController(0.1, 0.0, 0.0); } case SIM -> { m_driveFeedforward = new SimpleMotorFeedforward(0.0, 0.13); @@ -90,8 +90,7 @@ public void periodic() { // Run closed loop turn control if (m_angleSetpoint != null) { - m_io.setTurnPositionDegs( - m_turnFeedback.calculate(getAngle().getRadians(), m_angleSetpoint.getRadians())); + m_io.setTurnPositionDegs(m_angleSetpoint.minus(m_turnRelativeOffset).getRotations()); // Run closed loop drive control // Only allowed if closed loop turn control is running @@ -104,10 +103,10 @@ public void periodic() { double adjustSpeedSetpoint = m_speedSetpoint * Math.cos(m_turnFeedback.getPositionError()); // Run drive controller - double velocityRadPerSec = adjustSpeedSetpoint / WHEEL_RADIUS; - m_io.setDriveVelocityMPS( - m_driveFeedforward.calculate(velocityRadPerSec) - + m_driveFeedback.calculate(m_inputs.getDriveVelocityRadPerSec(), velocityRadPerSec)); + m_io.setDriveVelocityMPS(adjustSpeedSetpoint); +// m_io.setDriveVelocityMPS( +// m_driveFeedforward.calculate(velocityRadPerSec) +// + m_driveFeedback.calculate(m_inputs.getDriveVelocityRadPerSec(), velocityRadPerSec)); } } diff --git a/src/main/java/frc/robot/subsystems/drive/module/ModuleConstants.java b/src/main/java/frc/robot/subsystems/drive/module/ModuleConstants.java index d215cf77..f6abec07 100644 --- a/src/main/java/frc/robot/subsystems/drive/module/ModuleConstants.java +++ b/src/main/java/frc/robot/subsystems/drive/module/ModuleConstants.java @@ -55,7 +55,7 @@ public ModuleConstants(int id, DEFAULT_WHEEL_RADIUS_METERS * 2 * Math.PI, inverted, !inverted, - !inverted, + false, Rotation2d.fromDegrees(offsetDegs), id, ids[0], ids[1], ids[2], diff --git a/src/main/java/frc/robot/subsystems/drive/module/ModuleIOSparkMax.java b/src/main/java/frc/robot/subsystems/drive/module/ModuleIOSparkMax.java deleted file mode 100644 index e69de29b..00000000 diff --git a/src/main/java/frc/robot/subsystems/drive/module/ModuleIOTalonFX.java b/src/main/java/frc/robot/subsystems/drive/module/ModuleIOTalonFX.java index 7deb38d2..583332c1 100644 --- a/src/main/java/frc/robot/subsystems/drive/module/ModuleIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/drive/module/ModuleIOTalonFX.java @@ -20,7 +20,6 @@ import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.PositionVoltage; import com.ctre.phoenix6.controls.VelocityVoltage; -import com.ctre.phoenix6.controls.VoltageOut; import com.ctre.phoenix6.hardware.CANcoder; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue; @@ -29,8 +28,10 @@ import com.ctre.phoenix6.signals.SensorDirectionValue; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import lib.properties.phoenix6.Phoenix6PidPropertyBuilder; import lib.properties.phoenix6.PidPropertyPublic; +import org.littletonrobotics.junction.Logger; import java.util.Queue; @@ -51,8 +52,8 @@ public class ModuleIOTalonFX implements ModuleIO { private final TalonFX m_driveTalon; private final TalonFX m_turnTalon; - private final PidPropertyPublic m_drivePid; - private final PidPropertyPublic m_turnPid; + private final Phoenix6PidPropertyBuilder m_drivePid; + private final Phoenix6PidPropertyBuilder m_turnPid; private final ModuleConstants m_moduleConstants; @@ -68,6 +69,12 @@ public class ModuleIOTalonFX implements ModuleIO { private final StatusSignal m_turnVelocity; private final StatusSignal m_turnAppliedVolts; private final StatusSignal m_turnCurrent; + private final StatusSignal m_turnClosedLoopOutput; + private final StatusSignal m_turnClosedLoopError; + private final StatusSignal m_turnClosedLoopReference; + + + PositionVoltage m_posRequest; public ModuleIOTalonFX(ModuleConstants moduleConstants) { m_driveTalon = new TalonFX(moduleConstants.DRIVE_MOTOR_ID()); @@ -83,7 +90,7 @@ public ModuleIOTalonFX(ModuleConstants moduleConstants) { driveConfig.MotorOutput.Inverted = moduleConstants.DRIVE_MOTOR_INVERTED() ? InvertedValue.Clockwise_Positive : InvertedValue.CounterClockwise_Positive; - driveConfig.Feedback.RotorToSensorRatio = m_moduleConstants.DRIVE_GEAR_RATIO(); + driveConfig.Feedback.SensorToMechanismRatio = m_moduleConstants.DRIVE_GEAR_RATIO(); m_driveTalon.getConfigurator().apply(driveConfig); setDriveBrakeMode(true); @@ -95,8 +102,7 @@ public ModuleIOTalonFX(ModuleConstants moduleConstants) { .addI(m_moduleConstants.DRIVE_KI()) .addD(m_moduleConstants.DRIVE_KD()) .addKV(m_moduleConstants.DRIVE_KV()) - .addKS(m_moduleConstants.DRIVE_KS()) - .build(); + .addKS(m_moduleConstants.DRIVE_KS()); // run configs on turning motor var turnConfig = new TalonFXConfiguration(); @@ -106,7 +112,7 @@ public ModuleIOTalonFX(ModuleConstants moduleConstants) { moduleConstants.TURN_MOTOR_INVERTED() ? InvertedValue.Clockwise_Positive : InvertedValue.CounterClockwise_Positive; turnConfig.ClosedLoopGeneral.ContinuousWrap = true; - turnConfig.Feedback.RotorToSensorRatio = m_moduleConstants.TURNING_GEAR_RATIO(); + turnConfig.Feedback.SensorToMechanismRatio = m_moduleConstants.TURNING_GEAR_RATIO(); m_turnTalon.getConfigurator().apply(turnConfig); setTurnBrakeMode(true); @@ -118,8 +124,9 @@ public ModuleIOTalonFX(ModuleConstants moduleConstants) { 0) .addP(m_moduleConstants.TURN_KP()) .addI(m_moduleConstants.TURN_KI()) - .addD(m_moduleConstants.TURN_KD()) - .build(); + .addD(m_moduleConstants.TURN_KD()); + + m_posRequest = new PositionVoltage(0, 0, false, 0, 0, false, false, false); // run factory default on cancoder var encoderConfig = new CANcoderConfiguration(); @@ -149,6 +156,10 @@ public ModuleIOTalonFX(ModuleConstants moduleConstants) { m_turnAppliedVolts = m_turnTalon.getMotorVoltage(); m_turnCurrent = m_turnTalon.getStatorCurrent(); + m_turnClosedLoopOutput = m_turnTalon.getClosedLoopOutput(); + m_turnClosedLoopError = m_turnTalon.getClosedLoopError(); + m_turnClosedLoopReference = m_turnTalon.getClosedLoopReference(); + // setup refresh rates on all inputs BaseStatusSignal.setUpdateFrequencyForAll( Module.ODOMETRY_FREQUENCY, m_drivePosition, m_turnPosition); @@ -160,7 +171,10 @@ public ModuleIOTalonFX(ModuleConstants moduleConstants) { m_turnAbsolutePosition, m_turnVelocity, m_turnAppliedVolts, - m_turnCurrent); + m_turnCurrent, + m_turnClosedLoopOutput, + m_turnClosedLoopError, + m_turnClosedLoopReference); m_driveTalon.optimizeBusUtilization(); m_turnTalon.optimizeBusUtilization(); } @@ -176,7 +190,10 @@ public void updateInputs(ModuleIOInputs inputs) { m_turnPosition, m_turnVelocity, m_turnAppliedVolts, - m_turnCurrent); + m_turnCurrent, + m_turnClosedLoopOutput, + m_turnClosedLoopError, + m_turnClosedLoopReference); m_drivePid.updateIfChanged(); m_turnPid.updateIfChanged(); @@ -191,7 +208,7 @@ public void updateInputs(ModuleIOInputs inputs) { inputs.setTurnAbsolutePosition(Rotation2d.fromRotations(m_turnAbsolutePosition.getValueAsDouble()) .minus(m_moduleConstants.ENCODER_OFFSET())); inputs.setTurnPosition(Rotation2d.fromRotations(( - m_turnPosition.getValueAsDouble() / m_moduleConstants.TURNING_GEAR_RATIO()))); + m_turnPosition.getValueAsDouble()))); inputs.setTurnVelocityRadPerSec( Units.rotationsToRadians(m_turnVelocity.getValueAsDouble()) / m_moduleConstants.TURNING_GEAR_RATIO()); inputs.setTurnAppliedVolts(m_turnAppliedVolts.getValueAsDouble()); @@ -205,20 +222,29 @@ public void updateInputs(ModuleIOInputs inputs) { .toArray(Rotation2d[]::new)); m_drivePositionQueue.clear(); m_turnPositionQueue.clear(); + + SmartDashboard.putNumber("Module " + m_moduleConstants.MODULE_INDEX() + + "/Closed Loop Output", m_turnClosedLoopOutput.getValueAsDouble()); + SmartDashboard.putNumber("Module " + m_moduleConstants.MODULE_INDEX() + + "/Closed Loop Error", m_turnClosedLoopError.getValueAsDouble()); + SmartDashboard.putNumber("Module " + m_moduleConstants.MODULE_INDEX() + + "/Closed Loop Reference", m_turnClosedLoopReference.getValueAsDouble()); + + SmartDashboard.putNumber("Module " + m_moduleConstants.MODULE_INDEX() + + "/Recorded kP", m_turnPid.getSlotConfigs().kP); } @Override public void setDriveVelocityMPS(double mps) { double rps = (mps / m_moduleConstants.WHEEL_CURCUMFERENCE_METERS()) * m_moduleConstants.DRIVE_GEAR_RATIO(); VelocityVoltage velRequest = new VelocityVoltage(rps).withSlot(0); - m_driveTalon.setControl(velRequest); + m_driveTalon.setControl(velRequest.withVelocity(rps)); } @Override public void setTurnPositionDegs(double degrees) { - double rots = degrees / 360; - PositionVoltage posRequest = new PositionVoltage(rots).withSlot(0); - m_turnTalon.setControl(posRequest); +// double rots = degrees / 360; + m_turnTalon.setControl(m_posRequest.withPosition(degrees)); } @Override diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java index 38d32e0c..ad5d64d2 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java @@ -4,7 +4,11 @@ public interface ShooterIO { @AutoLog - class ShooterIOInputs {} + class ShooterIOInputs { + + } + + default void updateInput(ShooterIOInputs inputs) {} default void setMotorVoltageTL(double voltage) {} default void setMotorVoltageTR(double voltage) {} default void setMotorVoltageBL(double voltage) {} diff --git a/src/main/java/lib/properties/phoenix6/Phoenix6PidPropertyBuilder.java b/src/main/java/lib/properties/phoenix6/Phoenix6PidPropertyBuilder.java index 478fc716..fafc623a 100644 --- a/src/main/java/lib/properties/phoenix6/Phoenix6PidPropertyBuilder.java +++ b/src/main/java/lib/properties/phoenix6/Phoenix6PidPropertyBuilder.java @@ -6,6 +6,7 @@ import com.ctre.phoenix6.configs.SlotConfigs; import com.ctre.phoenix6.hardware.core.CoreTalonFX; import com.ctre.phoenix6.signals.GravityTypeValue; +import com.gos.lib.properties.BaseHeavyProperty; import com.gos.lib.properties.GosDoubleProperty; import com.gos.lib.properties.HeavyDoubleProperty; @@ -105,6 +106,17 @@ public Phoenix6PidPropertyBuilder addKA(double defaultValue) { return this; } + public void updateIfChanged(boolean forceUpdate) { + m_props.forEach((HeavyDoubleProperty prop) -> prop.updateIfChanged(forceUpdate)); + } + + public void updateIfChanged() { + updateIfChanged(false); + } + + public SlotConfigs getSlotConfigs() { + return m_slot; + } public PidPropertyPublic build() { return new PidPropertyPublic(m_props); } diff --git a/vendordeps/AdvantageKit.json b/vendordeps/AdvantageKit.json index a3a16b69..d0cc0d12 100644 --- a/vendordeps/AdvantageKit.json +++ b/vendordeps/AdvantageKit.json @@ -1,7 +1,7 @@ { "fileName": "AdvantageKit.json", "name": "AdvantageKit", - "version": "3.0.0", + "version": "3.0.2", "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", "frcYear": "2024", "mavenUrls": [], @@ -10,24 +10,24 @@ { "groupId": "org.littletonrobotics.akit.junction", "artifactId": "wpilib-shim", - "version": "3.0.0" + "version": "3.0.2" }, { "groupId": "org.littletonrobotics.akit.junction", "artifactId": "junction-core", - "version": "3.0.0" + "version": "3.0.2" }, { "groupId": "org.littletonrobotics.akit.conduit", "artifactId": "conduit-api", - "version": "3.0.0" + "version": "3.0.2" } ], "jniDependencies": [ { "groupId": "org.littletonrobotics.akit.conduit", "artifactId": "conduit-wpilibio", - "version": "3.0.0", + "version": "3.0.2", "skipInvalidPlatforms": false, "isJar": false, "validPlatforms": [ @@ -39,4 +39,4 @@ } ], "cppDependencies": [] -} +} \ No newline at end of file