diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/ClawCode.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/ClawCode.java index 90ac6d96..1f2e9746 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/ClawCode.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/ClawCode.java @@ -24,6 +24,7 @@ public void init() { } @Override + public void loop() { /* Rotating servos based on user input. */ if (gamepad1.a) { @@ -43,4 +44,3 @@ public void loop() { telemetry.addData("clawLock position", robot.get("clawLock").getPosition()); telemetry.addData("clawJoint position", robot.get("clawJoint").getPower()); } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/IntakeRunningCode.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/IntakeRunningCode.java index db9ec6a0..93783ed2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/IntakeRunningCode.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/IntakeRunningCode.java @@ -19,8 +19,7 @@ public void init() { robot.introduce(new HardwareElement<>(CRServo.class, hardwareMap, "intakeTube")); robot.introduce(new HardwareElement<>(CRServo.class, hardwareMap, "outerIntakeJoint1")); robot.introduce(new HardwareElement<>(CRServo.class, hardwareMap, "outerIntakeJoint2")); - robot.introduce(new HardwareElement<>(CRServo.class, hardwareMap, "outerIntakeTube1")); - robot.introduce(new HardwareElement<>(CRServo.class, hardwareMap, "outerIntakeTube2")); + robot.introduce(new HardwareElement<>(CRServo.class, hardwareMap, "outerIntakeTube")); telemetry.addData("Status", "Initialized"); } @@ -41,14 +40,12 @@ public void loop() { if (gamepad1.a) { robot.get("intakeTube").setPower(0.5); robot.get("intakeGeckoWheels").setPower(0.5); - robot.get("outerIntakeTube1").setPower(0.5); - robot.get("outerIntakeTube2").setPower(-0.5); + robot.get("outerIntakeTube").setPower(0.5); telemetry.addData("Intake", "Running"); } else { robot.get("intakeTube").setPower(0); robot.get("intakeGeckoWheels").setPower(0); - robot.get("outerIntakeTube1").setPower(0); - robot.get("outerIntakeTube2").setPower(0); + robot.get("outerIntakeTube").setPower(0); telemetry.addData("Intake", "Stopped"); }