Skip to content

Commit

Permalink
Create CI workflows (#20)
Browse files Browse the repository at this point in the history
# Description

Created a lint workflow to check any format errors, a format workflow to
format any code automatically that's pushed to main, and a build
workflow to check if code builds properly without errors. This is linked
to #2

## Type of change

Please delete options that are not relevant.

- [ ] Bug fix (non-breaking change which fixes an issue)
- [x] New feature (non-breaking change which adds functionality)
- [ ] Breaking change (fix or feature that would cause existing
functionality to not work as expected)
- [ ] This change requires a documentation update

# Checklist:

- [x] My code follows the style guidelines of this project
- [x] I have performed a self-review of my code
- [x] I have commented my code, particularly in hard-to-understand areas
- [x] I have made corresponding changes to the documentation, if any
- [x] My changes generate no new warnings
- [x] I have performed tests that prove my fix is effective or that my
feature works, if necessary
- [x] New and existing unit tests pass locally with my changes

---------

Co-authored-by: github-actions <>
  • Loading branch information
Ian Tapply authored Nov 12, 2023
1 parent 2f504d8 commit ec7dfea
Show file tree
Hide file tree
Showing 8 changed files with 1,001 additions and 880 deletions.
30 changes: 30 additions & 0 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
name: Build

# Controls when the action will run. Triggers the workflow on push to all branches.
on: [ push ]

jobs:

# Build our code to see if it can be deployed without errors
build:
# The type of runner that the job will run on
runs-on: ubuntu-latest

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

steps:
# Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it
- uses: actions/checkout@v3

# Declares the repository safe and not under dubious ownership.
- name: Add repository to git safe directories
run: git config --global --add safe.directory $GITHUB_WORKSPACE

# Grant execute permission for gradlew
- name: Grant execute permission for gradlew
run: chmod +x gradlew

# Runs a single command using the runners shell
- name: Compile and run tests on robot code
run: ./gradlew build
22 changes: 22 additions & 0 deletions .github/workflows/format.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
name: Format

on:
pull_request:
branches:
- main
- 2024-beta

jobs:

formatting:
# The type of runner that the job will run on
runs-on: ubuntu-latest

steps:
# Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it
- uses: actions/checkout@v3
with:
ref: ${{ github.event.pull_request.head.ref }}
- uses: axel-op/googlejavaformat-action@v3
with:
args: "--skip-sorting-imports --replace"
120 changes: 67 additions & 53 deletions src/main/java/frc/robot/CommandSwerveDrivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,66 +20,80 @@
import edu.wpi.first.wpilibj2.command.Subsystem;

/**
* Class that extends the Phoenix SwerveDrivetrain class and implements subsystem
* so it can be used in command-based projects easily.
* Class that extends the Phoenix SwerveDrivetrain class and implements subsystem so it can be used
* in command-based projects easily.
*/
public class CommandSwerveDrivetrain extends SwerveDrivetrain implements Subsystem {
private SwerveRequest.ApplyChassisSpeeds autoRequest = new SwerveRequest.ApplyChassisSpeeds();
public CommandSwerveDrivetrain(SwerveDrivetrainConstants driveTrainConstants, double OdometryUpdateFrequency, SwerveModuleConstants... modules) {
super(driveTrainConstants, OdometryUpdateFrequency, modules);
configurePathPlanner();
}
public CommandSwerveDrivetrain(SwerveDrivetrainConstants driveTrainConstants, SwerveModuleConstants... modules) {
super(driveTrainConstants, modules);
configurePathPlanner();
}
private SwerveRequest.ApplyChassisSpeeds autoRequest = new SwerveRequest.ApplyChassisSpeeds();

private void configurePathPlanner() {
AutoBuilder.configureHolonomic(
()->this.getState().Pose, // Supplier of current robot pose
this::seedFieldRelative, // Consumer for seeding pose against auto
this::getCurrentRobotChassisSpeeds,
(speeds)->this.setControl(autoRequest.withSpeeds(speeds)), // Consumer of ChassisSpeeds to drive the robot
new HolonomicPathFollowerConfig(new PIDConstants(10, 0, 0),
new PIDConstants(10, 0, 0),
1,
1,
new ReplanningConfig(),
0.004),
this); // Subsystem for requirements
}
public CommandSwerveDrivetrain(
SwerveDrivetrainConstants driveTrainConstants,
double OdometryUpdateFrequency,
SwerveModuleConstants... modules) {
super(driveTrainConstants, OdometryUpdateFrequency, modules);
configurePathPlanner();
}

public Command applyRequest(Supplier<SwerveRequest> requestSupplier) {
return new RunCommand(()->{this.setControl(requestSupplier.get());}, this);
}
public CommandSwerveDrivetrain(
SwerveDrivetrainConstants driveTrainConstants, SwerveModuleConstants... modules) {
super(driveTrainConstants, modules);
configurePathPlanner();
}

public Command getAutoPath(String pathName) {
return new PathPlannerAuto(pathName);
}
private void configurePathPlanner() {
AutoBuilder.configureHolonomic(
() -> this.getState().Pose, // Supplier of current robot pose
this::seedFieldRelative, // Consumer for seeding pose against auto
this::getCurrentRobotChassisSpeeds,
(speeds) ->
this.setControl(
autoRequest.withSpeeds(speeds)), // Consumer of ChassisSpeeds to drive the robot
new HolonomicPathFollowerConfig(
new PIDConstants(10, 0, 0),
new PIDConstants(10, 0, 0),
1,
1,
new ReplanningConfig(),
0.004),
this); // Subsystem for requirements
}

@Override
public void simulationPeriodic() {
/* Assume */
updateSimState(0.02, 12);
}
/**
* Takes the specified location and makes it the current pose for
* field-relative maneuvers
*
* @param location Pose to make the current pose at.
*/
@Override
public void seedFieldRelative(Pose2d location) {
try {
m_stateLock.writeLock().lock();
public Command applyRequest(Supplier<SwerveRequest> requestSupplier) {
return new RunCommand(
() -> {
this.setControl(requestSupplier.get());
},
this);
}

m_odometry.resetPosition(Rotation2d.fromDegrees(m_pigeon2.getYaw().getValue()), m_modulePositions, location);
} finally {
m_stateLock.writeLock().unlock();
}
}
public Command getAutoPath(String pathName) {
return new PathPlannerAuto(pathName);
}

@Override
public void simulationPeriodic() {
/* Assume */
updateSimState(0.02, 12);
}

public ChassisSpeeds getCurrentRobotChassisSpeeds() {
return m_kinematics.toChassisSpeeds(getState().ModuleStates);
/**
* Takes the specified location and makes it the current pose for field-relative maneuvers
*
* @param location Pose to make the current pose at.
*/
@Override
public void seedFieldRelative(Pose2d location) {
try {
m_stateLock.writeLock().lock();

m_odometry.resetPosition(
Rotation2d.fromDegrees(m_pigeon2.getYaw().getValue()), m_modulePositions, location);
} finally {
m_stateLock.writeLock().unlock();
}
}

public ChassisSpeeds getCurrentRobotChassisSpeeds() {
return m_kinematics.toChassisSpeeds(getState().ModuleStates);
}
}
Loading

0 comments on commit ec7dfea

Please sign in to comment.