From 27e15d525da86872b29455de67353d8262c8b3df Mon Sep 17 00:00:00 2001 From: AdityaP241 Date: Thu, 26 Dec 2024 14:59:22 -0500 Subject: [PATCH] fixed --- .idea/misc.xml | 2 +- .../commands/intake/SlowIntakeBeltCommand.kt | 30 +++++++++++++++++++ .../ftc/teamcode/opModes/teleOp/MainTeleOp.kt | 16 ++++++++++ .../subsystems/intake/IntakeSubsystem.kt | 4 +++ 4 files changed, 51 insertions(+), 1 deletion(-) create mode 100644 TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/SlowIntakeBeltCommand.kt diff --git a/.idea/misc.xml b/.idea/misc.xml index 2205f44..e15adbe 100644 --- a/.idea/misc.xml +++ b/.idea/misc.xml @@ -8,7 +8,7 @@ - + diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/SlowIntakeBeltCommand.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/SlowIntakeBeltCommand.kt new file mode 100644 index 0000000..b8de4ae --- /dev/null +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/commands/intake/SlowIntakeBeltCommand.kt @@ -0,0 +1,30 @@ +package org.firstinspires.ftc.teamcode.commands.intake + +import com.arcrobotics.ftclib.command.CommandBase +import org.firstinspires.ftc.teamcode.subsystems.intake.IntakeSubsystem + + +class SlowIntakeBeltCommand( + private val subsystem: IntakeSubsystem, + private val turn: Boolean, + +) : CommandBase() { + + override fun initialize() { + addRequirements(subsystem) + } + + override fun execute() { + if (turn) { + subsystem.wristUpSlow() + } else { + subsystem.wristDownSlow() + } + } + + override fun end(interrupted: Boolean) { + subsystem.wristStop() + } + + + } diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/teleOp/MainTeleOp.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/teleOp/MainTeleOp.kt index 3e8c121..1de5871 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/teleOp/MainTeleOp.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/opModes/teleOp/MainTeleOp.kt @@ -19,6 +19,7 @@ import org.firstinspires.ftc.teamcode.commands.elevator.SpinDownCommand import org.firstinspires.ftc.teamcode.commands.elevator.SpinUpCommand import org.firstinspires.ftc.teamcode.commands.intake.IntakeBeltCommand import org.firstinspires.ftc.teamcode.commands.intake.IntakeCommand +import org.firstinspires.ftc.teamcode.commands.intake.SlowIntakeBeltCommand import org.firstinspires.ftc.teamcode.commands.intake.ThrowbackCommand import org.firstinspires.ftc.teamcode.subsystems.arm.ArmSubsystem import org.firstinspires.ftc.teamcode.subsystems.drive.DriveSubsystem @@ -38,6 +39,9 @@ class MainTeleOp : CommandOpMode() { private lateinit var outtakeCommand: Command private lateinit var intakeBeltCommand: Command private lateinit var outtakeBeltCommand: Command + private lateinit var slowIntakeBeltCommand: Command + private lateinit var slowOuttakeBeltCommand: Command + private lateinit var driver: GamepadEx private var driverMode = DRIVER_MODE.SPEED @@ -104,6 +108,8 @@ class MainTeleOp : CommandOpMode() { intakeBeltCommand = IntakeBeltCommand(Math.toRadians(-60.0), IntakeSubsystem) // outtakeBeltCommand = IntakeBeltCommand(Math.toRadians(90.0), IntakeSubsystem) outtakeBeltCommand = ThrowbackCommand(IntakeSubsystem) + slowIntakeBeltCommand = SlowIntakeBeltCommand(IntakeSubsystem, true) + slowOuttakeBeltCommand = SlowIntakeBeltCommand(IntakeSubsystem, false) driveCommand = DriveCommand(DriveSubsystem, driver::getLeftX, driver::getLeftY, driver::getRightX, 0.0) @@ -206,6 +212,16 @@ class MainTeleOp : CommandOpMode() { outtakeBeltCommand, ) + driver.getGamepadButton(GamepadKeys.Button.LEFT_BUMPER).whileHeld( + slowOuttakeBeltCommand +// intakeBeltCommand + ) + + driver.getGamepadButton(GamepadKeys.Button.RIGHT_BUMPER).whileHeld( + slowIntakeBeltCommand +// outtakeBeltCommand + ) + driver.getGamepadButton(GamepadKeys.Button.B).whenPressed( InstantCommand({ operatorMode = operatorMode.toggle(operatorMode)}) ) diff --git a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeSubsystem.kt b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeSubsystem.kt index ab78b03..2a67320 100644 --- a/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeSubsystem.kt +++ b/TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/subsystems/intake/IntakeSubsystem.kt @@ -92,9 +92,13 @@ object IntakeSubsystem : SubsystemBase() { fun wristUp() = if (!isPressed) wrist.set(1.0) else wrist.stop() + fun wristUpSlow() = if (!isPressed) wrist.set(0.2) else wrist.stop() fun wristDown() = wrist.set(-1.0) + fun wristDownSlow() = if (!isPressed) wrist.set(-0.2) else wrist.stop() + + fun wristStop() = wrist.set(kCos * cos(position))