diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/cometbots/tests/WristTest.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/cometbots/tests/WristTest.java new file mode 100644 index 0000000..e8fd1ff --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/cometbots/tests/WristTest.java @@ -0,0 +1,93 @@ +/* Copyright (c) 2021 FIRST. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted (subject to the limitations in the disclaimer below) provided that + * the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or + * other materials provided with the distribution. + * + * Neither the name of FIRST nor the names of its contributors may be used to endorse or + * promote products derived from this software without specific prior written permission. + * + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +package org.firstinspires.ftc.teamcode.cometbots.tests; + +import com.acmerobotics.roadrunner.ftc.Actions; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.Gamepad; +import com.qualcomm.robotcore.util.ElapsedTime; + +import org.firstinspires.ftc.teamcode.subsystem.WristSubsystem; + +@TeleOp(name = "Wrist Test v2", group = "Debug") +public class WristTest extends LinearOpMode { + + // Declare OpMode members for each of the 4 motors. + private final ElapsedTime runtime = new ElapsedTime(); + + @Override + public void runOpMode() { + + /* + * Instantiate Wrist + */ + WristSubsystem wrist = new WristSubsystem(hardwareMap); + + /* + * Instantiate gamepad state holders + */ + Gamepad currentGamepad1 = new Gamepad(); + Gamepad previousGamepad1 = new Gamepad(); + + wrist.init(); + waitForStart(); + runtime.reset(); + + // run until the end of the match (driver presses STOP) + while (opModeIsActive()) { + + previousGamepad1.copy(currentGamepad1); + currentGamepad1.copy(gamepad1); + + if (currentGamepad1.square && !previousGamepad1.square) { + wrist.toBucketPosition(); + } + + if (currentGamepad1.cross && !previousGamepad1.cross) { + wrist.switchState(); + } + + if (currentGamepad1.left_bumper && !previousGamepad1.left_bumper) { + wrist.setPosition(wrist.getPosition() - .05); + } + + if (currentGamepad1.right_bumper && !previousGamepad1.right_bumper) { + wrist.setPosition(wrist.getPosition() + .05); + } + + // Show the elapsed game time and wheel power. + telemetry.addData("Status", "Run Time: " + runtime.toString()); + telemetry.addData("Wrist State", wrist.getState()); + telemetry.addData("Wrist Position", wrist.getPosition()); + telemetry.update(); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystem/WristSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystem/WristSubsystem.java new file mode 100644 index 0000000..d2bef2c --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystem/WristSubsystem.java @@ -0,0 +1,92 @@ +package org.firstinspires.ftc.teamcode.subsystem; + +import static org.firstinspires.ftc.teamcode.PedroConstants.WRIST_SERVO; +import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristBucket; +import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristFloor; +import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristPickup; +import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristSpeciemen; + +import androidx.annotation.NonNull; + +import com.acmerobotics.dashboard.telemetry.TelemetryPacket; +import com.acmerobotics.roadrunner.Action; +import com.acmerobotics.roadrunner.ftc.Actions; +import com.qualcomm.robotcore.hardware.HardwareMap; +import com.qualcomm.robotcore.hardware.ServoImplEx; + +public class WristSubsystem { + + public enum WristState { + FLOOR, BUCKET, PICKUP, RUNG, SPECIMEN + } + + public ServoImplEx wrist; + public WristState state; + + public WristSubsystem(HardwareMap hardwareMap) { + this.wrist = hardwareMap.get(ServoImplEx.class, WRIST_SERVO); + } + + public class MoveToPosition implements Action { + private double positionValue; + private WristState positionState; + + public MoveToPosition(double positionValue, WristState positionState) { + this.positionValue = positionValue; + this.positionState = positionState; + } + + @Override + public boolean run(@NonNull TelemetryPacket telemetryPacket) { + setState(positionState); + wrist.setPosition(positionValue); + telemetryPacket.put("Wrist State", positionState); + return false; + } + } + + public void toFloorPosition() { + setState(WristState.FLOOR); + wrist.setPosition(wristFloor); + } + + public void toBucketPosition() { + setState(WristState.BUCKET); + wrist.setPosition(wristBucket); + } + + public void toPickupPosition() { + setState(WristState.PICKUP); + wrist.setPosition(wristPickup); + } + + public void setState(WristState wristState) { + this.state = wristState; + } + + public void switchState() { + if (state == WristState.FLOOR) { + toPickupPosition(); + } else if (state == WristState.PICKUP) { + toFloorPosition(); + } + } + + public WristState getState() { + return this.state; + } + + public void init() { + wrist.resetDeviceConfigurationForOpMode(); + toPickupPosition(); + } + + public void setPosition(double position) { + wrist.setPosition(position); + } + + public double getPosition() { + return wrist.getPosition(); + } + +}