Skip to content

Commit

Permalink
AdvKit-add spotless format
Browse files Browse the repository at this point in the history
  • Loading branch information
rishabhreng committed Nov 20, 2024
1 parent 4ce3c86 commit 5a0f3fa
Show file tree
Hide file tree
Showing 14 changed files with 523 additions and 474 deletions.
10 changes: 5 additions & 5 deletions AdvKit2024/.wpilib/wpilib_preferences.json
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
{
"enableCppIntellisense": false,
"currentLanguage": "java",
"projectYear": "2024",
"teamNumber": 6672
}
"enableCppIntellisense": false,
"currentLanguage": "java",
"projectYear": "2024",
"teamNumber": 6672
}
49 changes: 48 additions & 1 deletion AdvKit2024/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.3.2"
id 'com.diffplug.spotless' version '6.20.0'
}

java {
Expand Down Expand Up @@ -108,7 +109,11 @@ wpi.sim.addDriverstation()
// in order to make them all available at runtime. Also adding the manifest so WPILib
// knows where to look for our Robot Class.
jar {
from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } }
from {
configurations.runtimeClasspath.collect {
it.isDirectory() ? it : zipTree(it)
}
}
from sourceSets.main.allSource
manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS)
duplicatesStrategy = DuplicatesStrategy.INCLUDE
Expand All @@ -123,3 +128,45 @@ wpi.java.configureTestTasks(test)
tasks.withType(JavaCompile) {
options.compilerArgs.add '-XDstringConcat=inline'
}

// Spotless formatting
project.compileJava.dependsOn(spotlessApply)
spotless {
java {
target fileTree(".") {
include "**/*.java"
exclude "**/build/**", "**/build-*/**"
}
toggleOffOn()
googleJavaFormat()
removeUnusedImports()
trimTrailingWhitespace()
endWithNewline()
}
groovyGradle {
target fileTree(".") {
include "**/*.gradle"
exclude "**/build/**", "**/build-*/**"
}
greclipse()
indentWithSpaces(4)
trimTrailingWhitespace()
endWithNewline()
}
json {
target fileTree(".") {
include "**/*.json"
exclude "**/build/**", "**/build-*/**"
}
gson().indentWithSpaces(2)
}
format "misc", {
target fileTree(".") {
include "**/*.md", "**/.gitignore"
exclude "**/build/**", "**/build-*/**"
}
trimTrailingWhitespace()
indentWithSpaces(2)
endWithNewline()
}
}
34 changes: 18 additions & 16 deletions AdvKit2024/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,15 +4,13 @@

package frc.robot;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import org.littletonrobotics.junction.LoggedRobot;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.NT4Publisher;
import org.littletonrobotics.junction.wpilog.WPILOGWriter;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;


public class Robot extends LoggedRobot {
private Command m_autonomousCommand;

Expand All @@ -22,21 +20,25 @@ public class Robot extends LoggedRobot {
public void robotInit() {
Logger.recordMetadata("ProjectName", "MyProject"); // Set a metadata value

// if (isReal()) {
// Logger.addDataReceiver(new WPILOGWriter()); // Log to a USB stick ("/U/logs")
// Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables
// new PowerDistribution(1, ModuleType.kRev); // Enables power distribution logging
// } else {
// setUseTiming(false); // Run as fast as possible
// String logPath = LogFileUtil.findReplayLog(); // Pull the replay log from AdvantageScope (or prompt the user)
// Logger.setReplaySource(new WPILOGReader(logPath)); // Read replay log
// Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); // Save outputs to a new log
// }
// if (isReal()) {
// Logger.addDataReceiver(new WPILOGWriter()); // Log to a USB stick ("/U/logs")
// Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables
// new PowerDistribution(1, ModuleType.kRev); // Enables power distribution logging
// } else {
// setUseTiming(false); // Run as fast as possible
// String logPath = LogFileUtil.findReplayLog(); // Pull the replay log from AdvantageScope
// (or prompt the user)
// Logger.setReplaySource(new WPILOGReader(logPath)); // Read replay log
// Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); //
// Save outputs to a new log
// }
Logger.addDataReceiver(new WPILOGWriter()); // Log to a USB stick ("/U/logs")
Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables

// Logger.disableDeterministicTimestamps() // See "Deterministic Timestamps" in the "Understanding Data Flow" page
Logger.start(); // Start logging! No more data receivers, replay sources, or metadata values may be added.
// Logger.disableDeterministicTimestamps() // See "Deterministic Timestamps" in the
// "Understanding Data Flow" page
Logger.start(); // Start logging! No more data receivers, replay sources, or metadata values may
// be added.

m_robotContainer = new RobotContainer();
}
Expand Down
2 changes: 1 addition & 1 deletion AdvKit2024/src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
public class RobotContainer {
private final Intake intake;
private final Drive drive;

public RobotContainer() {
intake = new Intake(new IntakeIOSim());
drive = new Drive(new DriveIOSim());
Expand Down
40 changes: 20 additions & 20 deletions AdvKit2024/src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
@@ -1,39 +1,37 @@
package frc.robot.subsystems.drive;

import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;
import static frc.robot.Constants.driverController;

import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d;
import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import static frc.robot.Constants.driverController;
import java.util.function.DoubleSupplier;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;

public class Drive extends SubsystemBase{
public class Drive extends SubsystemBase {
DriveIO driveIO;
DriveIOInputsAutoLogged inputs = new DriveIOInputsAutoLogged();

@AutoLogOutput
public Mechanism2d leftMechanism2d = new Mechanism2d(1, 1);
private MechanismLigament2d leftMotorMechanismModifiable = leftMechanism2d.getRoot("leftMotor", 0.5, 0.5)
.append(new MechanismLigament2d("leftMotorAngle", 0.25, 0)
);
@AutoLogOutput public Mechanism2d leftMechanism2d = new Mechanism2d(1, 1);
private MechanismLigament2d leftMotorMechanismModifiable =
leftMechanism2d
.getRoot("leftMotor", 0.5, 0.5)
.append(new MechanismLigament2d("leftMotorAngle", 0.25, 0));

@AutoLogOutput
public Mechanism2d rightMechanism2d = new Mechanism2d(1, 1);
private MechanismLigament2d rightMotorMechanismModifiable = rightMechanism2d.getRoot("rightMotor", 0.5, 0.5)
.append(new MechanismLigament2d("rightMotorAngle", 0.25, 0)
);
@AutoLogOutput public Mechanism2d rightMechanism2d = new Mechanism2d(1, 1);
private MechanismLigament2d rightMotorMechanismModifiable =
rightMechanism2d
.getRoot("rightMotor", 0.5, 0.5)
.append(new MechanismLigament2d("rightMotorAngle", 0.25, 0));

public Drive(DriveIO driveIO) {
this.driveIO = driveIO;

setDefaultCommand(
runArcadeDrive(() -> -driverController.getLeftY(), driverController::getRightX)
);
runArcadeDrive(() -> -driverController.getLeftY(), driverController::getRightX));
}

public void periodic() {
Expand All @@ -45,8 +43,10 @@ public void periodic() {
}

public Command runArcadeDrive(DoubleSupplier speed, DoubleSupplier rotation) {
return run(() -> driveIO.setDriveVoltage(
speed.getAsDouble() + rotation.getAsDouble(),
speed.getAsDouble() - rotation.getAsDouble()));
return run(
() ->
driveIO.setDriveVoltage(
speed.getAsDouble() + rotation.getAsDouble(),
speed.getAsDouble() - rotation.getAsDouble()));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,8 @@ public static class DriveIOInputs {

public default void updateInputs(DriveIOInputs inputs) {}

public default void setDriveVelocity(double leftVelocityRadPerSec, double rightVelocityRadPerSec) {}
public default void setDriveVelocity(
double leftVelocityRadPerSec, double rightVelocityRadPerSec) {}

public default void setDriveVoltage(double leftVolts, double rightVolts) {}
}
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.DCMotorSim;

public class DriveIOSim implements DriveIO{
public class DriveIOSim implements DriveIO {
DCMotorSim leftDriveMotorSim = new DCMotorSim(DCMotor.getFalcon500(1), 1, 0.0001);
DCMotorSim rightDriveMotorSim = new DCMotorSim(DCMotor.getFalcon500(1), 1, 0.0001);

Expand All @@ -29,7 +29,7 @@ public void updateInputs(DriveIO.DriveIOInputs inputs) {
inputs.leftDriveMotorAppliedVolts = leftDriveMotorAppliedVolts;
inputs.leftDriveMotorPosRad = leftDriveMotorSim.getAngularPositionRad();
inputs.leftDriveMotorVelocityRadPerSec = leftDriveMotorSim.getAngularVelocityRadPerSec();

inputs.rightDriveMotorAppliedVolts = rightDriveMotorAppliedVolts;
inputs.rightDriveMotorPosRad = rightDriveMotorSim.getAngularPositionRad();
inputs.rightDriveMotorVelocityRadPerSec = rightDriveMotorSim.getAngularVelocityRadPerSec();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
import com.ctre.phoenix6.controls.VoltageOut;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.NeutralModeValue;

import edu.wpi.first.math.util.Units;

public class DriveIOTalonFX implements DriveIO {
Expand All @@ -23,25 +22,29 @@ public class DriveIOTalonFX implements DriveIO {
private StatusSignal<Double> leftDriveMotorPosRad = leftDriveMotor.getPosition();
private StatusSignal<Double> leftDriveMotorVelocityRadPerSec = leftDriveMotor.getVelocity();
private StatusSignal<Double> leftDriveMotorAppliedVolts = leftDriveMotor.getMotorVoltage();

private StatusSignal<Double> rightDriveMotorPosRad = rightDriveMotor.getPosition();
private StatusSignal<Double> rightDriveMotorVelocityRadPerSec = rightDriveMotor.getVelocity();
private StatusSignal<Double> rightDriveMotorAppliedVolts = rightDriveMotor.getMotorVoltage();

public DriveIOTalonFX() {
leftDriveMotor.setInverted(false);
rightDriveMotor.setInverted(true);
leftDriveMotor.getConfigurator().apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake));
rightDriveMotor.getConfigurator().apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake));
leftDriveMotor
.getConfigurator()
.apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake));
rightDriveMotor
.getConfigurator()
.apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake));

BaseStatusSignal.setUpdateFrequencyForAll(
60,
leftDriveMotorPosRad,
leftDriveMotorVelocityRadPerSec,
leftDriveMotorAppliedVolts,
rightDriveMotorPosRad,
rightDriveMotorVelocityRadPerSec,
rightDriveMotorAppliedVolts);
60,
leftDriveMotorPosRad,
leftDriveMotorVelocityRadPerSec,
leftDriveMotorAppliedVolts,
rightDriveMotorPosRad,
rightDriveMotorVelocityRadPerSec,
rightDriveMotorAppliedVolts);
leftDriveMotor.optimizeBusUtilization();
rightDriveMotor.optimizeBusUtilization();
}
Expand All @@ -61,20 +64,22 @@ public void setDriveVoltage(double leftVolts, double rightVolts) {
@Override
public void updateInputs(DriveIOInputs inputs) {
BaseStatusSignal.refreshAll(
leftDriveMotorPosRad,
leftDriveMotorVelocityRadPerSec,
leftDriveMotorAppliedVolts,
rightDriveMotorPosRad,
rightDriveMotorVelocityRadPerSec,
rightDriveMotorAppliedVolts
);
leftDriveMotorPosRad,
leftDriveMotorVelocityRadPerSec,
leftDriveMotorAppliedVolts,
rightDriveMotorPosRad,
rightDriveMotorVelocityRadPerSec,
rightDriveMotorAppliedVolts);

inputs.leftDriveMotorAppliedVolts = leftDriveMotorAppliedVolts.getValueAsDouble();
inputs.leftDriveMotorPosRad = Units.rotationsToRadians(leftDriveMotorPosRad.getValueAsDouble());
inputs.leftDriveMotorVelocityRadPerSec = Units.rotationsToRadians(leftDriveMotorVelocityRadPerSec.getValueAsDouble());
inputs.leftDriveMotorVelocityRadPerSec =
Units.rotationsToRadians(leftDriveMotorVelocityRadPerSec.getValueAsDouble());

inputs.rightDriveMotorAppliedVolts = rightDriveMotorAppliedVolts.getValueAsDouble();
inputs.rightDriveMotorPosRad = Units.rotationsToRadians(rightDriveMotorPosRad.getValueAsDouble());
inputs.rightDriveMotorVelocityRadPerSec = Units.rotationsToRadians(rightDriveMotorVelocityRadPerSec.getValueAsDouble());
inputs.rightDriveMotorPosRad =
Units.rotationsToRadians(rightDriveMotorPosRad.getValueAsDouble());
inputs.rightDriveMotorVelocityRadPerSec =
Units.rotationsToRadians(rightDriveMotorVelocityRadPerSec.getValueAsDouble());
}
}
10 changes: 4 additions & 6 deletions AdvKit2024/src/main/java/frc/robot/subsystems/intake/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,10 @@

import static frc.robot.Constants.driverController;

import org.littletonrobotics.junction.Logger;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import org.littletonrobotics.junction.Logger;

public class Intake extends SubsystemBase {
private IntakeIO intakeIO;
Expand All @@ -25,9 +24,8 @@ public void periodic() {

public Command intakeCommand() {
return Commands.sequence(
runOnce(() -> intakeIO.setIntakeVoltage(2.0)),
Commands.waitSeconds(2.0),
runOnce(() -> intakeIO.setIntakeVoltage(0.0))
);
runOnce(() -> intakeIO.setIntakeVoltage(2.0)),
Commands.waitSeconds(2.0),
runOnce(() -> intakeIO.setIntakeVoltage(0.0)));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ public static class IntakeIOInputs {
public double intakeVelocityRadPerSec = 0.0;
}

public default void updateInputs(IntakeIOInputs inputs) {}
public default void updateInputs(IntakeIOInputs inputs) {}

public default void setIntakeVelocity(double velocityRadPerSec) {}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,9 @@ public class IntakeIOSim implements IntakeIO {
@Override
public void setIntakeVelocity(double velocityRadPerSec) {
intakeMotorSim.setInputVoltage(
intakeFeedforward.calculate(velocityRadPerSec) + intakeController.calculate(intakeMotorSim.getAngularVelocityRadPerSec(), velocityRadPerSec)
);
intakeFeedforward.calculate(velocityRadPerSec)
+ intakeController.calculate(
intakeMotorSim.getAngularVelocityRadPerSec(), velocityRadPerSec));
}

@Override
Expand All @@ -33,5 +34,4 @@ public void updateInputs(IntakeIOInputs inputs) {
inputs.intakePosRad = intakeMotorSim.getAngularPositionRad();
inputs.intakeVelocityRadPerSec = intakeMotorSim.getAngularVelocityRadPerSec();
}

}
Loading

0 comments on commit 5a0f3fa

Please sign in to comment.