Skip to content

Commit

Permalink
pull master (#13)
Browse files Browse the repository at this point in the history
* update to use .runEnd instead of run

this should fix a lot of the auto issues.

* make the green blink a part of the parallel race group

* Update path and autos

* [Dependency] bump wpilib to 2024.3.2

* rename "SmartShootCommand" to "ShootToSpeakerCommand"

This represents what it is about a lot better in my opinion.

* Fix tests by not shutting down the hal in teardown

* close the subsystem after super in basicIntakeTest

* add more comments for explanation

* don't shutdown HAL in DriveSubsystem test base
  • Loading branch information
kytpbs authored Jun 19, 2024
1 parent 7e0f70b commit d62e410
Show file tree
Hide file tree
Showing 7 changed files with 22 additions and 23 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
plugins {
id "java"
id "jacoco"
id "edu.wpi.first.GradleRIO" version "2024.2.1"
id "edu.wpi.first.GradleRIO" version "2024.3.2"
id "com.diffplug.spotless" version "6.23.3"
}

Expand Down
14 changes: 7 additions & 7 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@
import frc.robot.commands.BasicIntakeCommand;
import frc.robot.commands.DefaultDriveCommand;
import frc.robot.commands.ShootToAmpCommand;
import frc.robot.commands.ShootToSpeakerCommand;
import frc.robot.commands.SmartIntakeCommand;
import frc.robot.commands.SmartShootCommand;
import frc.robot.commands.led_commands.LEDIdleCommand;
import frc.robot.simulationSystems.PhotonSim;
import frc.robot.subsystems.ArmSubsystem;
Expand Down Expand Up @@ -58,7 +58,7 @@ public RobotContainer() {
autoChooser = AutoBuilder.buildAutoChooser();
autoChooser.addOption(
"Shoot To Shooter",
new SmartShootCommand(shooterSubsystem, intakeSubsystem, armSubsystem, driveSubsystem));
new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem, armSubsystem, driveSubsystem));
PhotonCameraSystem.getAprilTagWithID(0); // Load the class before enable.
SmartDashboard.putData("Auto Chooser", autoChooser);
if (RobotBase.isSimulation()) {
Expand Down Expand Up @@ -108,7 +108,7 @@ private void setupNamedCommands() {
NamedCommands.registerCommand("Intake", new BasicIntakeCommand(intakeSubsystem));
NamedCommands.registerCommand(
"Shoot To Speaker",
new SmartShootCommand(shooterSubsystem, intakeSubsystem, armSubsystem, driveSubsystem));
new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem, armSubsystem, driveSubsystem));
NamedCommands.registerCommand(
"Shoot To Amp", new ShootToAmpCommand(shooterSubsystem, intakeSubsystem, armSubsystem));
}
Expand Down Expand Up @@ -142,7 +142,7 @@ private void configureJoystickBindings() {

new JoystickButton(controller, Button.kY.value) // Shoot, smart (Fully Shoot)
.whileTrue(
new SmartShootCommand(
new ShootToSpeakerCommand(
shooterSubsystem,
intakeSubsystem,
armSubsystem,
Expand Down Expand Up @@ -171,7 +171,7 @@ private void configureJoystickBindings() {
.whileTrue(new RunCommand(() -> shooterSubsystem.setShooterSpeed(-1), shooterSubsystem));

new JoystickButton(controller, Button.kLeftBumper.value)
.whileTrue(new SmartShootCommand(shooterSubsystem, intakeSubsystem));
.whileTrue(new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem));

new Trigger(() -> controller.getPOV() == 0)
// Move arm to 0.5, and set it there until the button is released.
Expand All @@ -189,10 +189,10 @@ private void configureMidiBindings() {
.onTrue(armSubsystem.runOnce(armSubsystem::resetEncoder).ignoringDisable(true));

new JoystickButton(midiController, 3)
.whileTrue(new SmartShootCommand(shooterSubsystem, intakeSubsystem));
.whileTrue(new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem));

new JoystickButton(midiController, 4)
.whileTrue(new SmartShootCommand(shooterSubsystem, intakeSubsystem));
.whileTrue(new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem));

new JoystickButton(midiController, 16)
.onTrue(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,10 @@
import frc.robot.subsystems.ShooterSubsystem;
import java.util.function.DoubleSupplier;

public class SmartShootCommand extends ParallelRaceGroup {
public class ShootToSpeakerCommand extends ParallelRaceGroup {
private static final double waitTime = 2.5;

public SmartShootCommand(ShooterSubsystem shooterSubsystem, IntakeSubsystem intakeSubsystem) {
public ShootToSpeakerCommand(ShooterSubsystem shooterSubsystem, IntakeSubsystem intakeSubsystem) {
super(
new SequentialCommandGroup(
new BasicRunShooterCommand(shooterSubsystem, waitTime),
Expand All @@ -20,18 +20,18 @@ public SmartShootCommand(ShooterSubsystem shooterSubsystem, IntakeSubsystem inta
new LoadToShooterCommand(intakeSubsystem))));
}

public SmartShootCommand(
public ShootToSpeakerCommand(
ShooterSubsystem shooterSubsystem,
IntakeSubsystem intakeSubsystem,
ArmSubsystem armSubsystem,
DriveSubsystem driveSubsystem) {
super(
// Constantly move the arm until all the other commands finish.
new MoveArmToShooterCommand(armSubsystem, driveSubsystem),
new SmartShootCommand(shooterSubsystem, intakeSubsystem));
new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem));
}

public SmartShootCommand(
public ShootToSpeakerCommand(
ShooterSubsystem shooterSubsystem,
IntakeSubsystem intakeSubsystem,
ArmSubsystem armSubsystem,
Expand All @@ -43,6 +43,6 @@ public SmartShootCommand(
new MoveArmToShooterCommand(armSubsystem, driveSubsystem),
new DriveFacingShooter(driveSubsystem, xSpeed, ySpeed),
// The finishing command will be this one:
new SmartShootCommand(shooterSubsystem, intakeSubsystem));
new ShootToSpeakerCommand(shooterSubsystem, intakeSubsystem));
}
}
13 changes: 7 additions & 6 deletions src/main/java/frc/robot/subsystems/DriveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -220,7 +220,8 @@ private void updatePoseWithVision() {
}

private Optional<Pose3d> getTagPose(int id) {
var tag = PhotonCameraSystem.getFieldLayout().getTagPose(id);
var tagField = PhotonCameraSystem.getFieldLayout();
var tag = tagField.getTagPose(id);

if (tag.isEmpty()) {
DriverStation.reportError("Field Layout Couldn't be loaded", false);
Expand Down Expand Up @@ -251,13 +252,13 @@ public Rotation2d getRotationDifferenceToShooter() {
if (tag.isEmpty()) return new Rotation2d();

return tag.get()
.getTranslation()
.getTranslation() // Get the translation of the tag
.toTranslation2d()
.minus(getPose().getTranslation())
.minus(getPose().getTranslation()) // Subtract the robot's translation
.getAngle()
.minus(getRotation2d())
.rotateBy(Rotation2d.fromDegrees(180))
.times(-1);
.minus(getRotation2d()) // Subtract the robot's rotation
.rotateBy(Rotation2d.fromDegrees(180)) // Rotate by 180 so the back is 0
.times(-1); // Invert the angle, so the back is a positive angle that can be inverted.
}

public Pose2d getPose() {
Expand Down
2 changes: 1 addition & 1 deletion src/test/java/command_tests/arm_tests/BasicIntakeTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@ public void setUp() {

@AfterEach
public void tearDown() {
intakeSubsystem.close();
super.tearDown();
intakeSubsystem.close();
}

@Test
Expand Down
1 change: 0 additions & 1 deletion src/test/java/command_tests/utils/CommandTestBase.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,5 @@ protected void tearDown() {
commandScheduler.cancelAll();
commandScheduler.unregisterAllSubsystems(); // ! breaks all test tests if not done
commandScheduler.close();
HAL.shutdown();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,5 @@ public void tearDown() {
commandScheduler.cancelAll();
commandScheduler.unregisterAllSubsystems(); // ! breaks all test tests if not done
commandScheduler.close();
HAL.shutdown();
}
}

0 comments on commit d62e410

Please sign in to comment.