Skip to content
Merged
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
@@ -0,0 +1,15 @@
package org.firstinspires.ftc.teamcode;

public final class Constants {
public static class Drivetrain {
public static final String flMotorName = "frontLeftDrive";
public static final String frMotorName = "frontRightDrive";
public static final String blMotorName = "backLeftDrive";
public static final String brMotorName = "backRightDrive";
}

public static class Shooter {
public static final String shooterMotorName = "shooterMotor";
public static final double defaultSpeed = 1;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
package org.firstinspires.ftc.teamcode.OpModes;

import com.arcrobotics.ftclib.command.CommandOpMode;
import com.arcrobotics.ftclib.gamepad.GamepadEx;
import com.arcrobotics.ftclib.gamepad.GamepadKeys;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;

import org.firstinspires.ftc.teamcode.Constants;
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.Shooter;

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

private GamepadEx driverOp;
private GamepadEx coOp;

@Override
public void initialize() {
driverOp = new GamepadEx(gamepad1);
coOp = new GamepadEx(gamepad2);

drivetrain = new Drivetrain(
hardwareMap,
Constants.Drivetrain.flMotorName,
Constants.Drivetrain.frMotorName,
Constants.Drivetrain.blMotorName,
Constants.Drivetrain.brMotorName
);
drivetrain.setDefaultCommand(new UserDrive(drivetrain, driverOp));
register(drivetrain);

shooter = new Shooter(hardwareMap, Constants.Shooter.shooterMotorName);
register(shooter);
coOp.getGamepadButton(GamepadKeys.Button.A).whileHeld(
new RunShooter(shooter, Constants.Shooter.defaultSpeed));
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
package org.firstinspires.ftc.teamcode.OpModes;

import com.arcrobotics.ftclib.command.CommandOpMode;
import com.arcrobotics.ftclib.gamepad.GamepadEx;
import com.arcrobotics.ftclib.gamepad.GamepadKeys;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;

import org.firstinspires.ftc.teamcode.Constants;
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.Shooter;

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

private GamepadEx driverOp;
private GamepadEx coOp;

@Override
public void initialize() {
driverOp = new GamepadEx(gamepad1);
coOp = new GamepadEx(gamepad2);

drivetrain = new Drivetrain(
hardwareMap,
Constants.Drivetrain.flMotorName,
Constants.Drivetrain.frMotorName,
Constants.Drivetrain.blMotorName,
Constants.Drivetrain.brMotorName
);
drivetrain.setDefaultCommand(new UserDrive(drivetrain, driverOp));
register(drivetrain);
shooter = new Shooter(hardwareMap, Constants.Shooter.shooterMotorName);
register(shooter);
coOp.getGamepadButton(GamepadKeys.Button.A).whileHeld(
new RunShooter(shooter, Constants.Shooter.defaultSpeed));
}
}
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
package org.firstinspires.ftc.teamcode;
package org.firstinspires.ftc.teamcode.OpModes.learning;

import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;

@TeleOp(name = "Brodys OpMode", group = "Example OpMode")
@TeleOp(name = "Brody's OpMode", group = "Example OpMode")
@Disabled
public class BrodysFIRSTOpMode extends OpMode {
private DcMotor frontLeftMotor;
private DcMotor frontRightMotor;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
package org.firstinspires.ftc.teamcode;
package org.firstinspires.ftc.teamcode.OpModes.learning;

import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;

@TeleOp(name="Nick's OpMode", group="Example OpMode")
@TeleOp(name = "Nick's OpMode", group = "Example OpMode")
@Disabled
public class NicksFIRSTJavaOpMode extends OpMode {
private DcMotor frontLeftMotor;
private DcMotor frontRightMotor;
Expand Down Expand Up @@ -48,7 +50,7 @@ public void loop() {
}

@Override
public void stop() {
public void stop() {
telemetry.addData("Status", "Stopped");
telemetry.update();
}
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -5,25 +5,20 @@
import org.firstinspires.ftc.teamcode.subsystems.Shooter;

public class RunShooter extends CommandBase {
private Shooter subsystem;
private double speed;
private final Shooter subsystem;
private final double speed;

public RunShooter(Shooter _subsystem, double _speed) {
subsystem = _subsystem;
addRequirements(subsystem);
speed = _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();
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
package org.firstinspires.ftc.teamcode.commands;

import com.arcrobotics.ftclib.command.CommandBase;
import com.arcrobotics.ftclib.gamepad.GamepadEx;

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

public class UserDrive extends CommandBase {
private final Drivetrain drivetrain;
private final GamepadEx gamepad;

public UserDrive(Drivetrain drivetrain, GamepadEx gamepad) {
this.drivetrain = drivetrain;
this.gamepad = gamepad;
addRequirements(drivetrain);
}

@Override
public void execute() {
drivetrain.move(
gamepad.getLeftX(),
gamepad.getLeftY(),
gamepad.getRightX()
);
}

@Override
public void end(boolean interrupted) {
drivetrain.stop();
}
}
Loading
Loading