From dca0fd9080751f3926c53a198e4c0023090394d7 Mon Sep 17 00:00:00 2001 From: willitcode <91231142+willitcode@users.noreply.github.com> Date: Mon, 25 Mar 2024 16:43:49 -0500 Subject: [PATCH 1/5] used the correct method to get maximum drivetrain speed --- src/main/java/frc/robot/subsystems/Drive.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/Drive.java b/src/main/java/frc/robot/subsystems/Drive.java index 09566a09..0331be44 100644 --- a/src/main/java/frc/robot/subsystems/Drive.java +++ b/src/main/java/frc/robot/subsystems/Drive.java @@ -168,7 +168,7 @@ public ChassisSpeeds getTargetSpeeds( headingX, headingY, drive.getPose().getRotation().getRadians(), - Constants.Drive.MAX_SPEED); + getMaximumSpeed()); } /** From fb74c147093fb5b13c719306237d0d5224d29112 Mon Sep 17 00:00:00 2001 From: willitcode <91231142+willitcode@users.noreply.github.com> Date: Tue, 26 Mar 2024 07:44:16 -0500 Subject: [PATCH 2/5] use correct method to get max speed for paths --- src/main/java/frc/robot/subsystems/Drive.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/Drive.java b/src/main/java/frc/robot/subsystems/Drive.java index 0331be44..f5810117 100644 --- a/src/main/java/frc/robot/subsystems/Drive.java +++ b/src/main/java/frc/robot/subsystems/Drive.java @@ -70,7 +70,7 @@ public Drive() { /* HolonomicPathFollowerConfig, this should likely live in your Constants class */ Constants.Drive.TRANSLATION_DRIVE_PID, /* Translation PID constants */ Constants.Drive.ROTATION_DRIVE_PID, /* Rotation PID constants */ - Constants.Drive.MAX_SPEED, /* Max module speed, in m/s */ + getMaximumSpeed(), /* Max module speed, in m/s */ Constants.Drive .DISTANCE_ROBOT_CENTER_TO_SWERVE_MODULE, /* Drive base radius in meters. Distance from robot center to furthest module. */ new ReplanningConfig() /* Default path replanning config. See the API for the options here */), From bef9a92611b869c8a6976ab8c35fac1f485bfd7d Mon Sep 17 00:00:00 2001 From: willitcode <91231142+willitcode@users.noreply.github.com> Date: Wed, 27 Mar 2024 17:47:15 -0500 Subject: [PATCH 3/5] heading snapping by default --- 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 dc023519..1d27c75f 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -285,7 +285,7 @@ public RobotContainer() { startIntakeCamera.schedule(); - drive.setDefaultCommand(driveFieldOriented); + drive.setDefaultCommand(driveFieldOrientedHeadingSnapping); } private void configureAuto() { From 3f245ec9617210e56cd1dbfbb38c2ed6bc2e81d1 Mon Sep 17 00:00:00 2001 From: willitcode <91231142+willitcode@users.noreply.github.com> Date: Wed, 27 Mar 2024 17:51:00 -0500 Subject: [PATCH 4/5] fix note is in intake --- src/main/java/frc/robot/subsystems/Intake.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/Intake.java b/src/main/java/frc/robot/subsystems/Intake.java index 4d6433a7..db8ffbc8 100644 --- a/src/main/java/frc/robot/subsystems/Intake.java +++ b/src/main/java/frc/robot/subsystems/Intake.java @@ -51,7 +51,7 @@ public Intake() { intakeLower.burnFlash(); intakeUpper.burnFlash(); - Shuffleboard.getTab("Driver").add("Note in intake", false).getEntry(); + noteIsInIntake = Shuffleboard.getTab("Driver").add("Note in intake", false).getEntry(); } /** Runs the intake motors. */ From 164700eef643097f6871f7efe09400b3297b652e Mon Sep 17 00:00:00 2001 From: willitcode <91231142+willitcode@users.noreply.github.com> Date: Wed, 27 Mar 2024 17:51:26 -0500 Subject: [PATCH 5/5] comment out ll feed since it doesn't work --- src/main/java/frc/robot/subsystems/Limelight.java | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/Limelight.java b/src/main/java/frc/robot/subsystems/Limelight.java index 60180af6..07baff9c 100644 --- a/src/main/java/frc/robot/subsystems/Limelight.java +++ b/src/main/java/frc/robot/subsystems/Limelight.java @@ -21,7 +21,6 @@ import edu.wpi.first.networktables.DoubleTopic; import edu.wpi.first.networktables.GenericEntry; import edu.wpi.first.networktables.NetworkTableInstance; -import edu.wpi.first.wpilibj.shuffleboard.SendableCameraWrapper; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -65,9 +64,9 @@ public Limelight(String name) { .getDoubleArrayTopic(fmtPath("botpose")) .subscribe(defaultBotpos); - Shuffleboard.getTab("Driver") - .add(SendableCameraWrapper.wrap(name, "http://" + name + ".local:5800/stream.mjpg")) - .withSize(4, 4); + /* Shuffleboard.getTab("Driver") + .add(SendableCameraWrapper.wrap(name, "http://" + name + ".local:5800/stream.mjpg")) + .withSize(4, 4); */ /* TODO: CONSTANTS */ limelightHasTarget = Shuffleboard.getTab("Driver").add(name + "has target", false).getEntry();