Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix linting and build violations #22

Closed
wants to merge 9 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
48 changes: 48 additions & 0 deletions .github/workflows/build-lint.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
name: Build and Lint

# 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

# Lints our code to find any format violations
lint:
# 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:
fetch-depth: 0
- uses: actions/setup-java@v3
with:
distribution: 'zulu'
java-version: 17
# Executes linting
# If this fails, run ./gradlew spotlessApply locally to fix formatting
- run: ./gradlew spotlessCheck
17 changes: 17 additions & 0 deletions .github/workflows/format.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
name: Format

on:
pull_request: [ main, 2023-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
- uses: axel-op/googlejavaformat-action@v3
with:
args: "--skip-sorting-imports --replace"
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@
# Simbot-Base
A base robot with the most up to date utilities and starting components to get started on robot code as fast as possible
A base robot with the most up to date utilities and starting components to get started on robot code as fast as possible
15 changes: 15 additions & 0 deletions build.gradle
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
plugins {
id "java"
id 'com.diffplug.spotless' version "6.12.0"
id "edu.wpi.first.GradleRIO" version "2023.4.3"
}

Expand All @@ -8,6 +9,20 @@ targetCompatibility = JavaVersion.VERSION_11

def ROBOT_MAIN_CLASS = "frc.robot.Main"

spotless {
java {
target fileTree('.') {
include '**/*.java'
exclude '**/build/**', '**/build-*/**'
}
toggleOffOn()
googleJavaFormat()
removeUnusedImports()
trimTrailingWhitespace()
endWithNewline()
}
}

// Define my targets (RoboRIO) and artifacts (deployable files)
// This is added by GradleRIO's backing project DeployUtils.
deploy {
Expand Down
123 changes: 67 additions & 56 deletions src/main/java/frc/robot/CommandSwerveDrivetrain.java
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
package frc.robot;

import java.util.function.Supplier;

import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrain;
import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrainConstants;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants;
Expand All @@ -11,75 +9,88 @@
import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
import com.pathplanner.lib.util.PIDConstants;
import com.pathplanner.lib.util.ReplanningConfig;

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.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.Subsystem;
import java.util.function.Supplier;

/**
* 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);
}
/**
* 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 ChassisSpeeds getCurrentRobotChassisSpeeds() {
return m_kinematics.toChassisSpeeds(getState().ModuleStates);
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