Skip to content

Commit

Permalink
More ci stuff (#33)
Browse files Browse the repository at this point in the history
* decent changes

* Update VisionSubsystem.java

* fancy switch statement bc im cool like that

* decent changes

* hi

* Delete .vscode directory

* pr things

* fix build and apply spotless

* docstrings

* fix typo

* Update src/main/java/frc/robot/subsystems/vision/VisionSubsystem.java

Jacks change

Co-authored-by: Jack <85963782+JacksonElia@users.noreply.github.com>

* decent changes

* format

* Update TalonUtil.java

* sync changes

* fix build and test, add linting stuff

* i think this should work?

* ?

* haha

* rerun actions

* i gave up on that shiiiiiiiiiiiii

* format me thinks

* fix

* hgj

* things

* does this work?

* try this:

* bfdkjvls

* :(

* retry this

* copy whippy lib

---------

Co-authored-by: Jack <85963782+JacksonElia@users.noreply.github.com>
  • Loading branch information
Ishan1522 and JacksonElia authored Aug 20, 2024
1 parent be1e987 commit 34d87fd
Show file tree
Hide file tree
Showing 7 changed files with 341 additions and 171 deletions.
1 change: 0 additions & 1 deletion .github/CODEOWNERS

This file was deleted.

58 changes: 26 additions & 32 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -6,49 +6,43 @@ on:

jobs:
build:
name: Build
name: "Compile Java"
runs-on: ubuntu-latest
container: wpilib/roborio-cross-ubuntu:2024-22.04
steps:
- name: Checkout repository
uses: actions/checkout@v4
- name: Grant execute permission
run: chmod +x gradlew
- name: Build robot code
run: ./gradlew build
- uses: actions/checkout@v4
- name: Grant execute permission for gradlew
run: chmod +x gradlew
- name: Compile robot code
run: ./gradlew compileJava

test:
# This workflow contains a single job called "test"
name: "Test"
# The type of runner that the job will run on
name: "Test Java"
runs-on: ubuntu-latest

# This grabs the WPILib docker container
container: wpilib/roborio-cross-ubuntu:2024-22.04

# Steps represent a sequence of tasks that will be executed as part of the job
steps:
# Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it
- uses: actions/checkout@v4
# Grant execute permission for gradlew
- name: Grant execute permission for gradlew
run: chmod +x gradlew
# Runs a single command using the runners shell
- name: Simulate and test robot code
run: ./gradlew simulateJava
- name: Run tests on robot code
run: ./gradlew test -PrunTests

formate:
name: "Lint and Format Check"
# The type of runner that the job will run on
format:
name: "Check Format Java"
runs-on: ubuntu-latest
# Steps represent a sequence of tasks that will be executed as part of the job
steps:
# Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it
- uses: actions/checkout@v4
- name: Grant execute permission for gradlew
run: chmod +x gradlew
- uses: actions/setup-java@v4
with:
distribution: 'zulu'
java-version: 17
- run: ./gradlew spotlessCheck
- uses: actions/checkout@v4
with:
fetch-depth: 0
- name: Grant execute permission for gradlew
run: chmod +x gradlew
- name: Fetch all history and metadata
run: |
git checkout -b pr
git branch -f main origin/main
- uses: actions/setup-java@v4
with:
java-version: 17
distribution: temurin
- name: Run formatter
run: ./gradlew spotlessCheck
51 changes: 0 additions & 51 deletions .github/workflows/comment-command.yml

This file was deleted.

87 changes: 87 additions & 0 deletions src/main/java/frc/robot/extras/TalonUtil.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
// moderately inspired by 254
package frc.robot.extras;

import com.ctre.phoenix6.StatusCode;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.wpilibj.DriverStation;
import java.util.function.Supplier;

public class TalonUtil {

public static boolean applyAndCheckConfiguration(
TalonFX talon, TalonFXConfiguration config, double timeoutSeconds, int numTries) {
for (int i = 0; i < numTries; i++) {
if (checkErrorAndRetry(() -> talon.getConfigurator().apply(config, timeoutSeconds))) {
return true;
}
}
DriverStation.reportError(
"Failed to apply config for talon after " + numTries + " attempts", false);
return false;
}

public static boolean applyAndCheckConfiguration(
TalonFX talon, TalonFXConfiguration config, double timeoutMs) {
boolean result = applyAndCheckConfiguration(talon, config, timeoutMs, 5);
return result;
}

public enum StickyFault {
BootDuringEnable,
DeviceTemp,
ForwardHardLimit,
ForwardSoftLimit,
Hardware,
OverSupplyV,
ProcTemp,
ReverseHardLimit,
ReverseSoftLimit,
Undervoltage,
UnstableSupplyV
}

public static void checkStickyFaults(String motorName, TalonFX talon) {
boolean[] faults = new boolean[StickyFault.values().length];
faults[0] = talon.getStickyFault_BootDuringEnable().getValue();
faults[1] = talon.getStickyFault_DeviceTemp().getValue();
faults[2] = talon.getStickyFault_ForwardHardLimit().getValue();
faults[3] = talon.getStickyFault_ForwardSoftLimit().getValue();
faults[4] = talon.getStickyFault_Hardware().getValue();
faults[5] = talon.getStickyFault_OverSupplyV().getValue();
faults[6] = talon.getStickyFault_ProcTemp().getValue();
faults[7] = talon.getStickyFault_ReverseHardLimit().getValue();
faults[8] = talon.getStickyFault_ReverseSoftLimit().getValue();
faults[9] = talon.getStickyFault_Undervoltage().getValue();
faults[10] = talon.getStickyFault_UnstableSupplyV().getValue();

for (int i = 0; i < faults.length; i++) {
if (faults[i]) {
DriverStation.reportError(
motorName + ": Talon Fault! " + StickyFault.values()[i].toString(), false);
}
}

talon.clearStickyFaults();
}

public static boolean checkErrorAndRetry(Supplier<StatusCode> function, int numTries) {
StatusCode code = function.get();
int tries = 0;
while (code != StatusCode.OK && tries < numTries) {
DriverStation.reportWarning("Retrying CTRE Device Config " + code.getName(), false);
code = function.get();
tries++;
}
if (code != StatusCode.OK) {
DriverStation.reportError(
"Failed to execute phoenix pro api call after " + numTries + " attempts", false);
return false;
}
return true;
}

public static boolean checkErrorAndRetry(Supplier<StatusCode> function) {
return checkErrorAndRetry(function, 5);
}
}
40 changes: 30 additions & 10 deletions src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import frc.robot.Constants.HardwareConstants;
import frc.robot.Constants.ShooterConstants;
import frc.robot.extras.SmarterDashboardRegistry;
import frc.robot.extras.TalonUtil;

public class ShooterSubsystem extends SubsystemBase {
private final TalonFX leaderFlywheel;
Expand All @@ -42,7 +43,28 @@ public ShooterSubsystem() {
velocityRequest = new VelocityVoltage(0);
voltageRequest = new VoltageOut(0);

try {
configureTalons();
} catch (RuntimeException e) {
System.out.println("Failed to configure talons :(");
}

leaderVelocity = leaderFlywheel.getVelocity();
followerVelocity = followerFlywheel.getVelocity();

BaseStatusSignal.setUpdateFrequencyForAll(
HardwareConstants.SIGNAL_FREQUENCY, leaderVelocity, followerVelocity);
ParentDevice.optimizeBusUtilizationForAll(leaderFlywheel, rollerMotor, followerFlywheel);
}

private void configureTalons() throws RuntimeException {
TalonFXConfiguration shooterConfig = new TalonFXConfiguration();
TalonUtil.checkErrorAndRetry(
() -> leaderFlywheel.getConfigurator().refresh(shooterConfig, HardwareConstants.TIMEOUT_S));
TalonUtil.checkErrorAndRetry(
() ->
followerFlywheel.getConfigurator().refresh(shooterConfig, HardwareConstants.TIMEOUT_S));

shooterConfig.Slot0.kP = ShooterConstants.SHOOT_P;
shooterConfig.Slot0.kI = ShooterConstants.SHOOT_I;
shooterConfig.Slot0.kD = ShooterConstants.SHOOT_D;
Expand All @@ -58,21 +80,19 @@ public ShooterSubsystem() {
shooterConfig.CurrentLimits.SupplyCurrentLimit = ShooterConstants.SHOOTER_SUPPLY_LIMIT;
shooterConfig.CurrentLimits.SupplyCurrentLimitEnable = ShooterConstants.SHOOTER_SUPPLY_ENABLE;

leaderFlywheel.getConfigurator().apply(shooterConfig, HardwareConstants.TIMEOUT_S);
TalonUtil.applyAndCheckConfiguration(
leaderFlywheel, shooterConfig, HardwareConstants.TIMEOUT_S);
shooterConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;
followerFlywheel.getConfigurator().apply(shooterConfig, HardwareConstants.TIMEOUT_S);
TalonUtil.applyAndCheckConfiguration(
followerFlywheel, shooterConfig, HardwareConstants.TIMEOUT_S);

TalonFXConfiguration rollerConfig = new TalonFXConfiguration();
TalonUtil.checkErrorAndRetry(
() -> leaderFlywheel.getConfigurator().refresh(rollerConfig, HardwareConstants.TIMEOUT_S));

rollerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake;
rollerConfig.MotorOutput.DutyCycleNeutralDeadband = HardwareConstants.MIN_FALCON_DEADBAND;
rollerMotor.getConfigurator().apply(rollerConfig, HardwareConstants.TIMEOUT_S);

leaderVelocity = leaderFlywheel.getVelocity();
followerVelocity = followerFlywheel.getVelocity();

BaseStatusSignal.setUpdateFrequencyForAll(
HardwareConstants.SIGNAL_FREQUENCY, leaderVelocity, followerVelocity);
ParentDevice.optimizeBusUtilizationForAll(leaderFlywheel, rollerMotor, followerFlywheel);
TalonUtil.applyAndCheckConfiguration(rollerMotor, rollerConfig, HardwareConstants.TIMEOUT_S);
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,7 @@ public SwerveModule(

driveMotor.setPosition(0);
turnMotor.setPosition(0);
driveMotor.optimizeBusUtilization();

BaseStatusSignal.setUpdateFrequencyForAll(
HardwareConstants.SIGNAL_FREQUENCY, turnEncoderPos, driveMotorPosition, driveMotorVelocity);
Expand Down
Loading

0 comments on commit 34d87fd

Please sign in to comment.