From a520ac8225db0b8a79d2f9b0bd28c40287b2720e Mon Sep 17 00:00:00 2001 From: Ronan-B Date: Sat, 18 Jan 2025 13:44:00 -0800 Subject: [PATCH 1/8] Test Auto with more complicated path --- .../paths/{New Path.path => Test1.path} | 39 +++++++++++-------- .../java/frc/robot/commands/TestAuto1.java | 19 +++++++++ 2 files changed, 42 insertions(+), 16 deletions(-) rename src/main/deploy/pathplanner/paths/{New Path.path => Test1.path} (70%) create mode 100644 src/main/java/frc/robot/commands/TestAuto1.java diff --git a/src/main/deploy/pathplanner/paths/New Path.path b/src/main/deploy/pathplanner/paths/Test1.path similarity index 70% rename from src/main/deploy/pathplanner/paths/New Path.path rename to src/main/deploy/pathplanner/paths/Test1.path index b030c88..37e82e1 100644 --- a/src/main/deploy/pathplanner/paths/New Path.path +++ b/src/main/deploy/pathplanner/paths/Test1.path @@ -16,32 +16,32 @@ }, { "anchor": { - "x": 4.029, - "y": 6.922 + "x": 4.323, + "y": 6.921747159090909 }, "prevControl": { - "x": 3.779, - "y": 6.922 + "x": 4.073, + "y": 6.921747159090909 }, "nextControl": { - "x": 4.279, - "y": 6.922 + "x": 4.573, + "y": 6.921747159090909 }, "isLocked": false, "linkedName": null }, { "anchor": { - "x": 4.029, - "y": 5.645383522727273 + "x": 4.323, + "y": 5.546 }, "prevControl": { - "x": 3.779, - "y": 5.645383522727273 + "x": 4.072999999999999, + "y": 5.546 }, "nextControl": { - "x": 4.279, - "y": 5.645383522727273 + "x": 4.572999999999996, + "y": 5.546 }, "isLocked": false, "linkedName": null @@ -49,11 +49,11 @@ { "anchor": { "x": 1.884630681818182, - "y": 5.645383522727273 + "y": 5.545667613636364 }, "prevControl": { - "x": 1.6346306818181817, - "y": 5.645383522727273 + "x": 1.634630681818182, + "y": 5.545667613636364 }, "nextControl": null, "isLocked": false, @@ -63,7 +63,14 @@ "rotationTargets": [], "constraintZones": [], "pointTowardsZones": [], - "eventMarkers": [], + "eventMarkers": [ + { + "name": "", + "waypointRelativePos": 0, + "endWaypointRelativePos": null, + "command": null + } + ], "globalConstraints": { "maxVelocity": 3.0, "maxAcceleration": 3.0, diff --git a/src/main/java/frc/robot/commands/TestAuto1.java b/src/main/java/frc/robot/commands/TestAuto1.java new file mode 100644 index 0000000..2210c67 --- /dev/null +++ b/src/main/java/frc/robot/commands/TestAuto1.java @@ -0,0 +1,19 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.commands; + +import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; + +// NOTE: Consider using this command inline, rather than writing a subclass. For more +// information, see: +// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html +public class TestAuto1 extends SequentialCommandGroup { + /** Creates a new TestAuto1. */ + public TestAuto1() { + // Add your commands in the addCommands() call, e.g. + // addCommands(new FooCommand(), new BarCommand()); + addCommands(); + } +} From 4e0fb38f37fc088560120f4dc542c89ad258ca69 Mon Sep 17 00:00:00 2001 From: Ronan-B Date: Sat, 18 Jan 2025 14:16:20 -0800 Subject: [PATCH 2/8] More complicated auto --- .../java/frc/robot/commands/TestAuto1.java | 43 +++++++++++++++---- 1 file changed, 35 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/commands/TestAuto1.java b/src/main/java/frc/robot/commands/TestAuto1.java index 2210c67..afd9981 100644 --- a/src/main/java/frc/robot/commands/TestAuto1.java +++ b/src/main/java/frc/robot/commands/TestAuto1.java @@ -4,16 +4,43 @@ package frc.robot.commands; +import com.ctre.phoenix6.swerve.SwerveRequest; +import com.pathplanner.lib.auto.AutoBuilder; +import com.pathplanner.lib.path.PathPlannerPath; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; +import edu.wpi.first.wpilibj2.command.WaitCommand; +import frc.robot.subsystems.CommandSwerveDrivetrain; -// NOTE: Consider using this command inline, rather than writing a subclass. For more -// information, see: -// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html public class TestAuto1 extends SequentialCommandGroup { - /** Creates a new TestAuto1. */ - public TestAuto1() { - // Add your commands in the addCommands() call, e.g. - // addCommands(new FooCommand(), new BarCommand()); - addCommands(); + /** Creates a new DriveForward. */ + public TestAuto1(CommandSwerveDrivetrain swerveDrive /* TODO: Add field sim */) { + try { + PathPlannerPath path = PathPlannerPath.fromPathFile("Test1"); + + var m_ppCommand = AutoBuilder.followPath(path); + + var point = new SwerveRequest.PointWheelsAt(); + var stopRequest = new SwerveRequest.ApplyRobotSpeeds(); + + // Will throw an exception if the starting pose is not present + var starting_pose = path.getStartingHolonomicPose().orElseThrow(); + + // Add your commands in the addCommands() call, e.g. + // addCommands(new FooCommand(), new BarCommand()); + addCommands( + new InstantCommand( // Reset the pose of the robot to the starting pose of the path + () -> swerveDrive.resetPose(starting_pose)), + new InstantCommand( + () -> swerveDrive.applyRequest(() -> point.withModuleDirection(new Rotation2d())), + swerveDrive) + .alongWith(new WaitCommand(1)), + m_ppCommand.andThen(() -> swerveDrive.setControl(stopRequest))); + } catch (Exception e) { + DriverStation.reportError("Failed to load path for DriveForward", e.getStackTrace()); + addCommands(new WaitCommand(0)); + } } } From 92e3937d61431946c39b51e6342593404a50a9b5 Mon Sep 17 00:00:00 2001 From: Ronan-B Date: Sat, 18 Jan 2025 14:16:48 -0800 Subject: [PATCH 3/8] Auto stash before checking out "origin/drive-auto-testing" --- src/main/java/frc/robot/RobotContainer.java | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index ba1826e..135fb29 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -8,6 +8,14 @@ import com.ctre.phoenix6.SignalLogger; import com.ctre.phoenix6.swerve.SwerveRequest; +<<<<<<< Updated upstream +======= +import com.pathplanner.lib.auto.AutoBuilder; +import com.pathplanner.lib.commands.FollowPathCommand; +import com.pathplanner.lib.path.PathPlannerPath; + +import edu.wpi.first.wpilibj.DriverStation; +>>>>>>> Stashed changes import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; @@ -97,7 +105,11 @@ private void initializeSubSystems() { private void initAutoChooser() { SmartDashboard.putData("Auto Mode", m_chooser); m_chooser.setDefaultOption("Do Nothing", new WaitCommand(0)); +<<<<<<< Updated upstream +======= + +>>>>>>> Stashed changes m_chooser.addOption("DriveForward", new DriveForward(m_swerveDrive)); } @@ -176,7 +188,6 @@ private void configureBindings() { m_driverController.x().whileTrue(new RunAlgaeIntake(m_algaeIntake, 0.5)); // outtake m_driverController.y().whileTrue(new RunAlgaeIntake(m_algaeIntake, -0.5)); // intake } - /** * Use this to pass the autonomous command to the main {@link Robot} class. * From 8b27f04163cf9eb3cc48736874c3f8cd37e61393 Mon Sep 17 00:00:00 2001 From: Ronan-B Date: Sun, 19 Jan 2025 16:13:41 -0800 Subject: [PATCH 4/8] 4 piece (only path testing) --- .../deploy/pathplanner/autos/New Auto.auto | 19 +++ src/main/deploy/pathplanner/paths/Test1.path | 131 ++++++++++++++---- 2 files changed, 125 insertions(+), 25 deletions(-) create mode 100644 src/main/deploy/pathplanner/autos/New Auto.auto diff --git a/src/main/deploy/pathplanner/autos/New Auto.auto b/src/main/deploy/pathplanner/autos/New Auto.auto new file mode 100644 index 0000000..6cd4ec6 --- /dev/null +++ b/src/main/deploy/pathplanner/autos/New Auto.auto @@ -0,0 +1,19 @@ +{ + "version": "2025.0", + "command": { + "type": "sequential", + "data": { + "commands": [ + { + "type": "path", + "data": { + "pathName": "Test1" + } + } + ] + } + }, + "resetOdom": true, + "folder": null, + "choreoAuto": false +} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/Test1.path b/src/main/deploy/pathplanner/paths/Test1.path index 37e82e1..2edb4b4 100644 --- a/src/main/deploy/pathplanner/paths/Test1.path +++ b/src/main/deploy/pathplanner/paths/Test1.path @@ -3,64 +3,145 @@ "waypoints": [ { "anchor": { - "x": 1.884630681818182, - "y": 6.921747159090909 + "x": 6.980113636363637, + "y": 1.7464914772727262 }, "prevControl": null, "nextControl": { - "x": 2.134630681818182, - "y": 6.921747159090909 + "x": 5.914029925636826, + "y": 1.649596167268574 }, "isLocked": false, "linkedName": null }, { "anchor": { - "x": 4.323, - "y": 6.921747159090909 + "x": 5.055596590909091, + "y": 2.8034801136363625 }, "prevControl": { - "x": 4.073, - "y": 6.921747159090909 + "x": 5.27887391252156, + "y": 2.6910201756425938 }, "nextControl": { - "x": 4.573, - "y": 6.921747159090909 + "x": 4.832319269296622, + "y": 2.9159400516301313 }, "isLocked": false, "linkedName": null }, { "anchor": { - "x": 4.323, - "y": 5.546 + "x": 1.8148295454545456, + "y": 0.7293892045454539 }, "prevControl": { - "x": 4.072999999999999, - "y": 5.546 + "x": 1.926632944329535, + "y": 0.9529960022954329 }, "nextControl": { - "x": 4.572999999999996, - "y": 5.546 + "x": 1.7030261465795562, + "y": 0.5057824067954748 }, "isLocked": false, "linkedName": null }, { "anchor": { - "x": 1.884630681818182, - "y": 5.545667613636364 + "x": 3.878948863636363, + "y": 2.8034801136363625 }, "prevControl": { - "x": 1.634630681818182, - "y": 5.545667613636364 + "x": 3.710734216820903, + "y": 2.5632447010820343 + }, + "nextControl": { + "x": 4.022342972724125, + "y": 3.0082681247086107 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 1.4458806818181815, + "y": 0.8490482954545451 + }, + "prevControl": { + "x": 1.366107954545454, + "y": 0.5997585227272703 + }, + "nextControl": { + "x": 1.5220746135941274, + "y": 1.0871543322543762 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 3.5997443181818185, + "y": 2.963025568181818 + }, + "prevControl": { + "x": 3.549025212233497, + "y": 2.718224480986922 + }, + "nextControl": { + "x": 3.65046342413014, + "y": 3.207826655376714 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 1.4458806818181815, + "y": 0.958735795454545 + }, + "prevControl": { + "x": 1.5515352472533563, + "y": 1.1853127422137075 + }, + "nextControl": { + "x": 1.3402261163830067, + "y": 0.7321588486953825 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 3.0114204545454544, + "y": 3.840525568186805 + }, + "prevControl": { + "x": 2.968008410128722, + "y": 3.5943236299337533 }, "nextControl": null, "isLocked": false, "linkedName": null } ], - "rotationTargets": [], + "rotationTargets": [ + { + "waypointRelativePos": 0.976063829787228, + "rotationDegrees": 124.34099179535119 + }, + { + "waypointRelativePos": 1.9428191489361812, + "rotationDegrees": 46.59192238122859 + }, + { + "waypointRelativePos": 4.961436170212785, + "rotationDegrees": 52.1285759762159 + }, + { + "waypointRelativePos": 5.976063829787137, + "rotationDegrees": 52.25426954444807 + } + ], "constraintZones": [], "pointTowardsZones": [], "eventMarkers": [ @@ -72,8 +153,8 @@ } ], "globalConstraints": { - "maxVelocity": 3.0, - "maxAcceleration": 3.0, + "maxVelocity": 5.5, + "maxAcceleration": 6.7, "maxAngularVelocity": 540.0, "maxAngularAcceleration": 720.0, "nominalVoltage": 12.0, @@ -87,7 +168,7 @@ "folder": null, "idealStartingState": { "velocity": 0, - "rotation": 0.0 + "rotation": 180.0 }, - "useDefaultConstraints": true + "useDefaultConstraints": false } \ No newline at end of file From 664450581866313ffd32aed9f34a490c8c7e0828 Mon Sep 17 00:00:00 2001 From: Ronan-B Date: Sun, 19 Jan 2025 18:27:29 -0800 Subject: [PATCH 5/8] Testesd 4 peice auto The path lookes mostly accurate --- .../autos/{New Auto.auto => Test1.auto} | 0 src/main/deploy/pathplanner/paths/Test1.path | 80 +++++++++++-------- src/main/deploy/pathplanner/paths/Test2.path | 54 +++++++++++++ src/main/java/frc/robot/RobotContainer.java | 15 +--- 4 files changed, 105 insertions(+), 44 deletions(-) rename src/main/deploy/pathplanner/autos/{New Auto.auto => Test1.auto} (100%) create mode 100644 src/main/deploy/pathplanner/paths/Test2.path diff --git a/src/main/deploy/pathplanner/autos/New Auto.auto b/src/main/deploy/pathplanner/autos/Test1.auto similarity index 100% rename from src/main/deploy/pathplanner/autos/New Auto.auto rename to src/main/deploy/pathplanner/autos/Test1.auto diff --git a/src/main/deploy/pathplanner/paths/Test1.path b/src/main/deploy/pathplanner/paths/Test1.path index 2edb4b4..6245f03 100644 --- a/src/main/deploy/pathplanner/paths/Test1.path +++ b/src/main/deploy/pathplanner/paths/Test1.path @@ -3,12 +3,12 @@ "waypoints": [ { "anchor": { - "x": 6.980113636363637, + "x": 7.1, "y": 1.7464914772727262 }, "prevControl": null, "nextControl": { - "x": 5.914029925636826, + "x": 6.033916289273189, "y": 1.649596167268574 }, "isLocked": false, @@ -16,32 +16,48 @@ }, { "anchor": { - "x": 5.055596590909091, - "y": 2.8034801136363625 + "x": 5.0, + "y": 2.7 }, "prevControl": { - "x": 5.27887391252156, - "y": 2.6910201756425938 + "x": 5.223277321612469, + "y": 2.5875400620062314 }, "nextControl": { - "x": 4.832319269296622, - "y": 2.9159400516301313 + "x": 4.776722678387531, + "y": 2.812459937993769 }, "isLocked": false, "linkedName": null }, { "anchor": { - "x": 1.8148295454545456, - "y": 0.7293892045454539 + "x": 4.666704545454546, + "y": 2.1054687499999987 }, "prevControl": { - "x": 1.926632944329535, - "y": 0.9529960022954329 + "x": 5.396009858797951, + "y": 2.5773225696812925 }, "nextControl": { - "x": 1.7030261465795562, - "y": 0.5057824067954748 + "x": 3.9373992321111384, + "y": 1.633614930318703 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 1.6453125, + "y": 0.65 + }, + "prevControl": { + "x": 1.7571158988749893, + "y": 0.8736067977499792 + }, + "nextControl": { + "x": 1.5335091011250106, + "y": 0.426393202250021 }, "isLocked": false, "linkedName": null @@ -64,16 +80,16 @@ }, { "anchor": { - "x": 1.4458806818181815, - "y": 0.8490482954545451 + "x": 1.3361931818181818, + "y": 0.8091619318181813 }, "prevControl": { - "x": 1.366107954545454, - "y": 0.5997585227272703 + "x": 1.2564204545454543, + "y": 0.5598721590909065 }, "nextControl": { - "x": 1.5220746135941274, - "y": 1.0871543322543762 + "x": 1.4123871135941277, + "y": 1.0472679686180126 }, "isLocked": false, "linkedName": null @@ -107,17 +123,17 @@ "x": 1.3402261163830067, "y": 0.7321588486953825 }, - "isLocked": false, + "isLocked": true, "linkedName": null }, { "anchor": { - "x": 3.0114204545454544, - "y": 3.840525568186805 + "x": 3.091, + "y": 3.98 }, "prevControl": { - "x": 2.968008410128722, - "y": 3.5943236299337533 + "x": 3.0475879555832677, + "y": 3.733798061746948 }, "nextControl": null, "isLocked": false, @@ -127,18 +143,18 @@ "rotationTargets": [ { "waypointRelativePos": 0.976063829787228, - "rotationDegrees": 124.34099179535119 + "rotationDegrees": 115.438429497609 }, { - "waypointRelativePos": 1.9428191489361812, + "waypointRelativePos": 2.9, "rotationDegrees": 46.59192238122859 }, { - "waypointRelativePos": 4.961436170212785, + "waypointRelativePos": 5.961436170212785, "rotationDegrees": 52.1285759762159 }, { - "waypointRelativePos": 5.976063829787137, + "waypointRelativePos": 6.976063829787137, "rotationDegrees": 52.25426954444807 } ], @@ -153,8 +169,8 @@ } ], "globalConstraints": { - "maxVelocity": 5.5, - "maxAcceleration": 6.7, + "maxVelocity": 3.0, + "maxAcceleration": 3.0, "maxAngularVelocity": 540.0, "maxAngularAcceleration": 720.0, "nominalVoltage": 12.0, @@ -170,5 +186,5 @@ "velocity": 0, "rotation": 180.0 }, - "useDefaultConstraints": false + "useDefaultConstraints": true } \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/Test2.path b/src/main/deploy/pathplanner/paths/Test2.path new file mode 100644 index 0000000..c61191c --- /dev/null +++ b/src/main/deploy/pathplanner/paths/Test2.path @@ -0,0 +1,54 @@ +{ + "version": "2025.0", + "waypoints": [ + { + "anchor": { + "x": 7.109744318181819, + "y": 6.014332386363637 + }, + "prevControl": null, + "nextControl": { + "x": 6.078774943216172, + "y": 6.190289875933901 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 5.414573863636364, + "y": 5.136832386363635 + }, + "prevControl": { + "x": 5.1501165720311635, + "y": 4.782679945131105 + }, + "nextControl": null, + "isLocked": false, + "linkedName": null + } + ], + "rotationTargets": [], + "constraintZones": [], + "pointTowardsZones": [], + "eventMarkers": [], + "globalConstraints": { + "maxVelocity": 3.0, + "maxAcceleration": 3.0, + "maxAngularVelocity": 540.0, + "maxAngularAcceleration": 720.0, + "nominalVoltage": 12.0, + "unlimited": false + }, + "goalEndState": { + "velocity": 0.0, + "rotation": -126.19320730556458 + }, + "reversed": false, + "folder": null, + "idealStartingState": { + "velocity": 0, + "rotation": -178.89829388479356 + }, + "useDefaultConstraints": true +} \ No newline at end of file diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 135fb29..651c5ca 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -8,14 +8,6 @@ import com.ctre.phoenix6.SignalLogger; import com.ctre.phoenix6.swerve.SwerveRequest; -<<<<<<< Updated upstream -======= -import com.pathplanner.lib.auto.AutoBuilder; -import com.pathplanner.lib.commands.FollowPathCommand; -import com.pathplanner.lib.path.PathPlannerPath; - -import edu.wpi.first.wpilibj.DriverStation; ->>>>>>> Stashed changes import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; @@ -30,6 +22,7 @@ import frc.robot.commands.RunAlgaeIntake; import frc.robot.commands.RunCoralOuttake; import frc.robot.commands.SwerveCharacterization; +import frc.robot.commands.TestAuto1; import frc.robot.constants.ROBOT; import frc.robot.constants.SWERVE; import frc.robot.constants.SWERVE.ROUTINE_TYPE; @@ -105,12 +98,10 @@ private void initializeSubSystems() { private void initAutoChooser() { SmartDashboard.putData("Auto Mode", m_chooser); m_chooser.setDefaultOption("Do Nothing", new WaitCommand(0)); -<<<<<<< Updated upstream -======= - ->>>>>>> Stashed changes m_chooser.addOption("DriveForward", new DriveForward(m_swerveDrive)); + m_chooser.addOption("TestAuto1", new TestAuto1(m_swerveDrive)); + } private void initSmartDashboard() { From 3a3efbcb44b5f1337acc808b0ea642b8f1ea0723 Mon Sep 17 00:00:00 2001 From: Ronan-B Date: Tue, 21 Jan 2025 09:00:23 -0800 Subject: [PATCH 6/8] 4 piece mirrored version --- src/main/deploy/pathplanner/paths/Test2.path | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/deploy/pathplanner/paths/Test2.path b/src/main/deploy/pathplanner/paths/Test2.path index c61191c..0bf1d58 100644 --- a/src/main/deploy/pathplanner/paths/Test2.path +++ b/src/main/deploy/pathplanner/paths/Test2.path @@ -4,12 +4,12 @@ { "anchor": { "x": 7.109744318181819, - "y": 6.014332386363637 + "y": 6.2 }, "prevControl": null, "nextControl": { - "x": 6.078774943216172, - "y": 6.190289875933901 + "x": 6.09292862387953, + "y": 6.261535626920918 }, "isLocked": false, "linkedName": null @@ -20,8 +20,8 @@ "y": 5.136832386363635 }, "prevControl": { - "x": 5.1501165720311635, - "y": 4.782679945131105 + "x": 5.220522783519216, + "y": 4.8353394365031255 }, "nextControl": null, "isLocked": false, From 5ca31b9928f459034bbf67df001c4b83b27b9d2c Mon Sep 17 00:00:00 2001 From: Ronan-B Date: Tue, 21 Jan 2025 09:02:31 -0800 Subject: [PATCH 7/8] Added basic score 1 auto --- src/main/deploy/pathplanner/autos/Test2.auto | 12 +++++ src/main/deploy/pathplanner/paths/Score1.path | 54 +++++++++++++++++++ 2 files changed, 66 insertions(+) create mode 100644 src/main/deploy/pathplanner/autos/Test2.auto create mode 100644 src/main/deploy/pathplanner/paths/Score1.path diff --git a/src/main/deploy/pathplanner/autos/Test2.auto b/src/main/deploy/pathplanner/autos/Test2.auto new file mode 100644 index 0000000..440a1ea --- /dev/null +++ b/src/main/deploy/pathplanner/autos/Test2.auto @@ -0,0 +1,12 @@ +{ + "version": "2025.0", + "command": { + "type": "sequential", + "data": { + "commands": [] + } + }, + "resetOdom": true, + "folder": null, + "choreoAuto": false +} \ No newline at end of file diff --git a/src/main/deploy/pathplanner/paths/Score1.path b/src/main/deploy/pathplanner/paths/Score1.path new file mode 100644 index 0000000..15cc789 --- /dev/null +++ b/src/main/deploy/pathplanner/paths/Score1.path @@ -0,0 +1,54 @@ +{ + "version": "2025.0", + "waypoints": [ + { + "anchor": { + "x": 7.16, + "y": 3.830553977272727 + }, + "prevControl": null, + "nextControl": { + "x": 7.41, + "y": 3.830553977272727 + }, + "isLocked": false, + "linkedName": null + }, + { + "anchor": { + "x": 5.88, + "y": 3.830553977272727 + }, + "prevControl": { + "x": 5.63, + "y": 3.830553977272727 + }, + "nextControl": null, + "isLocked": false, + "linkedName": null + } + ], + "rotationTargets": [], + "constraintZones": [], + "pointTowardsZones": [], + "eventMarkers": [], + "globalConstraints": { + "maxVelocity": 3.0, + "maxAcceleration": 3.0, + "maxAngularVelocity": 540.0, + "maxAngularAcceleration": 720.0, + "nominalVoltage": 12.0, + "unlimited": false + }, + "goalEndState": { + "velocity": 0, + "rotation": 180.0 + }, + "reversed": false, + "folder": null, + "idealStartingState": { + "velocity": 0, + "rotation": 180.0 + }, + "useDefaultConstraints": true +} \ No newline at end of file From b1d753e2cb201e84f07931ad528c5173584a2004 Mon Sep 17 00:00:00 2001 From: Ronan-B <114883633+Ronan-B@users.noreply.github.com> Date: Mon, 27 Jan 2025 00:13:15 +0000 Subject: [PATCH 8/8] Automatically applied spotless --- src/main/java/frc/robot/RobotContainer.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 651c5ca..7eba0ca 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -101,7 +101,6 @@ private void initAutoChooser() { m_chooser.addOption("DriveForward", new DriveForward(m_swerveDrive)); m_chooser.addOption("TestAuto1", new TestAuto1(m_swerveDrive)); - } private void initSmartDashboard() { @@ -179,6 +178,7 @@ private void configureBindings() { m_driverController.x().whileTrue(new RunAlgaeIntake(m_algaeIntake, 0.5)); // outtake m_driverController.y().whileTrue(new RunAlgaeIntake(m_algaeIntake, -0.5)); // intake } + /** * Use this to pass the autonomous command to the main {@link Robot} class. *