From 2c197d2f940aac749591fb190d5f7d4da5daeff7 Mon Sep 17 00:00:00 2001 From: Arnav Jain <90660802+ArnoUUU@users.noreply.github.com> Date: Mon, 25 Mar 2024 17:17:48 -0700 Subject: [PATCH] Auton comp changes (#39) * removed quadratic scaling on drive rotation * untested, will test in match, 4 note change * fixed 4 note first note * increased shooter on time * feat: amp changes from comp --------- Co-authored-by: ProgrammingSR --- src/main/deploy/pathplanner/autos/4-Center-Stays.auto | 2 +- .../deploy/pathplanner/paths/CenterNote-Center.path | 4 ++-- .../deploy/pathplanner/paths/Middle5thNote-Right.path | 6 +++--- src/main/java/frc/robot/RobotContainer.java | 10 +++++++--- .../java/frc/robot/commands/NoteOuttakeCommand.java | 1 - .../java/frc/robot/subsystems/ShooterSubsystem.java | 4 ++++ 6 files changed, 17 insertions(+), 10 deletions(-) diff --git a/src/main/deploy/pathplanner/autos/4-Center-Stays.auto b/src/main/deploy/pathplanner/autos/4-Center-Stays.auto index 602b83d..7d849f7 100644 --- a/src/main/deploy/pathplanner/autos/4-Center-Stays.auto +++ b/src/main/deploy/pathplanner/autos/4-Center-Stays.auto @@ -2,7 +2,7 @@ "version": 1.0, "startingPose": { "position": { - "x": 1.3470318873095533, + "x": 1.4, "y": 5.5216374597852385 }, "rotation": 0 diff --git a/src/main/deploy/pathplanner/paths/CenterNote-Center.path b/src/main/deploy/pathplanner/paths/CenterNote-Center.path index b50dfaa..c8ea72a 100644 --- a/src/main/deploy/pathplanner/paths/CenterNote-Center.path +++ b/src/main/deploy/pathplanner/paths/CenterNote-Center.path @@ -3,12 +3,12 @@ "waypoints": [ { "anchor": { - "x": 1.3470318873095533, + "x": 1.4, "y": 5.5216374597852385 }, "prevControl": null, "nextControl": { - "x": 2.3470318873095533, + "x": 2.4, "y": 5.5216374597852385 }, "isLocked": false, diff --git a/src/main/deploy/pathplanner/paths/Middle5thNote-Right.path b/src/main/deploy/pathplanner/paths/Middle5thNote-Right.path index a389143..4777efb 100644 --- a/src/main/deploy/pathplanner/paths/Middle5thNote-Right.path +++ b/src/main/deploy/pathplanner/paths/Middle5thNote-Right.path @@ -17,15 +17,15 @@ { "anchor": { "x": 8.05, - "y": 0.7104198823782273 + "y": 0.6 }, "prevControl": { "x": 7.050000000000001, - "y": 0.7104198823782273 + "y": 0.6 }, "nextControl": { "x": 9.049999999999988, - "y": 0.7104198823782273 + "y": 0.6 }, "isLocked": false, "linkedName": null diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index db45276..5cc7405 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -12,7 +12,6 @@ import edu.wpi.first.math.MathUtil; import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.XboxController; import edu.wpi.first.wpilibj.XboxController.Button; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; @@ -65,8 +64,8 @@ public class RobotContainer { public RobotContainer() { NamedCommands.registerCommand("Shoot", new SequentialCommandGroup( - new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, ShooterConstants.kShooterOnTime), - new ParallelDeadlineGroup(new WaitCommand(0.25), new NoteOuttakeCommand(m_intakeSubsystem)), + new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, 1.5), + new ParallelDeadlineGroup(new WaitCommand(0.50), new NoteOuttakeCommand(m_intakeSubsystem)), new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, ShooterConstants.kShooterOffTime))); NamedCommands.registerCommand("Intake", @@ -217,6 +216,11 @@ private void configureBindings() { }).onTrue(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting, ShooterConstants.kShooterOnTime)) .onFalse(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, ShooterConstants.kShooterOffTime)); + new Trigger(() -> { + return m_operatorController.getXButtonPressed() == true; + }).onTrue(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Amp, 0.1)) + .onFalse(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off, 0.02)); + // Climber Up, Operator Controller Right Bumper + A Button new Trigger(() -> { return m_operatorController.getAButton() && m_operatorController.getRightBumper(); diff --git a/src/main/java/frc/robot/commands/NoteOuttakeCommand.java b/src/main/java/frc/robot/commands/NoteOuttakeCommand.java index 5338ea4..2cddff1 100644 --- a/src/main/java/frc/robot/commands/NoteOuttakeCommand.java +++ b/src/main/java/frc/robot/commands/NoteOuttakeCommand.java @@ -4,7 +4,6 @@ package frc.robot.commands; -import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.subsystems.IntakeSubsystem; diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java index 55c14ea..dc4cd49 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -42,6 +42,9 @@ public void setShootingSpeed(ShootSpeed speed) { m_topSpeed = ShooterConstants.kShooterSpeedTop; m_bottomSpeed = ShooterConstants.kShooterSpeedBottom; break; + case Amp: + m_topSpeed = 0.2; + m_bottomSpeed = 0.3; case Prep: m_topSpeed = ShooterConstants.kPrepShooterSpeed; m_bottomSpeed = ShooterConstants.kPrepShooterSpeed; @@ -70,6 +73,7 @@ public void periodic() { public static enum ShootSpeed { Shooting, Prep, + Amp, Off } }