From cc4a38eb5ef1abf6792c5ccfd2081d6c419e4230 Mon Sep 17 00:00:00 2001 From: Nick Date: Thu, 23 Oct 2025 18:37:44 -0500 Subject: [PATCH 1/2] Added Intake Subsystem --- .../ftc/teamcode/PrimaryOpMode.java | 6 ++++ .../ftc/teamcode/commands/RunIntake.java | 34 +++++++++++++++++++ .../ftc/teamcode/subsystems/Intake.java | 23 +++++++++++++ 3 files changed, 63 insertions(+) create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/commands/RunIntake.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/Intake.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PrimaryOpMode.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PrimaryOpMode.java index 33347058d842..e2ce412f609a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PrimaryOpMode.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PrimaryOpMode.java @@ -8,7 +8,9 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.hardware.HardwareMap; +import org.firstinspires.ftc.teamcode.commands.RunIntake; import org.firstinspires.ftc.teamcode.commands.RunShooter; +import org.firstinspires.ftc.teamcode.subsystems.Intake; import org.firstinspires.ftc.teamcode.subsystems.Shooter; @TeleOp(name = "PrimaryOpMode", group= "NormalOpModes") @@ -16,6 +18,7 @@ public class PrimaryOpMode extends OpMode { private Motor fL, fR, bL, bR; private MecanumDrive drive; private Shooter shooter; + private Intake intake; private GamepadEx driverOp; private GamepadEx coOp; @@ -33,7 +36,10 @@ public void init() { shooter = new Shooter(hardwareMap, "shooterMotor"); + intake = new Intake(hardwareMap, "intakeMotor"); + coOp.getGamepadButton(GamepadKeys.Button.A).whileHeld(new RunShooter(shooter, 1)); + coOp.getGamepadButton(GamepadKeys.Button.B).whileHeld(new RunIntake(intake, 0.5)); } @Override diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/commands/RunIntake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/commands/RunIntake.java new file mode 100644 index 000000000000..bfc39e9fbd0b --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/commands/RunIntake.java @@ -0,0 +1,34 @@ +package org.firstinspires.ftc.teamcode.commands; + +import com.arcrobotics.ftclib.command.CommandBase; +import com.qualcomm.robotcore.hardware.HardwareMap; + +import org.firstinspires.ftc.teamcode.subsystems.Intake; + +public class RunIntake extends CommandBase { + + private Intake subsystem; + + private double speed; + + public RunIntake(Intake _subsystem, double _speed) { + subsystem = _subsystem; + addRequirements(subsystem); + speed = _speed; + } + + @Override + public void initialize() { + subsystem.run(speed); + } + + @Override + public boolean isFinished() { + return false; + } + + @Override + public void end(boolean interrupted) { + subsystem.stop(); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/Intake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/Intake.java new file mode 100644 index 000000000000..c02fc5ce1144 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/Intake.java @@ -0,0 +1,23 @@ +package org.firstinspires.ftc.teamcode.subsystems; + +import com.arcrobotics.ftclib.command.SubsystemBase; +import com.arcrobotics.ftclib.hardware.motors.Motor; +import com.qualcomm.robotcore.hardware.HardwareMap; + +public class Intake extends SubsystemBase { + private Motor intakeMotor; + + public Intake(HardwareMap map, String motorName) { + intakeMotor = new Motor(map, motorName); + intakeMotor.setRunMode(Motor.RunMode.RawPower); + } + + public void run(double speed) { + double clampedSpeed = Math.max(-1.0, Math.min(1.0, speed)); + intakeMotor.set(clampedSpeed); + } + + public void stop() { + intakeMotor.stopMotor(); + } +} From 4764a73cc5b582d200200f20cc5636d20345f135 Mon Sep 17 00:00:00 2001 From: Nicholas Garnsworthy Date: Sat, 25 Oct 2025 10:25:03 -0500 Subject: [PATCH 2/2] Remove isFinished method from RunIntake Removed isFinished method from RunIntake command as it is default --- .../org/firstinspires/ftc/teamcode/commands/RunIntake.java | 5 ----- 1 file changed, 5 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/commands/RunIntake.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/commands/RunIntake.java index bfc39e9fbd0b..ac19f45ca52c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/commands/RunIntake.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/commands/RunIntake.java @@ -22,11 +22,6 @@ public void initialize() { subsystem.run(speed); } - @Override - public boolean isFinished() { - return false; - } - @Override public void end(boolean interrupted) { subsystem.stop();