Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
21 commits
Select commit Hold shift + click to select a range
b0ea613
Bump com.diffplug.spotless from 6.25.0 to 7.0.1
dependabot[bot] Jan 11, 2025
52ac8aa
Merge pull request #31 from AZ-First/dependabot/gradle/com.diffplug.s…
tbowers7 Jan 11, 2025
d4df9d2
Rename default auto paths
tbowers7 Jan 15, 2025
b03b210
Merge pull request #34 from AZ-First/33-pathplanner-auto-not-working
tbowers7 Jan 15, 2025
ec19aec
Use PhotonVision's tagger workflow
tbowers7 Jan 12, 2025
cedf763
More vendorlib updates
tbowers7 Jan 14, 2025
5f2562e
Update spotless formatting
tbowers7 Jan 15, 2025
58e7e4e
Test patch on PhotonVision vendorlib JSON file
tbowers7 Jan 15, 2025
67c2d3a
Remove GitHub tag workflow; update more vendordeps
tbowers7 Jan 15, 2025
616e3f7
Update Photon Vision release version
tbowers7 Jan 15, 2025
e52c1d9
Merge pull request #35 from AZ-First/prep4release
tbowers7 Jan 15, 2025
473d2f0
Bump com.diffplug.spotless from 6.25.0 to 7.0.2
dependabot[bot] Jan 20, 2025
cbe6f2d
Merge branch 'develop' into dependabot/gradle/com.diffplug.spotless-7…
tbowers7 Jan 20, 2025
7eb56e5
Merge pull request #37 from AZ-First/dependabot/gradle/com.diffplug.s…
tbowers7 Jan 20, 2025
63b3a19
Add a command cancel in autoInit()
tbowers7 Jan 15, 2025
0088bc8
Align PathPlanner calls to those in AK Template
tbowers7 Jan 16, 2025
26d27ce
Remove gyro manual reset function
tbowers7 Jan 17, 2025
93c33eb
Even more vendordeps, including AK 4.1.0
tbowers7 Jan 18, 2025
15e34bd
Massage the PathPlanner generator
tbowers7 Jan 18, 2025
25fe42a
Mars Climate Orbiter 🤦
tbowers7 Jan 20, 2025
64c3c5a
Merge pull request #36 from AZ-First/33-pathplanner-auto-not-working
tbowers7 Jan 20, 2025
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
8 changes: 4 additions & 4 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2025.2.1"
id "com.peterabeles.gversion" version "1.10.3"
id "com.diffplug.spotless" version "6.25.0"
id "com.diffplug.spotless" version "7.0.2"
id "io.freefair.lombok" version "8.11"
id "com.google.protobuf" version "0.9.4"
}
Expand Down Expand Up @@ -214,7 +214,7 @@ spotless {
exclude '**/build/**', '**/build-*/**'
}
greclipse()
indentWithSpaces(4)
leadingTabsToSpaces(4)
trimTrailingWhitespace()
endWithNewline()
}
Expand All @@ -232,7 +232,7 @@ spotless {
}
eclipseWtp('xml')
trimTrailingWhitespace()
indentWithSpaces(2)
leadingTabsToSpaces(2)
endWithNewline()
}
format "misc", {
Expand All @@ -241,7 +241,7 @@ spotless {
exclude '**/build/**', '**/build-*/**'
}
trimTrailingWhitespace()
indentWithSpaces(2)
leadingTabsToSpaces(2)
endWithNewline()
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
{
"type": "path",
"data": {
"pathName": "Example Path"
"pathName": "Consistancy Test"
}
}
]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,41 +3,25 @@
"waypoints": [
{
"anchor": {
"x": 2.0,
"y": 7.0
"x": 9.35,
"y": 6.18
},
"prevControl": null,
"nextControl": {
"x": 3.013282910175676,
"y": 6.5274984191074985
"x": 9.141987426415538,
"y": 6.318675049056306
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 5.166769560390973,
"y": 5.0964860911203305
"x": 8.18,
"y": 6.18
},
"prevControl": {
"x": 4.166769560390973,
"y": 6.0964860911203305
},
"nextControl": {
"x": 6.166769560390973,
"y": 4.0964860911203305
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 7.0,
"y": 1.0
},
"prevControl": {
"x": 6.75,
"y": 2.5
"x": 8.56,
"y": 6.17
},
"nextControl": null,
"isLocked": false,
Expand All @@ -49,8 +33,8 @@
"pointTowardsZones": [],
"eventMarkers": [],
"globalConstraints": {
"maxVelocity": 3.0,
"maxAcceleration": 3.0,
"maxVelocity": 0.5,
"maxAcceleration": 1.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0,
"nominalVoltage": 12.0,
Expand Down
36 changes: 28 additions & 8 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,17 +19,21 @@

import com.fasterxml.jackson.core.JsonProcessingException;
import com.fasterxml.jackson.databind.ObjectMapper;
import com.pathplanner.lib.config.ModuleConfig;
import com.pathplanner.lib.config.PIDConstants;
import com.pathplanner.lib.config.RobotConfig;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj.RobotBase;
import frc.robot.Constants.AprilTagConstants.AprilTagLayoutType;
import frc.robot.subsystems.drive.Drive;
import frc.robot.subsystems.drive.SwerveConstants;
import frc.robot.util.Alert;
import frc.robot.util.Alert.AlertType;
Expand Down Expand Up @@ -135,10 +139,6 @@ public static final class DrivebaseConstants {
public static final double kMaxLinearAccel = 4.0; // m/s/s
public static final double kMaxAngularAccel = Units.degreesToRadians(720);

// Drive and Turn PID constants
public static final PIDConstants drivePID = new PIDConstants(0.05, 0.0, 0.0);
public static final PIDConstants steerPID = new PIDConstants(2.0, 0.0, 0.4);

// Hold time on motor brakes when disabled
public static final double kWheelLockTime = 10; // seconds

Expand Down Expand Up @@ -235,10 +235,30 @@ public static class OperatorConstants {
/** Autonomous Action Constants ****************************************** */
public static final class AutoConstants {

// PathPlanner Translation PID constants
public static final PIDConstants kAutoDrivePID = new PIDConstants(0.7, 0, 0);
// PathPlanner Rotation PID constants
public static final PIDConstants kAutoSteerPID = new PIDConstants(0.4, 0, 0.01);
// Drive and Turn PID constants used for PathPlanner
public static final PIDConstants kPPdrivePID = new PIDConstants(5.0, 0.0, 0.0);
public static final PIDConstants kPPsteerPID = new PIDConstants(5.0, 0.0, 0.0);

// PathPlanner Config constants
public static final RobotConfig kPathPlannerConfig =
new RobotConfig(
PhysicalConstants.kRobotMassKg,
PhysicalConstants.kRobotMOI,
new ModuleConfig(
SwerveConstants.kWheelRadiusMeters,
DrivebaseConstants.kMaxLinearSpeed,
PhysicalConstants.kWheelCOF,
DCMotor.getKrakenX60Foc(1).withReduction(SwerveConstants.kDriveGearRatio),
SwerveConstants.kDriveSlipCurrent,
1),
Drive.getModuleTranslations());

// Alternatively, we can build this from the PathPlanner GUI:
// public static final RobotConfig kPathPlannerConfig = RobotConfig.fromGUISettings();

// Drive and Turn PID constants used for Chorep
public static final PIDConstants kChoreoDrivePID = new PIDConstants(10.0, 0.0, 0.0);
public static final PIDConstants kChoreoSteerPID = new PIDConstants(7.5, 0.0, 0.0);
}

/** Vision Constants (Assuming PhotonVision) ***************************** */
Expand Down
20 changes: 8 additions & 12 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,7 @@ public class Robot extends LoggedRobot {
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Record metadata
Logger.recordMetadata("Robot", Constants.getRobot().toString());
Logger.recordMetadata("TuningMode", Boolean.toString(Constants.tuningMode));
Expand Down Expand Up @@ -85,18 +84,14 @@ public void robotInit() {
break;
}

// See http://bit.ly/3YIzFZ6 for more information on timestamps in AdvantageKit.
// Logger.disableDeterministicTimestamps()

// Start AdvantageKit logger
Logger.start();

// Instantiate our RobotContainer. This will perform all our button bindings,
// and put our autonomous chooser on the dashboard.
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

// Create a timer to disable motor brake a few seconds after disable. This will
// let the robot
// Create a timer to disable motor brake a few seconds after disable. This will let the robot
// stop immediately when disabled, but then also let it be pushed more
m_disabledTimer = new Timer();
}
Expand Down Expand Up @@ -144,8 +139,11 @@ public void disabledPeriodic() {
@Override
public void autonomousInit() {

// TODO: Make sure Gyro inits here with whatever is in the path planning thingie
// Just in case, cancel all running commands
CommandScheduler.getInstance().cancelAll();
m_robotContainer.setMotorBrake(true);

// TODO: Make sure Gyro inits here with whatever is in the path planning thingie
switch (Constants.getAutoType()) {
case PATHPLANNER:
m_autoCommandPathPlanner = m_robotContainer.getAutonomousCommandPathPlanner();
Expand Down Expand Up @@ -179,7 +177,6 @@ public void teleopInit() {
} else {
CommandScheduler.getInstance().cancelAll();
}
m_robotContainer.setDriveMode();
m_robotContainer.setMotorBrake(true);
}

Expand All @@ -192,7 +189,6 @@ public void teleopPeriodic() {}
public void testInit() {
// Cancels all running commands at the start of test mode.
CommandScheduler.getInstance().cancelAll();
m_robotContainer.setDriveMode();
}

/** This function is called periodically during test mode. */
Expand Down
15 changes: 6 additions & 9 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
import choreo.auto.AutoRoutine;
import choreo.auto.AutoTrajectory;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.GenericHID;
Expand Down Expand Up @@ -164,6 +163,7 @@ public RobotContainer() {
autoChooserChoreo = null;
autoFactoryChoreo = null;
break;

case CHOREO:
autoFactoryChoreo =
new AutoFactory(
Expand All @@ -179,24 +179,25 @@ public RobotContainer() {
// Set the others to null
autoChooserPathPlanner = null;
break;

default:
// Then, throw the error
throw new RuntimeException(
"Incorrect AUTO type selected in Constants: " + Constants.getAutoType());
}

// Configure the trigger bindings
configureBindings();
// Define Auto commands
defineAutoCommands();
// Define SysIs Routines
definesysIdRoutines();
// Configure the button and trigger bindings
configureBindings();
}

/** Use this method to define your Autonomous commands for use with PathPlanner / Choreo */
private void defineAutoCommands() {

NamedCommands.registerCommand("Zero", Commands.runOnce(() -> m_drivebase.zero()));
// NamedCommands.registerCommand("Zero", Commands.runOnce(() -> m_drivebase.zero()));
}

/**
Expand Down Expand Up @@ -257,7 +258,7 @@ private void configureBindings() {
.onTrue(
Commands.runOnce(
() ->
m_drivebase.setPose(
m_drivebase.resetPose(
new Pose2d(m_drivebase.getPose().getTranslation(), new Rotation2d())),
m_drivebase)
.ignoringDisable(true));
Expand Down Expand Up @@ -295,10 +296,6 @@ public void getAutonomousCommandChoreo() {
RobotModeTriggers.autonomous().whileTrue(autoChooserChoreo.selectedCommandScheduler());
}

public void setDriveMode() {
configureBindings();
}

/** Set the motor neutral mode to BRAKE / COAST for T/F */
public void setMotorBrake(boolean brake) {
m_drivebase.setMotorBrake(brake);
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/commands/ChoreoAutoController.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,11 @@
public class ChoreoAutoController implements Consumer<SwerveSample> {
private final Drive drive; // drive subsystem
private final PIDController xController =
new PIDController(kAutoDrivePID.kP, 0.0, kAutoDrivePID.kD);
new PIDController(kChoreoDrivePID.kP, kChoreoDrivePID.kI, kChoreoDrivePID.kD);
private final PIDController yController =
new PIDController(kAutoDrivePID.kP, 0.0, kAutoDrivePID.kD);
new PIDController(kChoreoDrivePID.kP, kChoreoDrivePID.kI, kChoreoDrivePID.kD);
private final PIDController headingController =
new PIDController(kAutoSteerPID.kP, 0.0, kAutoSteerPID.kD);
new PIDController(kChoreoSteerPID.kP, kChoreoSteerPID.kI, kChoreoSteerPID.kD);

public ChoreoAutoController(Drive drive) {
this.drive = drive;
Expand Down
7 changes: 4 additions & 3 deletions src/main/java/frc/robot/commands/DriveCommands.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.Constants.AutoConstants;
import frc.robot.Constants.DrivebaseConstants;
import frc.robot.Constants.OperatorConstants;
import frc.robot.subsystems.drive.Drive;
Expand Down Expand Up @@ -125,9 +126,9 @@ public static Command fieldRelativeDriveAtAngle(
// Create PID controller
ProfiledPIDController angleController =
new ProfiledPIDController(
DrivebaseConstants.steerPID.kP,
DrivebaseConstants.steerPID.kI,
DrivebaseConstants.steerPID.kD,
AutoConstants.kPPsteerPID.kP,
AutoConstants.kPPsteerPID.kI,
AutoConstants.kPPsteerPID.kD,
new TrapezoidProfile.Constraints(
DrivebaseConstants.kMaxAngularSpeed, DrivebaseConstants.kMaxAngularAccel));
angleController.enableContinuousInput(-Math.PI, Math.PI);
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/generated/TunerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ public class TunerConstants {
private static final int kFrontLeftDriveMotorId = 1;
private static final int kFrontLeftSteerMotorId = 2;
private static final int kFrontLeftEncoderId = 3;
private static final Angle kFrontLeftEncoderOffset = Rotations.of(0.087158203125);
private static final Angle kFrontLeftEncoderOffset = Rotations.of(0.088134765625);
private static final boolean kFrontLeftSteerMotorInverted = true;
private static final boolean kFrontLeftEncoderInverted = false;

Expand All @@ -149,7 +149,7 @@ public class TunerConstants {
private static final int kFrontRightDriveMotorId = 4;
private static final int kFrontRightSteerMotorId = 5;
private static final int kFrontRightEncoderId = 6;
private static final Angle kFrontRightEncoderOffset = Rotations.of(0.410888671875);
private static final Angle kFrontRightEncoderOffset = Rotations.of(0.23779296875);
private static final boolean kFrontRightSteerMotorInverted = true;
private static final boolean kFrontRightEncoderInverted = false;

Expand All @@ -160,7 +160,7 @@ public class TunerConstants {
private static final int kBackLeftDriveMotorId = 7;
private static final int kBackLeftSteerMotorId = 8;
private static final int kBackLeftEncoderId = 9;
private static final Angle kBackLeftEncoderOffset = Rotations.of(-0.1142578125);
private static final Angle kBackLeftEncoderOffset = Rotations.of(-0.114990234375);
private static final boolean kBackLeftSteerMotorInverted = true;
private static final boolean kBackLeftEncoderInverted = false;

Expand All @@ -171,7 +171,7 @@ public class TunerConstants {
private static final int kBackRightDriveMotorId = 10;
private static final int kBackRightSteerMotorId = 11;
private static final int kBackRightEncoderId = 12;
private static final Angle kBackRightEncoderOffset = Rotations.of(-0.471923828125);
private static final Angle kBackRightEncoderOffset = Rotations.of(-0.47265625);
private static final boolean kBackRightSteerMotorInverted = true;
private static final boolean kBackRightEncoderInverted = false;

Expand Down
Loading
Loading