Skip to content

Commit 91a47a2

Browse files
committed
Re-Re-Re-added Intake controls with new formatting with
the correct base branch and correct motor controls. Updated Readme.md
1 parent 9f93c24 commit 91a47a2

File tree

7 files changed

+82
-6
lines changed

7 files changed

+82
-6
lines changed

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Constants.java

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,12 @@ public static class Drivetrain {
1010

1111
public static class Shooter {
1212
public static final String shooterMotorName = "shooterMotor";
13+
public static final String rampMotorName = "rampMotor";
1314
public static final double defaultSpeed = 1;
1415
}
16+
17+
public static class Intake {
18+
public static final String intakeMotorName = "intakeMotor";
19+
public static final double defaultSpeed = 0.5;
20+
}
1521
}

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/OpModes/BackupOpMode.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ public void initialize() {
3434
drivetrain.setDefaultCommand(new UserDrive(drivetrain, driverOp));
3535
register(drivetrain);
3636

37-
shooter = new Shooter(hardwareMap, Constants.Shooter.shooterMotorName);
37+
shooter = new Shooter(hardwareMap, Constants.Shooter.shooterMotorName, Constants.Shooter.rampMotorName);
3838
register(shooter);
3939
coOp.getGamepadButton(GamepadKeys.Button.A).whileHeld(
4040
new RunShooter(shooter, Constants.Shooter.defaultSpeed));

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/OpModes/PrimaryOpMode.java

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,14 +6,17 @@
66
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
77

88
import org.firstinspires.ftc.teamcode.Constants;
9+
import org.firstinspires.ftc.teamcode.commands.RunIntake;
910
import org.firstinspires.ftc.teamcode.commands.RunShooter;
1011
import org.firstinspires.ftc.teamcode.commands.UserDrive;
1112
import org.firstinspires.ftc.teamcode.subsystems.Drivetrain;
13+
import org.firstinspires.ftc.teamcode.subsystems.Intake;
1214
import org.firstinspires.ftc.teamcode.subsystems.Shooter;
1315

1416
@TeleOp(name = "PrimaryOpMode", group = "NormalOpModes")
1517
public class PrimaryOpMode extends CommandOpMode {
1618
private Shooter shooter;
19+
private Intake intake;
1720
private Drivetrain drivetrain;
1821

1922
private GamepadEx driverOp;
@@ -33,9 +36,13 @@ public void initialize() {
3336
);
3437
drivetrain.setDefaultCommand(new UserDrive(drivetrain, driverOp));
3538
register(drivetrain);
36-
shooter = new Shooter(hardwareMap, Constants.Shooter.shooterMotorName);
39+
shooter = new Shooter(hardwareMap, Constants.Shooter.shooterMotorName, Constants.Shooter.rampMotorName);
3740
register(shooter);
41+
intake = new Intake(hardwareMap, Constants.Intake.intakeMotorName);
42+
register(intake);
3843
coOp.getGamepadButton(GamepadKeys.Button.A).whileHeld(
3944
new RunShooter(shooter, Constants.Shooter.defaultSpeed));
45+
coOp.getGamepadButton(GamepadKeys.Button.B).whileHeld(
46+
new RunIntake(intake, Constants.Intake.defaultSpeed));
4047
}
4148
}
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
package org.firstinspires.ftc.teamcode.commands;
2+
3+
import com.arcrobotics.ftclib.command.CommandBase;
4+
5+
import org.firstinspires.ftc.teamcode.subsystems.Intake;
6+
7+
public class RunIntake extends CommandBase {
8+
private final Intake subsystem;
9+
10+
private final double speed;
11+
12+
public RunIntake(Intake _subsystem, double _speed) {
13+
subsystem = _subsystem;
14+
addRequirements(subsystem);
15+
speed = _speed;
16+
}
17+
18+
@Override
19+
public void initialize() {
20+
subsystem.run(speed);
21+
}
22+
23+
@Override
24+
public void end(boolean interrupted) {
25+
subsystem.stop();
26+
}
27+
}

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/readme.md

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,4 +42,13 @@ Subsystem that runs launcher
4242
### Commands
4343

4444
- RunShooter
45-
- Runs shooter motors in raw mode with the specified power
45+
- Runs shooter motors and ramp motors in raw mode with the specified power
46+
47+
## Intake
48+
49+
Subsystem that runs intake
50+
51+
### Commands
52+
53+
- RunIntake
54+
- Runs intake motor in raw mode with the specified power
Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
package org.firstinspires.ftc.teamcode.subsystems;
2+
3+
import com.arcrobotics.ftclib.command.SubsystemBase;
4+
import com.arcrobotics.ftclib.hardware.motors.Motor;
5+
import com.qualcomm.robotcore.hardware.HardwareMap;
6+
7+
public class Intake extends SubsystemBase {
8+
private final Motor intakeMotor;
9+
10+
public Intake(HardwareMap map, String intakeMotorName) {
11+
intakeMotor = new Motor(map, intakeMotorName);
12+
intakeMotor.setRunMode(Motor.RunMode.RawPower);
13+
}
14+
15+
public void run(double speed) {
16+
double clampedSpeed = Math.max(1.0, Math.min(-1.0, speed));
17+
intakeMotor.set(clampedSpeed);
18+
}
19+
20+
public void stop() {
21+
intakeMotor.stopMotor();
22+
}
23+
}

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystems/Shooter.java

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -5,20 +5,24 @@
55
import com.qualcomm.robotcore.hardware.HardwareMap;
66

77
public class Shooter extends SubsystemBase {
8-
private final Motor shooterMotor;
8+
private final Motor shooterMotor, rampMotor;
99

10-
public Shooter(HardwareMap map, String motorName) {
11-
shooterMotor = new Motor(map, motorName);
10+
public Shooter(HardwareMap map, String shooterMotorName, String rampMotorName) {
11+
shooterMotor = new Motor(map, shooterMotorName);
1212
shooterMotor.setRunMode(Motor.RunMode.RawPower);
13+
rampMotor = new Motor(map, rampMotorName);
14+
rampMotor.setRunMode(Motor.RunMode.RawPower);
1315
}
1416

1517
public void run(double speed) {
1618
// Clamp speed to valid motor range [-1.0, 1.0]
1719
double clampedSpeed = Math.max(-1.0, Math.min(1.0, speed));
1820
shooterMotor.set(clampedSpeed);
21+
rampMotor.set(clampedSpeed);
1922
}
2023

2124
public void stop() {
2225
shooterMotor.stopMotor();
26+
rampMotor.stopMotor();
2327
}
2428
}

0 commit comments

Comments
 (0)