Skip to content
This repository has been archived by the owner on Nov 2, 2024. It is now read-only.

Commit

Permalink
fix linting issues
Browse files Browse the repository at this point in the history
  • Loading branch information
legoguy1000 committed Jan 22, 2024
1 parent be0e92c commit e6b6fe2
Show file tree
Hide file tree
Showing 5 changed files with 24 additions and 19 deletions.
3 changes: 1 addition & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -190,8 +190,7 @@ public static final class Mod3 {
public static final HolonomicPathFollowerConfig pathFollowerConfig =
new HolonomicPathFollowerConfig(new PIDConstants(5.0, 0, 0), // Translation constants
new PIDConstants(5.0, 0, 0), // Rotation constants
MAX_SPEED, MOD0_MODOFFSET.getNorm(), // Drive base radius (distance from center
// to furthest module)
MAX_SPEED, MOD0_MODOFFSET.getNorm(), // Drive base radius (distance from center to furthest module)

Check warning on line 193 in src/main/java/frc/robot/Constants.java

View workflow job for this annotation

GitHub Actions / testtool

[testtool] src/main/java/frc/robot/Constants.java#L193 <com.puppycrawl.tools.checkstyle.checks.sizes.LineLengthCheck>

Line is longer than 100 characters (found 115).
Raw output
/github/workspace/./src/main/java/frc/robot/Constants.java:193:0: warning: Line is longer than 100 characters (found 115). (com.puppycrawl.tools.checkstyle.checks.sizes.LineLengthCheck)
new ReplanningConfig());

}
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -293,7 +293,7 @@ public Command getAutonomousCommand() {
// vision);
Robot.level = levelsChooser.getSelected();
Robot.column = columnsChooser.getSelected();
Command autocommand = new WaitCommand(1.0);
Command autocommand;
String stuff = autoChooser.getSelected();
switch (stuff) {
case "example":
Expand All @@ -309,6 +309,8 @@ public Command getAutonomousCommand() {
.andThen(new PathPlannerAuto("New Auto"));

break;
default:
autocommand = new WaitCommand(1.0);
}

// return new DockArm(s_Arm, s_wristIntake).withTimeout(.2).andThen(autocommand);
Expand Down
9 changes: 8 additions & 1 deletion src/main/java/frc/robot/autos/PPExample.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,17 @@
import edu.wpi.first.wpilibj2.command.InstantCommand;
import frc.robot.subsystems.Swerve;

/**
* Path Planner Example Auto
*/
public class PPExample extends TrajectoryBase {
public Swerve swerve;

/**
* Path Planner Example Auto
*
* @param swerve The {@link Swerve} subsystem
*/
public PPExample(Swerve swerve) {
super(swerve);
PathPlannerPath examplepath = PathPlannerPath.fromPathFile("Example Path");
Expand All @@ -19,5 +27,4 @@ public PPExample(Swerve swerve) {
new Pose2d(initialState.getTranslation(), initialState.getRotation()))),
exampleCommand);
}

}
15 changes: 1 addition & 14 deletions src/main/java/frc/robot/autos/TrajectoryBase.java
Original file line number Diff line number Diff line change
@@ -1,12 +1,9 @@
package frc.robot.autos;

import java.util.Optional;
import com.pathplanner.lib.commands.FollowPathHolonomic;
import com.pathplanner.lib.path.PathPlannerPath;
import com.pathplanner.lib.util.PIDConstants;
import com.pathplanner.lib.util.ReplanningConfig;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.robot.Constants;
import frc.robot.subsystems.Swerve;
Expand Down Expand Up @@ -42,17 +39,7 @@ public FollowPathHolonomic baseSwerveCommand(PathPlannerPath trajectory) {
FollowPathHolonomic command = new FollowPathHolonomic(trajectory, swerve::getPose,
swerve::getChassisSpeeds, swerve::setModuleStates, pidX, pidTheta,
Constants.Swerve.MAX_SPEED, Constants.Swerve.ROBOT_RADIUS, new ReplanningConfig(),
() -> shouldFlipPath(), swerve);
() -> swerve.shouldFlipPath(), swerve);
return command;
}

public static boolean shouldFlipPath() {
Optional<Alliance> ally = DriverStation.getAlliance();
if (ally.isPresent()) {
return ally.get() == Alliance.Red;
}
return false;


}
}
12 changes: 11 additions & 1 deletion src/main/java/frc/robot/subsystems/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,11 @@ public Pose2d getPose() {
}


/**
* Get the current Swerve Module States
*
* @return The current {@link SwerveModuleStates}
*/
public SwerveModuleState[] getModuleStates() {
SwerveModuleState[] states = new SwerveModuleState[swerveMods.length];
for (int i = 0; i < swerveMods.length; i++) {
Expand All @@ -146,6 +151,11 @@ public SwerveModuleState[] getModuleStates() {
return states;
}

/**
* Get the current Chassis Speeds
*
* @return The current {@link ChassisSpeeds}
*/
public ChassisSpeeds getChassisSpeeds() {
return Constants.Swerve.SWERVE_KINEMATICS.toChassisSpeeds(getModuleStates());
}
Expand Down Expand Up @@ -275,7 +285,7 @@ public void zeroGyro() {
gyro.zeroYaw();
}

public static boolean shouldFlipPath() {
public boolean shouldFlipPath() {

Check warning on line 288 in src/main/java/frc/robot/subsystems/Swerve.java

View workflow job for this annotation

GitHub Actions / testtool

[testtool] src/main/java/frc/robot/subsystems/Swerve.java#L288 <com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocMethodCheck>

Missing a Javadoc comment.
Raw output
/github/workspace/./src/main/java/frc/robot/subsystems/Swerve.java:288:5: warning: Missing a Javadoc comment. (com.puppycrawl.tools.checkstyle.checks.javadoc.MissingJavadocMethodCheck)
Optional<Alliance> ally = DriverStation.getAlliance();
if (ally.isPresent()) {
return ally.get() == Alliance.Red;
Expand Down

0 comments on commit e6b6fe2

Please sign in to comment.