From e57531de8374b686cc22e5252be02e069465a71b Mon Sep 17 00:00:00 2001 From: blueberry Date: Fri, 9 Feb 2024 16:23:09 -0800 Subject: [PATCH] added commands for other autos --- .../robot2024/auto/routines/Experimental1PieceTaxi.kt | 5 +---- .../robot2024/auto/routines/Experimental3PieceMid.kt | 11 ++++++----- .../robot2024/auto/routines/ExperimentalTaxi.kt | 7 +------ 3 files changed, 8 insertions(+), 15 deletions(-) diff --git a/src/main/kotlin/frc/team449/robot2024/auto/routines/Experimental1PieceTaxi.kt b/src/main/kotlin/frc/team449/robot2024/auto/routines/Experimental1PieceTaxi.kt index c16d4f8..9b9a898 100644 --- a/src/main/kotlin/frc/team449/robot2024/auto/routines/Experimental1PieceTaxi.kt +++ b/src/main/kotlin/frc/team449/robot2024/auto/routines/Experimental1PieceTaxi.kt @@ -1,6 +1,5 @@ package frc.team449.robot2024.auto.routines -import edu.wpi.first.wpilibj2.command.WaitCommand import frc.team449.control.auto.ChoreoRoutine import frc.team449.control.auto.ChoreoRoutineStructure import frc.team449.control.auto.ChoreoTrajectory @@ -17,9 +16,7 @@ class Experimental1PieceTaxi( drive = robot.drive, parallelEventMap = hashMapOf(), stopEventMap = hashMapOf( - 0 to WaitCommand(1.5), - 1 to WaitCommand(1.5), - 2 to WaitCommand(1.5) + 0 to AutoUtil.autoShoot(robot) ), debug = true ) diff --git a/src/main/kotlin/frc/team449/robot2024/auto/routines/Experimental3PieceMid.kt b/src/main/kotlin/frc/team449/robot2024/auto/routines/Experimental3PieceMid.kt index 6ef3818..8f12019 100644 --- a/src/main/kotlin/frc/team449/robot2024/auto/routines/Experimental3PieceMid.kt +++ b/src/main/kotlin/frc/team449/robot2024/auto/routines/Experimental3PieceMid.kt @@ -1,6 +1,5 @@ package frc.team449.robot2024.auto.routines -import edu.wpi.first.wpilibj2.command.WaitCommand import frc.team449.control.auto.ChoreoRoutine import frc.team449.control.auto.ChoreoRoutineStructure import frc.team449.control.auto.ChoreoTrajectory @@ -15,11 +14,13 @@ class Experimental3PieceMid( override val routine = ChoreoRoutine( drive = robot.drive, - parallelEventMap = hashMapOf(), + parallelEventMap = hashMapOf( + 0 to AutoUtil.autoIntake(robot) + ), stopEventMap = hashMapOf( - 0 to WaitCommand(1.5), - 1 to WaitCommand(1.5), - 2 to WaitCommand(1.5) + 0 to AutoUtil.autoShoot(robot), + 1 to AutoUtil.autoShoot(robot), + 2 to AutoUtil.autoShoot(robot) ), debug = true ) diff --git a/src/main/kotlin/frc/team449/robot2024/auto/routines/ExperimentalTaxi.kt b/src/main/kotlin/frc/team449/robot2024/auto/routines/ExperimentalTaxi.kt index 1718b14..32a2bf0 100644 --- a/src/main/kotlin/frc/team449/robot2024/auto/routines/ExperimentalTaxi.kt +++ b/src/main/kotlin/frc/team449/robot2024/auto/routines/ExperimentalTaxi.kt @@ -1,6 +1,5 @@ package frc.team449.robot2024.auto.routines -import edu.wpi.first.wpilibj2.command.WaitCommand import frc.team449.control.auto.ChoreoRoutine import frc.team449.control.auto.ChoreoRoutineStructure import frc.team449.control.auto.ChoreoTrajectory @@ -16,11 +15,7 @@ class ExperimentalTaxi( ChoreoRoutine( drive = robot.drive, parallelEventMap = hashMapOf(), - stopEventMap = hashMapOf( - 0 to WaitCommand(1.5), - 1 to WaitCommand(1.5), - 2 to WaitCommand(1.5) - ), + stopEventMap = hashMapOf(), debug = true )