Add drone launcher
This commit is contained in:
parent
0fc58a36e8
commit
59fed0a5f7
|
@ -0,0 +1,25 @@
|
||||||
|
package org.firstinspires.ftc.teamcode.hardware;
|
||||||
|
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
import com.qualcomm.robotcore.hardware.Servo;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.util.Constants;
|
||||||
|
|
||||||
|
public class DroneLauncher {
|
||||||
|
private Servo servo;
|
||||||
|
public static double initPos = 0;
|
||||||
|
public static double launchPos = 0.5;
|
||||||
|
|
||||||
|
public DroneLauncher(HardwareMap hardwareMap) {
|
||||||
|
this.servo = hardwareMap.get(Servo.class, Constants.droneLauncher);
|
||||||
|
this.servo.setPosition(initPos);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void launch() {
|
||||||
|
this.servo.setPosition(launchPos);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void reset() {
|
||||||
|
this.servo.setPosition(initPos);
|
||||||
|
}
|
||||||
|
}
|
|
@ -20,6 +20,7 @@ public class Robot {
|
||||||
public Intake intake;
|
public Intake intake;
|
||||||
public Slides slides;
|
public Slides slides;
|
||||||
public Arm arm;
|
public Arm arm;
|
||||||
|
public DroneLauncher droneLauncher;
|
||||||
public double macroStartTime = 0;
|
public double macroStartTime = 0;
|
||||||
public int macroState = 0;
|
public int macroState = 0;
|
||||||
public int runningMacro = 0; // 0 = no macro | 1 = tier 1 | 2 = tier 2 | 3 = tier 3 | 4 = return
|
public int runningMacro = 0; // 0 = no macro | 1 = tier 1 | 2 = tier 2 | 3 = tier 3 | 4 = return
|
||||||
|
@ -35,6 +36,7 @@ public class Robot {
|
||||||
intake = new Intake(hardwareMap, UP);
|
intake = new Intake(hardwareMap, UP);
|
||||||
slides = new Slides(hardwareMap);
|
slides = new Slides(hardwareMap);
|
||||||
arm = new Arm(hardwareMap);
|
arm = new Arm(hardwareMap);
|
||||||
|
droneLauncher = new DroneLauncher(hardwareMap);
|
||||||
camEnabled = true;
|
camEnabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -43,7 +43,7 @@ public class NewTeleop extends OpMode {
|
||||||
double y = -gamepad1.left_stick_x;
|
double y = -gamepad1.left_stick_x;
|
||||||
double z = -gamepad1.right_stick_x;
|
double z = -gamepad1.right_stick_x;
|
||||||
|
|
||||||
if (controller1.getA().isPressed()) {
|
if (controller1.getRightTrigger().getValue() > 0.1) {
|
||||||
x *= turbo;
|
x *= turbo;
|
||||||
y *= turbo;
|
y *= turbo;
|
||||||
z *= turbo;
|
z *= turbo;
|
||||||
|
@ -63,6 +63,13 @@ public class NewTeleop extends OpMode {
|
||||||
robot.intake.decrementPos();
|
robot.intake.decrementPos();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Drone launcher
|
||||||
|
if (controller1.getA().isPressed()) {
|
||||||
|
this.robot.droneLauncher.launch();
|
||||||
|
} else {
|
||||||
|
this.robot.droneLauncher.reset();
|
||||||
|
}
|
||||||
|
|
||||||
// macros
|
// macros
|
||||||
switch (robot.runningMacro) {
|
switch (robot.runningMacro) {
|
||||||
case (0): // manual mode
|
case (0): // manual mode
|
||||||
|
|
|
@ -55,4 +55,5 @@ public class Constants {
|
||||||
public static final String IMU_SENSOR = "imu";
|
public static final String IMU_SENSOR = "imu";
|
||||||
public static final String lServo = "lServo";
|
public static final String lServo = "lServo";
|
||||||
public static final String rServo = "rServo";
|
public static final String rServo = "rServo";
|
||||||
|
public static final String droneLauncher = "droneLauncher";
|
||||||
}
|
}
|
Loading…
Reference in New Issue