diff --git a/teamcode/BlueBoardSide.java b/teamcode/BlueBoardSide.java deleted file mode 100644 index 1998257..0000000 --- a/teamcode/BlueBoardSide.java +++ /dev/null @@ -1,85 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import static org.firstinspires.ftc.teamcode.operations.inputs.AprilTag.*; -import static org.firstinspires.ftc.teamcode.operations.outputs.DriverStation.output; -import static org.firstinspires.ftc.teamcode.operations.outputs.motors.drive.HardcoreMovements.*; -import static org.firstinspires.ftc.teamcode.operations.outputs.motors.drive.configureMotors.*; - -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; - -import org.firstinspires.ftc.teamcode.operations.TargetOperations; - -@Autonomous(name="Blue, Board Side") -public class BlueBoardSide extends TargetOperations { - - @Override - public void runOpMode() throws InterruptedException { - // LinearOpMode that calls a different form of OpMode: - runInit(); - while(opModeInInit()){runInitLoop();} - waitForStart(); - runStart(); - if (isStopRequested()){runStop();} // stop OpMode if the button is pressed - while (opModeIsActive()) {runLoop();} - visionPortal.close(); // close view for camera - } - - @Override - public void runInit() { - mapMotors("fr","fl","br","bl"); - forwardMotors(false,true,false,true); - // ^ set motor directions - initAprilTag("Camera 1"); - } - - @Override - public void runInitLoop(){} - - @Override - public void runStart() {} - @Override - public void runStop() { - stopAll(); - } - @Override - public void runLoop() { - - setAprilTagVariables(); - // ^ this line puts the april tag number into a variable, along with other april tag infromation - if (gamepad1.a) { - drive(0.5,0.5, 0.25,0.25); - } - else { - driveZeroPower(); - } - - if (gamepad1.x) { - drive(0.5,-0.5, 0.25,-0.25); - } - else { - driveZeroPower(); - } - - if (gamepad1.b) { - drive(-0.5,0.5, -0.25,0.25); - } - else { - driveZeroPower(); - } - output(tagId); - if (tagId == 1){ - output("The First Tag!"); - runStop(); - } - else if (tagId == 2){ - output("The Second Tag!"); - runStop(); - } - else if (tagId == 3){ - output("The Third Tag!"); - runStop(); - } - - } -} - diff --git a/teamcode/BlueFarSide.java b/teamcode/BlueFarSide.java deleted file mode 100644 index d372a7e..0000000 --- a/teamcode/BlueFarSide.java +++ /dev/null @@ -1,45 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; - -import org.firstinspires.ftc.teamcode.operations.TargetOperations; - -@Autonomous(name="Blue, Far Side") -public class BlueFarSide extends TargetOperations { - - @Override - public void runOpMode() { - - runInit(); - while(opModeInInit()){runInitLoop();} - waitForStart(); - runStart(); - if (isStopRequested()){runStop();} - while (opModeIsActive()) {runLoop();} - } - - @Override - public void runInit() { - - } - - @Override - public void runInitLoop() { - - } - - @Override - public void runStart() { - - } - - @Override - public void runLoop() { - - } - - @Override - public void runStop() { - - } -} \ No newline at end of file diff --git a/teamcode/Main.java b/teamcode/Main.java deleted file mode 100644 index 2e94cff..0000000 --- a/teamcode/Main.java +++ /dev/null @@ -1,98 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import static org.firstinspires.ftc.teamcode.operations.inputs.Imu.*; -import static org.firstinspires.ftc.teamcode.operations.outputs.motors.drive.configureMotors.*; -import static org.firstinspires.ftc.teamcode.operations.outputs.motors.pixelMotor.ConfigureMotorPixel.pixelMotor; - -import com.qualcomm.robotcore.eventloop.opmode.TeleOp; - -import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; -import org.firstinspires.ftc.teamcode.operations.TargetOperations; -import org.firstinspires.ftc.teamcode.operations.outputs.motors.barMotor.BarMotorMovements; - -@TeleOp -public class Main extends TargetOperations { - - @Override - public void runOpMode() { - runInit(); - while(opModeInInit()){runInitLoop();} - waitForStart(); - runStart(); - if (isStopRequested()){runStop();} - while (opModeIsActive()) {runLoop();} - } - - @Override - public void runInit() { - mapMotors("fr","fl","br","bl"); - forwardMotors(false,true,false,true); - //ConfigureMotorBar.mapMotor("bar"); - //ConfigureMotorPixel.mapMotor("pixel"); - imuGet("imu", "LEFT", "UP"); - } - - @Override - public void runInitLoop() { - - } - - @Override - public void runStart() { - - } - - @Override - public void runLoop() { - double y = -gamepad1.left_stick_y; // Remember, Y stick value is reversed - double x = gamepad1.left_stick_x; - double rx = gamepad1.right_stick_x; - - // This button choice was made so that it is hard to hit on accident, - // it can be freely changed based on preference. - // The equivalent button is start on Xbox-style controllers. - if (gamepad1.options) { - imu.resetYaw(); - } - - double botHeading = imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS); - - // Rotate the movement direction counter to the bot's rotation - double rotX = x * Math.cos(-botHeading) - y * Math.sin(-botHeading); - double rotY = x * Math.sin(-botHeading) + y * Math.cos(-botHeading); - - rotX = rotX * 1.1; // Counteract imperfect strafing - - // Denominator is the largest motor power (absolute value) or 1 - // This ensures all the powers maintain the same ratio, - // but only if at least one is out of the range [-1, 1] - double denominator = Math.max(Math.abs(rotY) + Math.abs(rotX) + Math.abs(rx), 1); - double frontLeftPower = (rotY + rotX + rx) / denominator; - double backLeftPower = (rotY - rotX + rx) / denominator; - double frontRightPower = (rotY - rotX - rx) / denominator; - double backRightPower = (rotY + rotX - rx) / denominator; - - if (gamepad2.a) { - pixelMotor.setPower(1); // set speed to pixel motor to pick up pixels - } - else if (gamepad2.y) { // run to position for bar motor - pixelMotor.setPower(0); - BarMotorMovements.rotate(50, 1); - - } - - fl.setPower(frontLeftPower); - bl.setPower(backLeftPower); - fr.setPower(frontRightPower); - br.setPower(backRightPower); - - - // speed is still there, more force given to joystick, more power. - - } - - @Override - public void runStop() { - - } -} \ No newline at end of file diff --git a/teamcode/RedBoardSide.java b/teamcode/RedBoardSide.java deleted file mode 100644 index 31f56bc..0000000 --- a/teamcode/RedBoardSide.java +++ /dev/null @@ -1,45 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; - -import org.firstinspires.ftc.teamcode.operations.TargetOperations; - -@Autonomous(name="Red, Board Side") -public class RedBoardSide extends TargetOperations { - @Override - public void runOpMode() { - - runInit(); - while(opModeInInit()){runInitLoop();} - waitForStart(); - runStart(); - if (isStopRequested()){runStop();} - while (opModeIsActive()) {runLoop();} - } - - @Override - public void runInit() { - - } - - @Override - public void runInitLoop() { - - } - - @Override - public void runStart() { - - } - - @Override - public void runLoop() { - - } - - @Override - public void runStop() { - - } - -} \ No newline at end of file diff --git a/teamcode/RedFarSide.java b/teamcode/RedFarSide.java deleted file mode 100644 index 59aeb68..0000000 --- a/teamcode/RedFarSide.java +++ /dev/null @@ -1,46 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import com.qualcomm.robotcore.eventloop.opmode.Autonomous; - -import org.firstinspires.ftc.teamcode.operations.TargetOperations; - -@Autonomous(name="Red, Far Side") -public class RedFarSide extends TargetOperations { - - @Override - public void runOpMode() { - - runInit(); - while(opModeInInit()){runInitLoop();} - waitForStart(); - runStart(); - if (isStopRequested()){runStop();} - while (opModeIsActive()) {runLoop();} - } - - @Override - public void runInit() { - - } - - @Override - public void runInitLoop() { - - } - - @Override - public void runStart() { - - } - - @Override - public void runLoop() { - - } - - @Override - public void runStop() { - - } - -} \ No newline at end of file diff --git a/teamcode/operations/TargetOperations.java b/teamcode/operations/TargetOperations.java deleted file mode 100644 index db89256..0000000 --- a/teamcode/operations/TargetOperations.java +++ /dev/null @@ -1,10 +0,0 @@ -package org.firstinspires.ftc.teamcode.operations; - -import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -public abstract class TargetOperations extends LinearOpMode implements TargetSetup { - - public void stopAll() { - requestOpModeStop(); - } - -} \ No newline at end of file diff --git a/teamcode/operations/TargetSetup.java b/teamcode/operations/TargetSetup.java deleted file mode 100644 index 4ac5484..0000000 --- a/teamcode/operations/TargetSetup.java +++ /dev/null @@ -1,15 +0,0 @@ -// public is not needed, because Interface has public by default -package org.firstinspires.ftc.teamcode.operations; - - interface TargetSetup { - /* - this interface was made so that - both LinearOpMode and OpMode can be - ran within the same class - */ - void runInit(); - void runInitLoop(); - void runStart(); - void runLoop(); - void runStop(); -} diff --git a/teamcode/operations/inputs/AprilTag.java b/teamcode/operations/inputs/AprilTag.java deleted file mode 100644 index a1fa369..0000000 --- a/teamcode/operations/inputs/AprilTag.java +++ /dev/null @@ -1,81 +0,0 @@ -package org.firstinspires.ftc.teamcode.operations.inputs; - -import static org.firstinspires.ftc.robotcore.external.BlocksOpModeCompanion.hardwareMap; - -import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; -import org.firstinspires.ftc.vision.VisionPortal; -import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; -import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; - -import java.util.ArrayList; -import java.util.List; - -public class AprilTag { - - public static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera - - public static VisionPortal visionPortal; - - public static double firstTagId, tagId; - public static AprilTagDetection firstTagFound; - public static double tagsFound; - public static String tagName; - - public static List tagCenter, tagPosition; - - public static AprilTagProcessor aprilTag; - - - public static void initAprilTag(String CameraName) { - - // Create the AprilTag processor - aprilTag = AprilTagProcessor.easyCreateWithDefaults(); - - visionPortal = VisionPortal.easyCreateWithDefaults( - hardwareMap.get(WebcamName.class, CameraName), aprilTag); - } - - public static void initAprilTag() { - // default hardware map name for the camera - initAprilTag("Camera 1"); // sets the name to the default name - } - - public static void setAprilTagVariables() { - // add AprilTag found information to set variables - - List currentDetections = aprilTag.getDetections(); - firstTagFound = currentDetections.get(0); - firstTagId = firstTagFound.id; - tagsFound = currentDetections.size(); - - // Step through the list of detections and display info for each one. - for (AprilTagDetection detection : currentDetections) { - if (detection.metadata != null) { - - tagName = detection.metadata.name; - tagPosition = new ArrayList(); - tagPosition.add(detection.ftcPose.x); - tagPosition.add(detection.ftcPose.y); - tagPosition.add(detection.ftcPose.z); - tagPosition.add(detection.ftcPose.pitch); - tagPosition.add(detection.ftcPose.roll); - tagPosition.add(detection.ftcPose.yaw); - tagPosition.add(detection.ftcPose.range); - tagPosition.add(detection.ftcPose.bearing); - tagPosition.add(detection.ftcPose.elevation); - - } - else { - - tagName = "unknown"; - } - - tagId = detection.id; - - tagCenter = new ArrayList(); - tagCenter.add(detection.center.x); - tagCenter.add(detection.center.y); - } - } - -} diff --git a/teamcode/operations/inputs/Imu.java b/teamcode/operations/inputs/Imu.java deleted file mode 100644 index eaa7585..0000000 --- a/teamcode/operations/inputs/Imu.java +++ /dev/null @@ -1,82 +0,0 @@ -package org.firstinspires.ftc.teamcode.operations.inputs; - -import static com.qualcomm.hardware.rev.RevHubOrientationOnRobot.LogoFacingDirection.BACKWARD; -import static com.qualcomm.hardware.rev.RevHubOrientationOnRobot.LogoFacingDirection.DOWN; -import static com.qualcomm.hardware.rev.RevHubOrientationOnRobot.LogoFacingDirection.FORWARD; -import static com.qualcomm.hardware.rev.RevHubOrientationOnRobot.LogoFacingDirection.LEFT; -import static com.qualcomm.hardware.rev.RevHubOrientationOnRobot.LogoFacingDirection.RIGHT; -import static com.qualcomm.hardware.rev.RevHubOrientationOnRobot.LogoFacingDirection.UP; - -import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; -import com.qualcomm.robotcore.hardware.HardwareMap; -import com.qualcomm.robotcore.hardware.IMU; - - -public class Imu { - - public static IMU imu; - - static HardwareMap hardwareMap = null; - - public static void imuGet (String hardwareMapImuName, String logoFacing, String usbFacing) { - // get imu from hardware map and set the directions to the directions of the robot's brain - imu = hardwareMap.get(IMU .class, hardwareMapImuName); - // Retrieve the IMU from the hardware map - IMU.Parameters parameters = null; - // Adjust the orientation parameters to match your robot - if (logoFacing == UP.name() && usbFacing == FORWARD.name()) { - parameters = new IMU.Parameters(new RevHubOrientationOnRobot( - UP, - RevHubOrientationOnRobot.UsbFacingDirection.FORWARD)); - } - - else if (logoFacing == LEFT.name() && usbFacing == UP.name()) { - parameters = new IMU.Parameters(new RevHubOrientationOnRobot( - RevHubOrientationOnRobot.LogoFacingDirection.LEFT, - RevHubOrientationOnRobot.UsbFacingDirection.UP)); - } - - else if (logoFacing == RIGHT.name() && usbFacing == UP.name()) { - parameters = new IMU.Parameters(new RevHubOrientationOnRobot( - RevHubOrientationOnRobot.LogoFacingDirection.RIGHT, - RevHubOrientationOnRobot.UsbFacingDirection.UP)); - } - - else if (logoFacing == FORWARD.name() && usbFacing == UP.name()) { - parameters = new IMU.Parameters(new RevHubOrientationOnRobot( - RevHubOrientationOnRobot.LogoFacingDirection.FORWARD, - RevHubOrientationOnRobot.UsbFacingDirection.UP)); - } - - else if (logoFacing == BACKWARD.name() && usbFacing == UP.name()) { - parameters = new IMU.Parameters(new RevHubOrientationOnRobot( - RevHubOrientationOnRobot.LogoFacingDirection.BACKWARD, - RevHubOrientationOnRobot.UsbFacingDirection.UP)); - } - - else if (logoFacing == FORWARD.name() && usbFacing == RIGHT.name()) { - parameters = new IMU.Parameters(new RevHubOrientationOnRobot( - RevHubOrientationOnRobot.LogoFacingDirection.FORWARD, - RevHubOrientationOnRobot.UsbFacingDirection.RIGHT)); - } - - else if (logoFacing == UP.name() && usbFacing == BACKWARD.name()) { - parameters = new IMU.Parameters(new RevHubOrientationOnRobot( - UP, - RevHubOrientationOnRobot.UsbFacingDirection.BACKWARD)); - } - - else if (logoFacing == DOWN.name() && usbFacing == FORWARD.name()) { - parameters = new IMU.Parameters(new RevHubOrientationOnRobot( - RevHubOrientationOnRobot.LogoFacingDirection.DOWN, - RevHubOrientationOnRobot.UsbFacingDirection.FORWARD)); - } - - else if (logoFacing == FORWARD.name() && usbFacing == LEFT.name()) { - parameters = new IMU.Parameters(new RevHubOrientationOnRobot( - RevHubOrientationOnRobot.LogoFacingDirection.FORWARD, - RevHubOrientationOnRobot.UsbFacingDirection.LEFT)); - } - imu.initialize(parameters); - } -} diff --git a/teamcode/operations/outputs/DriverStation.java b/teamcode/operations/outputs/DriverStation.java deleted file mode 100644 index 404373f..0000000 --- a/teamcode/operations/outputs/DriverStation.java +++ /dev/null @@ -1,11 +0,0 @@ -package org.firstinspires.ftc.teamcode.operations.outputs; - -import static org.firstinspires.ftc.robotcore.external.BlocksOpModeCompanion.telemetry; - -public class DriverStation { - public static void output(Object output) { - // display to telemetry without a caption - telemetry.addData("", output); - telemetry.update(); - } -} diff --git a/teamcode/operations/outputs/motors/barMotor/BarMotorMovements.java b/teamcode/operations/outputs/motors/barMotor/BarMotorMovements.java deleted file mode 100644 index 709d381..0000000 --- a/teamcode/operations/outputs/motors/barMotor/BarMotorMovements.java +++ /dev/null @@ -1,20 +0,0 @@ -package org.firstinspires.ftc.teamcode.operations.outputs.motors.barMotor; - -import static org.firstinspires.ftc.teamcode.operations.outputs.motors.barMotor.ConfigureMotorBar.barMotor; - -import com.qualcomm.robotcore.hardware.DcMotor; - -public class BarMotorMovements { - - public void motorEncoder () { - barMotor.setMode(DcMotor.RunMode.RUN_USING_ENCODER); - barMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); - barMotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); - } - - public static void rotate(int rotations, int speed) { - barMotor.setTargetPosition(rotations); - barMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION); - barMotor.setPower(speed); - } -} diff --git a/teamcode/operations/outputs/motors/barMotor/ConfigureMotorBar.java b/teamcode/operations/outputs/motors/barMotor/ConfigureMotorBar.java deleted file mode 100644 index a243496..0000000 --- a/teamcode/operations/outputs/motors/barMotor/ConfigureMotorBar.java +++ /dev/null @@ -1,14 +0,0 @@ -package org.firstinspires.ftc.teamcode.operations.outputs.motors.barMotor; - -import static org.firstinspires.ftc.robotcore.external.BlocksOpModeCompanion.hardwareMap; - -import com.qualcomm.robotcore.hardware.DcMotor; - -public class ConfigureMotorBar { - - public static DcMotor barMotor; - public static void mapMotor (String motorName) { - barMotor = hardwareMap.dcMotor.get(motorName); - } - -} diff --git a/teamcode/operations/outputs/motors/drive/HardcoreMovements.java b/teamcode/operations/outputs/motors/drive/HardcoreMovements.java deleted file mode 100644 index 7aac3a2..0000000 --- a/teamcode/operations/outputs/motors/drive/HardcoreMovements.java +++ /dev/null @@ -1,91 +0,0 @@ -package org.firstinspires.ftc.teamcode.operations.outputs.motors.drive; -import static org.firstinspires.ftc.teamcode.operations.outputs.motors.drive.configureMotors.*; - -public class HardcoreMovements { - - public static void forward(double speed) { - fr.setPower(speed); - fl.setPower(speed); - br.setPower(speed); - bl.setPower(speed); - - } - - public static void backward(double speed) { - fr.setPower(speed); - fl.setPower(speed); - br.setPower(speed); - bl.setPower(speed); - - } - - public static void left(double speed) { - fr.setPower(speed); - fl.setPower(-speed); - br.setPower(-speed); - bl.setPower(speed); - - } - - public static void right(double speed) { - fr.setPower(-speed); - fl.setPower(speed); - br.setPower(speed); - bl.setPower(-speed); - - } - - public static void forwardLeft(double speed) { - fr.setPower(speed); - bl.setPower(speed); - - } - - public static void forwardRight(double speed) { - fl.setPower(speed); - br.setPower(speed); - - } - - public static void backwardLeft(double speed) {; - fl.setPower(-speed); - br.setPower(-speed); - - } - - public static void backwardRight(double speed) { - fr.setPower(-speed); - bl.setPower(-speed); - - } - - public static void turnRight(double speed) { - fr.setPower(-speed); - fl.setPower(speed); - br.setPower(-speed); - bl.setPower(speed); - - } - - public static void turnLeft(double speed) { - fr.setPower(speed); - fl.setPower(-speed); - br.setPower(speed); - bl.setPower(-speed); - - } - - public static void drive(double frontLeftSpeed, double frontRightSpeed, double backLeftSpeed, double backRightSpeed) { - fr.setPower(frontLeftSpeed); - fl.setPower(frontRightSpeed); - br.setPower(backLeftSpeed); - bl.setPower(backRightSpeed); - - } - - public static void driveZeroPower() { - drive(0,0,0,0); - } - // ^ set all motors to 0, this stops all movements - -} diff --git a/teamcode/operations/outputs/motors/drive/configureMotors.java b/teamcode/operations/outputs/motors/drive/configureMotors.java deleted file mode 100644 index a1c1d1c..0000000 --- a/teamcode/operations/outputs/motors/drive/configureMotors.java +++ /dev/null @@ -1,59 +0,0 @@ -package org.firstinspires.ftc.teamcode.operations.outputs.motors.drive; - -import com.qualcomm.robotcore.hardware.DcMotor; -import com.qualcomm.robotcore.hardware.DcMotorSimple; -import com.qualcomm.robotcore.hardware.HardwareMap; - -public class configureMotors { - - public static DcMotor fr; - public static DcMotor fl; - public static DcMotor br; - public static DcMotor bl; - - static HardwareMap hardwareMap = null; - - public static void mapMotors (String frontLeftMotor, String frontRightMotor, String backLeftMotor, String backRightMotor) { - fr = hardwareMap.dcMotor.get(frontRightMotor); - fl = hardwareMap.dcMotor.get(frontLeftMotor); - br = hardwareMap.dcMotor.get(backRightMotor); - bl = hardwareMap.dcMotor.get(backLeftMotor); - } - - - public static void forwardMotors (boolean frontLeftMotor, boolean frontRightMotor, boolean backLeftMotor, boolean backRightMotor) { - - if (frontRightMotor) { - fr.setDirection(DcMotorSimple.Direction.FORWARD); - } - - else { - fr.setDirection(DcMotorSimple.Direction.REVERSE); - } - - if (frontLeftMotor) { - fl.setDirection(DcMotorSimple.Direction.FORWARD); - } - - else { - fl.setDirection(DcMotorSimple.Direction.REVERSE); - } - - if (backRightMotor) { - br.setDirection(DcMotorSimple.Direction.FORWARD); - } - - else { - br.setDirection(DcMotorSimple.Direction.REVERSE); - } - - if (backLeftMotor) { - bl.setDirection(DcMotorSimple.Direction.FORWARD); - } - - else { - bl.setDirection(DcMotorSimple.Direction.REVERSE); - } - } - -} diff --git a/teamcode/operations/outputs/motors/pixelMotor/ConfigureMotorPixel.java b/teamcode/operations/outputs/motors/pixelMotor/ConfigureMotorPixel.java deleted file mode 100644 index 91e7288..0000000 --- a/teamcode/operations/outputs/motors/pixelMotor/ConfigureMotorPixel.java +++ /dev/null @@ -1,15 +0,0 @@ -package org.firstinspires.ftc.teamcode.operations.outputs.motors.pixelMotor; - -import static org.firstinspires.ftc.robotcore.external.BlocksOpModeCompanion.hardwareMap; - -import com.qualcomm.robotcore.hardware.DcMotor; - -public class ConfigureMotorPixel { - - public static DcMotor pixelMotor; - - public static void mapMotor (String motorName) { - pixelMotor = hardwareMap.dcMotor.get(motorName); - } - -} diff --git a/teamcode/operations/outputs/motors/pixelMotor/PixelMotorMovements.java b/teamcode/operations/outputs/motors/pixelMotor/PixelMotorMovements.java deleted file mode 100644 index d1704f7..0000000 --- a/teamcode/operations/outputs/motors/pixelMotor/PixelMotorMovements.java +++ /dev/null @@ -1,21 +0,0 @@ -package org.firstinspires.ftc.teamcode.operations.outputs.motors.pixelMotor; - -import static org.firstinspires.ftc.teamcode.operations.outputs.motors.pixelMotor.ConfigureMotorPixel.pixelMotor; - -import com.qualcomm.robotcore.hardware.DcMotor; - -public class PixelMotorMovements { - - public static void motorEncoder () { - pixelMotor.setMode(DcMotor.RunMode.RUN_USING_ENCODER); - pixelMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); - pixelMotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); - } - - public static void rotate (int rotations, int speed) { - pixelMotor.setTargetPosition(rotations); - pixelMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION); - pixelMotor.setPower(speed); - } - -}