Skip to content

Commit

Permalink
fixed
Browse files Browse the repository at this point in the history
  • Loading branch information
AdityaP241 committed Dec 26, 2024
1 parent 24445f1 commit 27e15d5
Show file tree
Hide file tree
Showing 4 changed files with 51 additions and 1 deletion.
2 changes: 1 addition & 1 deletion .idea/misc.xml

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

Original file line number Diff line number Diff line change
@@ -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()
}


}
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -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)

Expand Down Expand Up @@ -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)})
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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))

Expand Down

0 comments on commit 27e15d5

Please sign in to comment.