Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -12,4 +12,10 @@ public static class Shooter {
public static final String shooterMotorName = "shooterMotor";
public static final double defaultSpeed = 1;
}

public static class Intake {
public static final String intakeMotorName = "intakeMotor";
public static final String rampMotorName = "rampMotor";
public static final double defaultSpeed = 0.5;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,17 @@
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;

import org.firstinspires.ftc.teamcode.Constants;
import org.firstinspires.ftc.teamcode.commands.RunIntake;
import org.firstinspires.ftc.teamcode.commands.RunShooter;
import org.firstinspires.ftc.teamcode.commands.UserDrive;
import org.firstinspires.ftc.teamcode.subsystems.Drivetrain;
import org.firstinspires.ftc.teamcode.subsystems.Intake;
import org.firstinspires.ftc.teamcode.subsystems.Shooter;

@TeleOp(name = "PrimaryOpMode", group = "NormalOpModes")
public class PrimaryOpMode extends CommandOpMode {
private Shooter shooter;
private Intake intake;
private Drivetrain drivetrain;

private GamepadEx driverOp;
Expand All @@ -35,7 +38,11 @@ public void initialize() {
register(drivetrain);
shooter = new Shooter(hardwareMap, Constants.Shooter.shooterMotorName);
register(shooter);
intake = new Intake(hardwareMap, Constants.Intake.intakeMotorName, Constants.Intake.rampMotorName);
register(intake);
coOp.getGamepadButton(GamepadKeys.Button.A).whileHeld(
new RunShooter(shooter, Constants.Shooter.defaultSpeed));
coOp.getGamepadButton(GamepadKeys.Button.B).whileHeld(
new RunIntake(intake, Constants.Intake.defaultSpeed));
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
package org.firstinspires.ftc.teamcode.commands;

import com.arcrobotics.ftclib.command.CommandBase;

import org.firstinspires.ftc.teamcode.subsystems.Intake;

public class RunIntake extends CommandBase {
public final Intake subsystem;

public final double speed;

public RunIntake(Intake _subsystem, double _speed) {
subsystem = _subsystem;
addRequirements(subsystem);
speed = _speed;
}

@Override
public void initialize() {
subsystem.run(speed);
}

@Override
public void end(boolean interrupted) {
subsystem.stop();
}
}
15 changes: 14 additions & 1 deletion TeamCode/src/main/java/org/firstinspires/ftc/teamcode/readme.md
Original file line number Diff line number Diff line change
Expand Up @@ -42,4 +42,17 @@ Subsystem that runs launcher
### Commands

- RunShooter
- Runs shooter motors in raw mode with the specified power
- Runs shooter motors in raw mode with the specified power
- Controls
- A: Runs shooter

## Intake

Subsystem that runs launcher

### Commands

- RunIntake
- Runs intake motor and intake ramp motor
- Controls
- B: Runs Intake and Ramp
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
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 {
// intakeMotor is the one that runs the intake, rampMotor is the one on the ramp.
private final Motor intakeMotor, rampMotor;

public Intake(HardwareMap hardwareMap, String intakeMotorName, String rampMotorName) {
intakeMotor = new Motor(hardwareMap, intakeMotorName);
rampMotor = new Motor(hardwareMap, rampMotorName);

intakeMotor.setRunMode(Motor.RunMode.RawPower);
rampMotor.setRunMode(Motor.RunMode.RawPower);
}

public void run(double speed) {
double clampedSpeed = Math.max(-1.0, Math.min(1.0, speed));
intakeMotor.set(clampedSpeed);
rampMotor.set(clampedSpeed);
}

public void stop() {
intakeMotor.stopMotor();
rampMotor.stopMotor();
}
}
Loading