From 77e6ce4801be0b0b872af818fb633b76eee4a983 Mon Sep 17 00:00:00 2001 From: Jestin VanScoyoc <31118852+JediScoy@users.noreply.github.com> Date: Sat, 30 Mar 2024 22:07:05 -0400 Subject: [PATCH] with event marker --- src/main/deploy/pathplanner/autos/Start1.0-3 Quick.auto | 6 ++++++ src/main/java/frc/robot/RobotContainer.java | 6 ++---- src/main/java/frc/robot/commands/ShootFromStage.java | 3 +-- src/main/java/frc/robot/util/Constants.java | 4 ++-- 4 files changed, 11 insertions(+), 8 deletions(-) diff --git a/src/main/deploy/pathplanner/autos/Start1.0-3 Quick.auto b/src/main/deploy/pathplanner/autos/Start1.0-3 Quick.auto index a67ba7a..46a53e0 100644 --- a/src/main/deploy/pathplanner/autos/Start1.0-3 Quick.auto +++ b/src/main/deploy/pathplanner/autos/Start1.0-3 Quick.auto @@ -42,6 +42,12 @@ ] } }, + { + "type": "named", + "data": { + "name": "ShootFromStage" + } + }, { "type": "path", "data": { diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 07023a2..0d3a677 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -127,11 +127,9 @@ public RobotContainer() { /* Pathplanner Named Commands */ NamedCommands.registerCommand("ShootClose", new ShootClose(arm, index, intake, shooter)); - NamedCommands.registerCommand("ShootClose2", shootWhenReadyAuton); NamedCommands.registerCommand("ShootFromStage", shootFromStage); NamedCommands.registerCommand("Intake", new IntakeIndex(index, intake)); NamedCommands.registerCommand("AutoShootWhenReady", shootWhenReadyAuton); // Autonomous - NamedCommands.registerCommand("ShootWhenReady", shootWhenReadyAuton); // Autonomous NamedCommands.registerCommand("SetFlywheelToIdle", setShooterIdle); // Constants.ArmConstants.ARM_MID_POSE)); @@ -207,10 +205,10 @@ private void configureBindings() { // m_driverController.rightTrigger().whileTrue(setShooterVelocity); // TODO Testing "autonShootWhenReady" Remove later - // m_driverController.rightTrigger().whileTrue(autonShootWhenReady); + m_driverController.leftTrigger().whileTrue(shootWhenReadyAuton); // TODO Test MotionMagicVelocityVoltage" only, then remove - m_driverController.leftTrigger().whileTrue(new InstantCommand(() -> shooter2.setFlywheelVelocityMM(shooter2.FLYWHEEL_VELOCITY))); + // m_driverController.leftTrigger().whileTrue(new InstantCommand(() -> shooter2.setFlywheelVelocityMM(shooter2.FLYWHEEL_VELOCITY))); // TODO Remove comment out after testing the MotionMagic Velocity Voltage // m_driverController.leftTrigger().whileTrue(new SetIndex(index, -0.75)); diff --git a/src/main/java/frc/robot/commands/ShootFromStage.java b/src/main/java/frc/robot/commands/ShootFromStage.java index 281eb1e..8502125 100644 --- a/src/main/java/frc/robot/commands/ShootFromStage.java +++ b/src/main/java/frc/robot/commands/ShootFromStage.java @@ -14,9 +14,8 @@ public ShootFromStage(ArmSubsystem arm, IndexSubsystem index, IntakeSubsystem in addCommands( // Set the arm to the middle position for shooting from the closest Stage leg new SetArmPosition(arm, Constants.ArmConstants.ARM_MID_POSE), - // Check target velocity and index the game piece forward - new ShootWhenReady(shooter2, index, notesensor), + new ShootWhenReady(shooter2, index, notesensor).withTimeout(.75), // Set arm back to home position new SetArmPosition(arm, Constants.ArmConstants.ARM_HOME_POSE) diff --git a/src/main/java/frc/robot/util/Constants.java b/src/main/java/frc/robot/util/Constants.java index bad80bd..fa66359 100644 --- a/src/main/java/frc/robot/util/Constants.java +++ b/src/main/java/frc/robot/util/Constants.java @@ -112,8 +112,8 @@ public static class IndexConstants { } public static class IntakeConstants { - public static final double INTAKE_POWER = 0.75; // 0.75 - public static final double INTAKE_POWER_REV = -0.75; + public static final double INTAKE_POWER = -0.75; // 0.75 + public static final double INTAKE_POWER_REV = 0.75; }