diff --git a/.gitignore b/.gitignore index 8c94b97..b85aa2f 100644 --- a/.gitignore +++ b/.gitignore @@ -78,7 +78,4 @@ lint/intermediates/ lint/generated/ lint/outputs/ lint/tmp/ -# lint/reports/ - -.DS_Store -/.idea +# lint/reports/ \ No newline at end of file diff --git a/FtcRobotController/src/main/AndroidManifest.xml b/FtcRobotController/src/main/AndroidManifest.xml index b5a63b1..3b87d9d 100644 --- a/FtcRobotController/src/main/AndroidManifest.xml +++ b/FtcRobotController/src/main/AndroidManifest.xml @@ -1,8 +1,8 @@ + android:versionCode="55" + android:versionName="10.0"> diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOmniOpMode_Linear.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOmniOpMode_Linear.java index 940b527..1d14dfb 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOmniOpMode_Linear.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOmniOpMode_Linear.java @@ -99,7 +99,7 @@ public class BasicOmniOpMode_Linear extends LinearOpMode { rightFrontDrive.setDirection(DcMotor.Direction.FORWARD); rightBackDrive.setDirection(DcMotor.Direction.FORWARD); - // Wait for the game to start (driver presses PLAY) + // Wait for the game to start (driver presses START) telemetry.addData("Status", "Initialized"); telemetry.update(); diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Iterative.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Iterative.java index 7c10408..6504e58 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Iterative.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Iterative.java @@ -83,14 +83,14 @@ public class BasicOpMode_Iterative extends OpMode } /* - * Code to run REPEATEDLY after the driver hits INIT, but before they hit PLAY + * Code to run REPEATEDLY after the driver hits INIT, but before they hit START */ @Override public void init_loop() { } /* - * Code to run ONCE when the driver hits PLAY + * Code to run ONCE when the driver hits START */ @Override public void start() { @@ -98,7 +98,7 @@ public class BasicOpMode_Iterative extends OpMode } /* - * Code to run REPEATEDLY after the driver hits PLAY but before they hit STOP + * Code to run REPEATEDLY after the driver hits START but before they hit STOP */ @Override public void loop() { diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Linear.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Linear.java index 9fe0bb6..ab0bb25 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Linear.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOpMode_Linear.java @@ -76,7 +76,7 @@ public class BasicOpMode_Linear extends LinearOpMode { leftDrive.setDirection(DcMotor.Direction.REVERSE); rightDrive.setDirection(DcMotor.Direction.FORWARD); - // Wait for the game to start (driver presses PLAY) + // Wait for the game to start (driver presses START) waitForStart(); runtime.reset(); diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTag.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTag.java index b6aa4e5..8ec77dd 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTag.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTag.java @@ -88,7 +88,7 @@ public class ConceptAprilTag extends LinearOpMode { // Wait for the DS start button to be touched. telemetry.addData("DS preview on/off", "3 dots, Camera Stream"); - telemetry.addData(">", "Touch Play to start OpMode"); + telemetry.addData(">", "Touch START to start OpMode"); telemetry.update(); waitForStart(); diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagEasy.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagEasy.java index d305d55..12dcf6e 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagEasy.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagEasy.java @@ -84,7 +84,7 @@ public class ConceptAprilTagEasy extends LinearOpMode { // Wait for the DS start button to be touched. telemetry.addData("DS preview on/off", "3 dots, Camera Stream"); - telemetry.addData(">", "Touch Play to start OpMode"); + telemetry.addData(">", "Touch START to start OpMode"); telemetry.update(); waitForStart(); diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagLocalization.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagLocalization.java new file mode 100644 index 0000000..05318ba --- /dev/null +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagLocalization.java @@ -0,0 +1,244 @@ +/* Copyright (c) 2024 Dryw Wade. 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.robotcontroller.external.samples; + +import com.qualcomm.robotcore.eventloop.opmode.Disabled; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; + +import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; +import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; +import org.firstinspires.ftc.robotcore.external.navigation.Position; +import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles; +import org.firstinspires.ftc.vision.VisionPortal; +import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; +import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; + +import java.util.List; + +/* + * This OpMode illustrates the basics of AprilTag based localization. + * + * For an introduction to AprilTags, see the FTC-DOCS link below: + * https://ftc-docs.firstinspires.org/en/latest/apriltag/vision_portal/apriltag_intro/apriltag-intro.html + * + * In this sample, any visible tag ID will be detected and displayed, but only tags that are included in the default + * "TagLibrary" will be used to compute the robot's location and orientation. This default TagLibrary contains + * the current Season's AprilTags and a small set of "test Tags" in the high number range. + * + * When an AprilTag in the TagLibrary is detected, the SDK provides location and orientation of the robot, relative to the field origin. + * This information is provided in the "robotPose" member of the returned "detection". + * + * Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name. + * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list. + */ +@TeleOp(name = "Concept: AprilTag Localization", group = "Concept") +@Disabled +public class ConceptAprilTagLocalization extends LinearOpMode { + + private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera + + /** + * Variables to store the position and orientation of the camera on the robot. Setting these + * values requires a definition of the axes of the camera and robot: + * + * Camera axes: + * Origin location: Center of the lens + * Axes orientation: +x right, +y down, +z forward (from camera's perspective) + * + * Robot axes (this is typical, but you can define this however you want): + * Origin location: Center of the robot at field height + * Axes orientation: +x right, +y forward, +z upward + * + * Position: + * If all values are zero (no translation), that implies the camera is at the center of the + * robot. Suppose your camera is positioned 5 inches to the left, 7 inches forward, and 12 + * inches above the ground - you would need to set the position to (-5, 7, 12). + * + * Orientation: + * If all values are zero (no rotation), that implies the camera is pointing straight up. In + * most cases, you'll need to set the pitch to -90 degrees (rotation about the x-axis), meaning + * the camera is horizontal. Use a yaw of 0 if the camera is pointing forwards, +90 degrees if + * it's pointing straight left, -90 degrees for straight right, etc. You can also set the roll + * to +/-90 degrees if it's vertical, or 180 degrees if it's upside-down. + */ + private Position cameraPosition = new Position(DistanceUnit.INCH, + 0, 0, 0, 0); + private YawPitchRollAngles cameraOrientation = new YawPitchRollAngles(AngleUnit.DEGREES, + 0, -90, 0, 0); + + /** + * The variable to store our instance of the AprilTag processor. + */ + private AprilTagProcessor aprilTag; + + /** + * The variable to store our instance of the vision portal. + */ + private VisionPortal visionPortal; + + @Override + public void runOpMode() { + + initAprilTag(); + + // Wait for the DS start button to be touched. + telemetry.addData("DS preview on/off", "3 dots, Camera Stream"); + telemetry.addData(">", "Touch START to start OpMode"); + telemetry.update(); + waitForStart(); + + while (opModeIsActive()) { + + telemetryAprilTag(); + + // Push telemetry to the Driver Station. + telemetry.update(); + + // Save CPU resources; can resume streaming when needed. + if (gamepad1.dpad_down) { + visionPortal.stopStreaming(); + } else if (gamepad1.dpad_up) { + visionPortal.resumeStreaming(); + } + + // Share the CPU. + sleep(20); + } + + // Save more CPU resources when camera is no longer needed. + visionPortal.close(); + + } // end method runOpMode() + + /** + * Initialize the AprilTag processor. + */ + private void initAprilTag() { + + // Create the AprilTag processor. + aprilTag = new AprilTagProcessor.Builder() + + // The following default settings are available to un-comment and edit as needed. + //.setDrawAxes(false) + //.setDrawCubeProjection(false) + //.setDrawTagOutline(true) + //.setTagFamily(AprilTagProcessor.TagFamily.TAG_36h11) + //.setTagLibrary(AprilTagGameDatabase.getCenterStageTagLibrary()) + //.setOutputUnits(DistanceUnit.INCH, AngleUnit.DEGREES) + .setCameraPose(cameraPosition, cameraOrientation) + + // == CAMERA CALIBRATION == + // If you do not manually specify calibration parameters, the SDK will attempt + // to load a predefined calibration for your camera. + //.setLensIntrinsics(578.272, 578.272, 402.145, 221.506) + // ... these parameters are fx, fy, cx, cy. + + .build(); + + // Adjust Image Decimation to trade-off detection-range for detection-rate. + // eg: Some typical detection data using a Logitech C920 WebCam + // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second + // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second + // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second (default) + // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second (default) + // Note: Decimation can be changed on-the-fly to adapt during a match. + //aprilTag.setDecimation(3); + + // Create the vision portal by using a builder. + VisionPortal.Builder builder = new VisionPortal.Builder(); + + // Set the camera (webcam vs. built-in RC phone camera). + if (USE_WEBCAM) { + builder.setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")); + } else { + builder.setCamera(BuiltinCameraDirection.BACK); + } + + // Choose a camera resolution. Not all cameras support all resolutions. + //builder.setCameraResolution(new Size(640, 480)); + + // Enable the RC preview (LiveView). Set "false" to omit camera monitoring. + //builder.enableLiveView(true); + + // Set the stream format; MJPEG uses less bandwidth than default YUY2. + //builder.setStreamFormat(VisionPortal.StreamFormat.YUY2); + + // Choose whether or not LiveView stops if no processors are enabled. + // If set "true", monitor shows solid orange screen if no processors enabled. + // If set "false", monitor shows camera view without annotations. + //builder.setAutoStopLiveView(false); + + // Set and enable the processor. + builder.addProcessor(aprilTag); + + // Build the Vision Portal, using the above settings. + visionPortal = builder.build(); + + // Disable or re-enable the aprilTag processor at any time. + //visionPortal.setProcessorEnabled(aprilTag, true); + + } // end method initAprilTag() + + /** + * Add telemetry about AprilTag detections. + */ + private void telemetryAprilTag() { + + List currentDetections = aprilTag.getDetections(); + telemetry.addData("# AprilTags Detected", currentDetections.size()); + + // Step through the list of detections and display info for each one. + for (AprilTagDetection detection : currentDetections) { + if (detection.metadata != null) { + telemetry.addLine(String.format("\n==== (ID %d) %s", detection.id, detection.metadata.name)); + telemetry.addLine(String.format("XYZ %6.1f %6.1f %6.1f (inch)", + detection.robotPose.getPosition().x, + detection.robotPose.getPosition().y, + detection.robotPose.getPosition().z)); + telemetry.addLine(String.format("PRY %6.1f %6.1f %6.1f (deg)", + detection.robotPose.getOrientation().getPitch(AngleUnit.DEGREES), + detection.robotPose.getOrientation().getRoll(AngleUnit.DEGREES), + detection.robotPose.getOrientation().getYaw(AngleUnit.DEGREES))); + } else { + telemetry.addLine(String.format("\n==== (ID %d) Unknown", detection.id)); + telemetry.addLine(String.format("Center %6.0f %6.0f (pixels)", detection.center.x, detection.center.y)); + } + } // end for() loop + + // Add "key" information to telemetry + telemetry.addLine("\nkey:\nXYZ = X (Right), Y (Forward), Z (Up) dist."); + telemetry.addLine("PRY = Pitch, Roll & Yaw (XYZ Rotation)"); + + } // end method telemetryAprilTag() + +} // end class diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagOptimizeExposure.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagOptimizeExposure.java index 3792992..adee952 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagOptimizeExposure.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagOptimizeExposure.java @@ -98,7 +98,7 @@ public class ConceptAprilTagOptimizeExposure extends LinearOpMode // Wait for the match to begin. telemetry.addData("Camera preview on/off", "3 dots, Camera Stream"); - telemetry.addData(">", "Touch Play to start OpMode"); + telemetry.addData(">", "Touch START to start OpMode"); telemetry.update(); waitForStart(); diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagSwitchableCameras.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagSwitchableCameras.java index 9285224..7ee1064 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagSwitchableCameras.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptAprilTagSwitchableCameras.java @@ -77,7 +77,7 @@ public class ConceptAprilTagSwitchableCameras extends LinearOpMode { // Wait for the DS start button to be touched. telemetry.addData("DS preview on/off", "3 dots, Camera Stream"); - telemetry.addData(">", "Touch Play to start OpMode"); + telemetry.addData(">", "Touch START to start OpMode"); telemetry.update(); waitForStart(); diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptExternalHardwareClass.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptExternalHardwareClass.java index 2fe4154..7a721fe 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptExternalHardwareClass.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptExternalHardwareClass.java @@ -83,7 +83,7 @@ public class ConceptExternalHardwareClass extends LinearOpMode { robot.init(); // Send telemetry message to signify robot waiting; - // Wait for the game to start (driver presses PLAY) + // Wait for the game to start (driver presses START) waitForStart(); // run until the end of the match (driver presses STOP) diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptLEDStick.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptLEDStick.java new file mode 100644 index 0000000..01729bb --- /dev/null +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptLEDStick.java @@ -0,0 +1,123 @@ +package org.firstinspires.ftc.robotcontroller.external.samples; +/* + Copyright (c) 2021-24 Alan Smith + + 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 Alan Smith 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 FITNESSFOR 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. +*/ + +import android.graphics.Color; + +import com.qualcomm.hardware.sparkfun.SparkFunLEDStick; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.util.Range; + +/* + * This OpMode illustrates how to use the SparkFun QWIIC LED Strip + * + * This is a simple way to add a strip of 10 LEDs to your robot where you can set the color of each + * LED or the whole strip. This allows for driver feedback or even just fun ways to show your team + * colors. + * + * Why? + * Because more LEDs == more fun!! + * + * This OpMode assumes that the QWIIC LED Stick is attached to an I2C interface named "back_leds" in the robot configuration. + * + * Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name. + * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list + * + * You can buy this product here: https://www.sparkfun.com/products/18354 + * Don't forget to also buy this to make it easy to connect to your Control or Expansion Hub: + * https://www.sparkfun.com/products/25596 + */ +@TeleOp(name = "Concept: LED Stick", group = "Concept") +@Disabled +public class ConceptLEDStick extends OpMode { + private boolean wasUp; + private boolean wasDown; + private int brightness = 5; // this needs to be between 0 and 31 + private final static double END_GAME_TIME = 120 - 30; + + private SparkFunLEDStick ledStick; + + @Override + public void init() { + ledStick = hardwareMap.get(SparkFunLEDStick.class, "back_leds"); + ledStick.setBrightness(brightness); + ledStick.setColor(Color.GREEN); + } + + @Override + public void start() { + resetRuntime(); + } + + @Override + public void loop() { + telemetry.addLine("Hold the A button to turn blue"); + telemetry.addLine("Hold the B button to turn red"); + telemetry.addLine("Hold the left bumper to turn off"); + telemetry.addLine("Use DPAD Up/Down to change brightness"); + + if (getRuntime() > END_GAME_TIME) { + int[] ledColors = {Color.RED, Color.YELLOW, Color.RED, Color.YELLOW, Color.RED, + Color.YELLOW, Color.RED, Color.YELLOW, Color.RED, Color.YELLOW}; + ledStick.setColors(ledColors); + } else if (gamepad1.a) { + ledStick.setColor(Color.BLUE); + } else if (gamepad1.b) { + ledStick.setColor(Color.RED); + } else if (gamepad1.left_bumper) { + ledStick.turnAllOff(); + } else { + ledStick.setColor(Color.GREEN); + } + + /* + * Use DPAD up and down to change brightness + */ + int newBrightness = brightness; + if (gamepad1.dpad_up && !wasUp) { + newBrightness = brightness + 1; + } else if (gamepad1.dpad_down && !wasDown) { + newBrightness = brightness - 1; + } + if (newBrightness != brightness) { + brightness = Range.clip(newBrightness, 0, 31); + ledStick.setBrightness(brightness); + } + telemetry.addData("Brightness", brightness); + + wasDown = gamepad1.dpad_down; + wasUp = gamepad1.dpad_up; + } +} diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptMotorBulkRead.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptMotorBulkRead.java index 3bade8b..5439f78 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptMotorBulkRead.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptMotorBulkRead.java @@ -110,7 +110,7 @@ public class ConceptMotorBulkRead extends LinearOpMode { ElapsedTime timer = new ElapsedTime(); - telemetry.addData(">", "Press play to start tests"); + telemetry.addData(">", "Press START to start tests"); telemetry.addData(">", "Test results will update for each access method."); telemetry.update(); waitForStart(); diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptNullOp.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptNullOp.java index 7ea4683..4a887bd 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptNullOp.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptNullOp.java @@ -53,7 +53,7 @@ public class ConceptNullOp extends OpMode { /** * This method will be called repeatedly during the period between when - * the init button is pressed and when the play button is pressed (or the + * the INIT button is pressed and when the START button is pressed (or the * OpMode is stopped). */ @Override @@ -61,7 +61,7 @@ public class ConceptNullOp extends OpMode { } /** - * This method will be called once, when the play button is pressed. + * This method will be called once, when the START button is pressed. */ @Override public void start() { @@ -70,7 +70,7 @@ public class ConceptNullOp extends OpMode { /** * This method will be called repeatedly during the period between when - * the play button is pressed and when the OpMode is stopped. + * the START button is pressed and when the OpMode is stopped. */ @Override public void loop() { diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptRevLED.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptRevLED.java new file mode 100644 index 0000000..9c168d5 --- /dev/null +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptRevLED.java @@ -0,0 +1,78 @@ +/* + Copyright (c) 2024 Alan Smith + 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 Alan Smith 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 FITNESSFOR 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.robotcontroller.external.samples; + +/* + * This OpMode illustrates how to use the REV Digital Indicator + * + * This is a simple way to add the REV Digital Indicator which has a red and green LED. + * (and as you may remember, red + green = yellow so when they are both on you can get yellow) + * + * Why? + * You can use this to show information to the driver. For example, green might be that you can + * pick up more game elements and red would be that you already have the possession limit. + * + * This OpMode assumes that the REV Digital Indicator is setup as 2 Digital Channels named + * front_led_green and front_led_red. (the green should be the lower of the 2 channels it is plugged + * into and the red should be the higher) + * + * Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name. + * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list + * + * You can buy this product here: https://www.revrobotics.com/rev-31-2010/ + */ +import com.qualcomm.robotcore.eventloop.opmode.Disabled; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.LED; + +@TeleOp(name = "Concept: RevLED", group = "Concept") +@Disabled +public class ConceptRevLED extends OpMode { + LED frontLED_red; + LED frontLED_green; + + @Override + public void init() { + frontLED_green = hardwareMap.get(LED.class, "front_led_green"); + frontLED_red = hardwareMap.get(LED.class, "front_led_red"); + } + + @Override + public void loop() { + if (gamepad1.a) { + frontLED_red.on(); + } else { + frontLED_red.off(); + } + if (gamepad1.b) { + frontLED_green.on(); + } else { + frontLED_green.off(); + } + } +} diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptRevSPARKMini.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptRevSPARKMini.java index e710662..798d689 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptRevSPARKMini.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptRevSPARKMini.java @@ -38,8 +38,9 @@ import com.qualcomm.robotcore.util.Range; /* - * This OpMode executes a basic Tank Drive Teleop for a two wheeled robot using two REV SPARKminis. - * To use this example, connect two REV SPARKminis into servo ports on the Expansion Hub. On the + * This OpMode demonstrates a POV Drive system, with commented-out code for a Tank Drive system, + * for a two wheeled robot using two REV SPARKminis. + * To use this example, connect two REV SPARKminis into servo ports on the Control Hub. On the * robot configuration, use the drop down list under 'Servos' to select 'REV SPARKmini Controller' * and name them 'left_drive' and 'right_drive'. * @@ -62,8 +63,7 @@ public class ConceptRevSPARKMini extends LinearOpMode { telemetry.update(); // Initialize the hardware variables. Note that the strings used here as parameters - // to 'get' must correspond to the names assigned during the robot configuration - // step (using the FTC Robot Controller app on the phone). + // to 'get' must correspond to the names assigned during robot configuration. leftDrive = hardwareMap.get(DcMotorSimple.class, "left_drive"); rightDrive = hardwareMap.get(DcMotorSimple.class, "right_drive"); @@ -72,7 +72,7 @@ public class ConceptRevSPARKMini extends LinearOpMode { leftDrive.setDirection(DcMotorSimple.Direction.FORWARD); rightDrive.setDirection(DcMotorSimple.Direction.REVERSE); - // Wait for the game to start (driver presses PLAY) + // Wait for the game to start (driver presses START) waitForStart(); runtime.reset(); diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptSoundsASJava.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptSoundsASJava.java index f0a855f..1ceaa17 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptSoundsASJava.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptSoundsASJava.java @@ -100,7 +100,7 @@ public class ConceptSoundsASJava extends LinearOpMode { telemetry.addData("gold resource", goldFound ? "Found" : "NOT found\n Add gold.wav to /src/main/res/raw" ); telemetry.addData("silver resource", silverFound ? "Found" : "Not found\n Add silver.wav to /src/main/res/raw" ); - // Wait for the game to start (driver presses PLAY) + // Wait for the game to start (driver presses START) telemetry.addData(">", "Press Start to continue"); telemetry.update(); waitForStart(); diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByEncoder_Linear.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByEncoder_Linear.java index be2e218..63293d0 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByEncoder_Linear.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByEncoder_Linear.java @@ -110,7 +110,7 @@ public class RobotAutoDriveByEncoder_Linear extends LinearOpMode { rightDrive.getCurrentPosition()); telemetry.update(); - // Wait for the game to start (driver presses PLAY) + // Wait for the game to start (driver presses START) waitForStart(); // Step through each leg of the path, diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByGyro_Linear.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByGyro_Linear.java index 7885fe4..ab70934 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByGyro_Linear.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByGyro_Linear.java @@ -65,7 +65,7 @@ import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles; * Notes: * * All angles are referenced to the coordinate-frame that is set whenever resetHeading() is called. - * In this sample, the heading is reset when the Start button is touched on the Driver station. + * In this sample, the heading is reset when the Start button is touched on the Driver Station. * Note: It would be possible to reset the heading after each move, but this would accumulate steering errors. * * The angle of movement/rotation is assumed to be a standardized rotation around the robot Z axis, @@ -124,15 +124,15 @@ public class RobotAutoDriveByGyro_Linear extends LinearOpMode { // These constants define the desired driving/control characteristics // They can/should be tweaked to suit the specific robot drive train. static final double DRIVE_SPEED = 0.4; // Max driving speed for better distance accuracy. - static final double TURN_SPEED = 0.2; // Max Turn speed to limit turn rate + static final double TURN_SPEED = 0.2; // Max turn speed to limit turn rate. static final double HEADING_THRESHOLD = 1.0 ; // How close must the heading get to the target before moving to next step. // Requiring more accuracy (a smaller number) will often make the turn take longer to get into the final position. // Define the Proportional control coefficient (or GAIN) for "heading control". // We define one value when Turning (larger errors), and the other is used when Driving straight (smaller errors). - // Increase these numbers if the heading does not corrects strongly enough (eg: a heavy robot or using tracks) + // Increase these numbers if the heading does not correct strongly enough (eg: a heavy robot or using tracks) // Decrease these numbers if the heading does not settle on the correct value (eg: very agile robot with omni wheels) - static final double P_TURN_GAIN = 0.02; // Larger is more responsive, but also less stable - static final double P_DRIVE_GAIN = 0.03; // Larger is more responsive, but also less stable + static final double P_TURN_GAIN = 0.02; // Larger is more responsive, but also less stable. + static final double P_DRIVE_GAIN = 0.03; // Larger is more responsive, but also less stable. @Override @@ -317,7 +317,7 @@ public class RobotAutoDriveByGyro_Linear extends LinearOpMode { *

* Move will stop once the requested time has elapsed *

- * This function is useful for giving the robot a moment to stabilize it's heading between movements. + * This function is useful for giving the robot a moment to stabilize its heading between movements. * * @param maxTurnSpeed Maximum differential turn speed (range 0 to +1.0) * @param heading Absolute Heading Angle (in Degrees) relative to last gyro reset. diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByTime_Linear.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByTime_Linear.java index b449258..a714748 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByTime_Linear.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveByTime_Linear.java @@ -85,10 +85,10 @@ public class RobotAutoDriveByTime_Linear extends LinearOpMode { telemetry.addData("Status", "Ready to run"); // telemetry.update(); - // Wait for the game to start (driver presses PLAY) + // Wait for the game to start (driver presses START) waitForStart(); - // Step through each leg of the path, ensuring that the Auto mode has not been stopped along the way + // Step through each leg of the path, ensuring that the OpMode has not been stopped along the way. // Step 1: Drive forward for 3 seconds leftDrive.setPower(FORWARD_SPEED); diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToAprilTagOmni.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToAprilTagOmni.java index 21def8a..9bac006 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToAprilTagOmni.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToAprilTagOmni.java @@ -64,7 +64,7 @@ import java.util.concurrent.TimeUnit; * The code assumes a Robot Configuration with motors named: leftfront_drive and rightfront_drive, leftback_drive and rightback_drive. * The motor directions must be set so a positive power goes forward on all wheels. * This sample assumes that the current game AprilTag Library (usually for the current season) is being loaded by default, - * so you should choose to approach a valid tag ID (usually starting at 0) + * so you should choose to approach a valid tag ID. * * Under manual control, the left stick will move forward/back & left/right. The right stick will rotate the robot. * Manually drive the robot until it displays Target data on the Driver Station. @@ -95,12 +95,12 @@ public class RobotAutoDriveToAprilTagOmni extends LinearOpMode // Set the GAIN constants to control the relationship between the measured position error, and how much power is // applied to the drive motors to correct the error. // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. - final double SPEED_GAIN = 0.02 ; // Forward Speed Control "Gain". eg: Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) - final double STRAFE_GAIN = 0.015 ; // Strafe Speed Control "Gain". eg: Ramp up to 25% power at a 25 degree Yaw error. (0.25 / 25.0) - final double TURN_GAIN = 0.01 ; // Turn Control "Gain". eg: Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) + final double SPEED_GAIN = 0.02 ; // Forward Speed Control "Gain". e.g. Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) + final double STRAFE_GAIN = 0.015 ; // Strafe Speed Control "Gain". e.g. Ramp up to 37% power at a 25 degree Yaw error. (0.375 / 25.0) + final double TURN_GAIN = 0.01 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) final double MAX_AUTO_SPEED = 0.5; // Clip the approach speed to this max value (adjust for your robot) - final double MAX_AUTO_STRAFE= 0.5; // Clip the approach speed to this max value (adjust for your robot) + final double MAX_AUTO_STRAFE= 0.5; // Clip the strafing speed to this max value (adjust for your robot) final double MAX_AUTO_TURN = 0.3; // Clip the turn speed to this max value (adjust for your robot) private DcMotor leftFrontDrive = null; // Used to control the left front drive wheel @@ -145,7 +145,7 @@ public class RobotAutoDriveToAprilTagOmni extends LinearOpMode // Wait for driver to press start telemetry.addData("Camera preview on/off", "3 dots, Camera Stream"); - telemetry.addData(">", "Touch Play to start OpMode"); + telemetry.addData(">", "Touch START to start OpMode"); telemetry.update(); waitForStart(); @@ -259,7 +259,7 @@ public class RobotAutoDriveToAprilTagOmni extends LinearOpMode aprilTag = new AprilTagProcessor.Builder().build(); // Adjust Image Decimation to trade-off detection-range for detection-rate. - // eg: Some typical detection data using a Logitech C920 WebCam + // e.g. Some typical detection data using a Logitech C920 WebCam // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToAprilTagTank.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToAprilTagTank.java index 58bbaa6..ba3eb4f 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToAprilTagTank.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToAprilTagTank.java @@ -63,7 +63,7 @@ import java.util.concurrent.TimeUnit; * The code assumes a Robot Configuration with motors named left_drive and right_drive. * The motor directions must be set so a positive power goes forward on both wheels; * This sample assumes that the default AprilTag Library (usually for the current season) is being loaded by default - * so you should choose to approach a valid tag ID (usually starting at 0) + * so you should choose to approach a valid tag ID. * * Under manual control, the left stick will move forward/back, and the right stick will rotate the robot. * This is called POV Joystick mode, different than Tank Drive (where each joystick controls a wheel). @@ -94,8 +94,8 @@ public class RobotAutoDriveToAprilTagTank extends LinearOpMode // Set the GAIN constants to control the relationship between the measured position error, and how much power is // applied to the drive motors to correct the error. // Drive = Error * Gain Make these values smaller for smoother control, or larger for a more aggressive response. - final double SPEED_GAIN = 0.02 ; // Speed Control "Gain". eg: Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) - final double TURN_GAIN = 0.01 ; // Turn Control "Gain". eg: Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) + final double SPEED_GAIN = 0.02 ; // Speed Control "Gain". e.g. Ramp up to 50% power at a 25 inch error. (0.50 / 25.0) + final double TURN_GAIN = 0.01 ; // Turn Control "Gain". e.g. Ramp up to 25% power at a 25 degree error. (0.25 / 25.0) final double MAX_AUTO_SPEED = 0.5; // Clip the approach speed to this max value (adjust for your robot) final double MAX_AUTO_TURN = 0.25; // Clip the turn speed to this max value (adjust for your robot) @@ -135,7 +135,7 @@ public class RobotAutoDriveToAprilTagTank extends LinearOpMode // Wait for the driver to press Start telemetry.addData("Camera preview on/off", "3 dots, Camera Stream"); - telemetry.addData(">", "Touch Play to start OpMode"); + telemetry.addData(">", "Touch START to start OpMode"); telemetry.update(); waitForStart(); @@ -234,7 +234,7 @@ public class RobotAutoDriveToAprilTagTank extends LinearOpMode aprilTag = new AprilTagProcessor.Builder().build(); // Adjust Image Decimation to trade-off detection-range for detection-rate. - // eg: Some typical detection data using a Logitech C920 WebCam + // e.g. Some typical detection data using a Logitech C920 WebCam // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToLine_Linear.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToLine_Linear.java index e5076c0..780f260 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToLine_Linear.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotAutoDriveToLine_Linear.java @@ -106,7 +106,7 @@ public class RobotAutoDriveToLine_Linear extends LinearOpMode { // A gain of 15 causes a Rev Color Sensor V2 to produce an Alpha value of 1.0 at about 1.5" above the floor. colorSensor.setGain(15); - // Wait for driver to press PLAY) + // Wait for driver to press START) // Abort this loop is started or stopped. while (opModeInInit()) { diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotTeleopPOV_Linear.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotTeleopPOV_Linear.java index 454d5a7..af3840d 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotTeleopPOV_Linear.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotTeleopPOV_Linear.java @@ -96,10 +96,10 @@ public class RobotTeleopPOV_Linear extends LinearOpMode { rightClaw.setPosition(MID_SERVO); // Send telemetry message to signify robot waiting; - telemetry.addData(">", "Robot Ready. Press Play."); // + telemetry.addData(">", "Robot Ready. Press START."); // telemetry.update(); - // Wait for the game to start (driver presses PLAY) + // Wait for the game to start (driver presses START) waitForStart(); // run until the end of the match (driver presses STOP) diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotTeleopTank_Iterative.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotTeleopTank_Iterative.java index b9f4fcf..a622f27 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotTeleopTank_Iterative.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotTeleopTank_Iterative.java @@ -94,25 +94,25 @@ public class RobotTeleopTank_Iterative extends OpMode{ rightClaw.setPosition(MID_SERVO); // Send telemetry message to signify robot waiting; - telemetry.addData(">", "Robot Ready. Press Play."); // + telemetry.addData(">", "Robot Ready. Press START."); // } /* - * Code to run REPEATEDLY after the driver hits INIT, but before they hit PLAY + * Code to run REPEATEDLY after the driver hits INIT, but before they hit START */ @Override public void init_loop() { } /* - * Code to run ONCE when the driver hits PLAY + * Code to run ONCE when the driver hits START */ @Override public void start() { } /* - * Code to run REPEATEDLY after the driver hits PLAY but before they hit STOP + * Code to run REPEATEDLY after the driver hits START but before they hit STOP */ @Override public void loop() { diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorHuskyLens.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorHuskyLens.java index 1ec1f55..af7ca55 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorHuskyLens.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorHuskyLens.java @@ -33,13 +33,10 @@ THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. package org.firstinspires.ftc.robotcontroller.external.samples; import com.qualcomm.hardware.dfrobot.HuskyLens; -import com.qualcomm.hardware.rev.Rev2mDistanceSensor; import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; -import com.qualcomm.robotcore.hardware.DistanceSensor; -import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; import org.firstinspires.ftc.robotcore.internal.system.Deadline; import java.util.concurrent.TimeUnit; @@ -51,6 +48,9 @@ import java.util.concurrent.TimeUnit; * detect a number of predefined objects and AprilTags in the 36h11 family, can * recognize colors, and can be trained to detect custom objects. See this website for * documentation: https://wiki.dfrobot.com/HUSKYLENS_V1.0_SKU_SEN0305_SEN0336 + * + * For detailed instructions on how a HuskyLens is used in FTC, please see this tutorial: + * https://ftc-docs.firstinspires.org/en/latest/devices/huskylens/huskylens.html * * This sample illustrates how to detect AprilTags, but can be used to detect other types * of objects by changing the algorithm. It assumes that the HuskyLens is configured with @@ -110,6 +110,8 @@ public class SensorHuskyLens extends LinearOpMode { * Users, should, in general, explicitly choose the algorithm they want to use * within the OpMode by calling selectAlgorithm() and passing it one of the values * found in the enumeration HuskyLens.Algorithm. + * + * Other algorithm choices for FTC might be: OBJECT_RECOGNITION, COLOR_RECOGNITION or OBJECT_CLASSIFICATION. */ huskyLens.selectAlgorithm(HuskyLens.Algorithm.TAG_RECOGNITION); @@ -141,6 +143,15 @@ public class SensorHuskyLens extends LinearOpMode { telemetry.addData("Block count", blocks.length); for (int i = 0; i < blocks.length; i++) { telemetry.addData("Block", blocks[i].toString()); + /* + * Here inside the FOR loop, you could save or evaluate specific info for the currently recognized Bounding Box: + * - blocks[i].width and blocks[i].height (size of box, in pixels) + * - blocks[i].left and blocks[i].top (edges of box) + * - blocks[i].x and blocks[i].y (center location) + * - blocks[i].id (Color ID) + * + * These values have Java type int (integer). + */ } telemetry.update(); diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorIMUNonOrthogonal.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorIMUNonOrthogonal.java index eb1c7ca..70bc8d4 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorIMUNonOrthogonal.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorIMUNonOrthogonal.java @@ -58,7 +58,7 @@ import static com.qualcomm.hardware.rev.RevHubOrientationOnRobot.xyzOrientation; * planes (X/Y, X/Z or Y/Z) OR that the Hub has only been rotated in a range of 90 degree increments. * * Note: if your Hub is mounted Orthogonally (on a orthogonal surface, angled at some multiple of - * 90 Degrees) then you should use the simpler SensorImuOrthogonal sample in this folder. + * 90 Degrees) then you should use the simpler SensorIMUOrthogonal sample in this folder. * * But... If your Hub is mounted Non-Orthogonally, you must specify one or more rotational angles * that transform a "Default" Hub orientation into your desired orientation. That is what is @@ -94,6 +94,9 @@ public class SensorIMUNonOrthogonal extends LinearOpMode * 1) Hub laying flat on a horizontal surface, with the Printed Logo facing UP * 2) Rotated such that the USB ports are facing forward on the robot. * + * If you are using a REV External IMU, the "Default" orientation is the same as for a REV Hub, but instead of + * the USB ports facing forward, the I2C port faces forward. + * * The order that the rotations are performed matters, so this sample shows doing them in the order X, Y, then Z. * For specifying non-orthogonal hub mounting orientations, we must temporarily use axes * defined relative to the Hub itself, instead of the usual Robot Coordinate System axes @@ -124,7 +127,7 @@ public class SensorIMUNonOrthogonal extends LinearOpMode * * To get the "Default" hub into this configuration you would just need a single rotation, but around a different axis. * 1) No rotation around the X or Y axes. - * 1) Rotate the Hub -30 degrees (Clockwise) around the Z axis, since a positive angle would be Counter Clockwise. + * 2) Rotate the Hub -30 degrees (Clockwise) around the Z axis, since a positive angle would be Counter Clockwise. * * So the X,Y,Z rotations would be 0,0,-30 * diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorIMUOrthogonal.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorIMUOrthogonal.java index d92ce3e..af4c202 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorIMUOrthogonal.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorIMUOrthogonal.java @@ -55,7 +55,7 @@ import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles; * (X/Y, X/Z or Y/Z) and that the Hub has only been rotated in a range of 90 degree increments. * * Note: if your Hub is mounted on a surface angled at some non-90 Degree multiple (like 30) look at - * the alternative SensorImuNonOrthogonal sample in this folder. + * the alternative SensorIMUNonOrthogonal sample in this folder. * * This "Orthogonal" requirement means that: * @@ -98,6 +98,9 @@ public class SensorIMUOrthogonal extends LinearOpMode * The first parameter specifies the direction the printed logo on the Hub is pointing. * The second parameter specifies the direction the USB connector on the Hub is pointing. * All directions are relative to the robot, and left/right is as-viewed from behind the robot. + * + * If you are using a REV 9-Axis IMU, you can use the Rev9AxisImuOrientationOnRobot class instead of the + * RevHubOrientationOnRobot class, which has an I2cPortFacingDirection instead of a UsbFacingDirection. */ /* The next two lines define Hub orientation. diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorLimelight3A.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorLimelight3A.java new file mode 100644 index 0000000..6c1f702 --- /dev/null +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorLimelight3A.java @@ -0,0 +1,159 @@ +/* +Copyright (c) 2024 Limelight Vision + +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.robotcontroller.external.samples; + +import com.qualcomm.hardware.limelightvision.LLResult; +import com.qualcomm.hardware.limelightvision.LLResultTypes; +import com.qualcomm.hardware.limelightvision.LLStatus; +import com.qualcomm.hardware.limelightvision.Limelight3A; +import com.qualcomm.robotcore.eventloop.opmode.Disabled; +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; + +import org.firstinspires.ftc.robotcore.external.navigation.Pose3D; + +import java.util.List; + +/* + * This OpMode illustrates how to use the Limelight3A Vision Sensor. + * + * @see Limelight + * + * Notes on configuration: + * + * The device presents itself, when plugged into a USB port on a Control Hub as an ethernet + * interface. A DHCP server running on the Limelight automatically assigns the Control Hub an + * ip address for the new ethernet interface. + * + * Since the Limelight is plugged into a USB port, it will be listed on the top level configuration + * activity along with the Control Hub Portal and other USB devices such as webcams. Typically + * serial numbers are displayed below the device's names. In the case of the Limelight device, the + * Control Hub's assigned ip address for that ethernet interface is used as the "serial number". + * + * Tapping the Limelight's name, transitions to a new screen where the user can rename the Limelight + * and specify the Limelight's ip address. Users should take care not to confuse the ip address of + * the Limelight itself, which can be configured through the Limelight settings page via a web browser, + * and the ip address the Limelight device assigned the Control Hub and which is displayed in small text + * below the name of the Limelight on the top level configuration screen. + */ +@TeleOp(name = "Sensor: Limelight3A", group = "Sensor") +@Disabled +public class SensorLimelight3A extends LinearOpMode { + + private Limelight3A limelight; + + @Override + public void runOpMode() throws InterruptedException + { + limelight = hardwareMap.get(Limelight3A.class, "limelight"); + + telemetry.setMsTransmissionInterval(11); + + limelight.pipelineSwitch(0); + + /* + * Starts polling for data. If you neglect to call start(), getLatestResult() will return null. + */ + limelight.start(); + + telemetry.addData(">", "Robot Ready. Press Play."); + telemetry.update(); + waitForStart(); + + while (opModeIsActive()) { + LLStatus status = limelight.getStatus(); + telemetry.addData("Name", "%s", + status.getName()); + telemetry.addData("LL", "Temp: %.1fC, CPU: %.1f%%, FPS: %d", + status.getTemp(), status.getCpu(),(int)status.getFps()); + telemetry.addData("Pipeline", "Index: %d, Type: %s", + status.getPipelineIndex(), status.getPipelineType()); + + LLResult result = limelight.getLatestResult(); + if (result != null) { + // Access general information + Pose3D botpose = result.getBotpose(); + double captureLatency = result.getCaptureLatency(); + double targetingLatency = result.getTargetingLatency(); + double parseLatency = result.getParseLatency(); + telemetry.addData("LL Latency", captureLatency + targetingLatency); + telemetry.addData("Parse Latency", parseLatency); + telemetry.addData("PythonOutput", java.util.Arrays.toString(result.getPythonOutput())); + + if (result.isValid()) { + telemetry.addData("tx", result.getTx()); + telemetry.addData("txnc", result.getTxNC()); + telemetry.addData("ty", result.getTy()); + telemetry.addData("tync", result.getTyNC()); + + telemetry.addData("Botpose", botpose.toString()); + + // Access barcode results + List barcodeResults = result.getBarcodeResults(); + for (LLResultTypes.BarcodeResult br : barcodeResults) { + telemetry.addData("Barcode", "Data: %s", br.getData()); + } + + // Access classifier results + List classifierResults = result.getClassifierResults(); + for (LLResultTypes.ClassifierResult cr : classifierResults) { + telemetry.addData("Classifier", "Class: %s, Confidence: %.2f", cr.getClassName(), cr.getConfidence()); + } + + // Access detector results + List detectorResults = result.getDetectorResults(); + for (LLResultTypes.DetectorResult dr : detectorResults) { + telemetry.addData("Detector", "Class: %s, Area: %.2f", dr.getClassName(), dr.getTargetArea()); + } + + // Access fiducial results + List fiducialResults = result.getFiducialResults(); + for (LLResultTypes.FiducialResult fr : fiducialResults) { + telemetry.addData("Fiducial", "ID: %d, Family: %s, X: %.2f, Y: %.2f", fr.getFiducialId(), fr.getFamily(),fr.getTargetXDegrees(), fr.getTargetYDegrees()); + } + + // Access color results + List colorResults = result.getColorResults(); + for (LLResultTypes.ColorResult cr : colorResults) { + telemetry.addData("Color", "X: %.2f, Y: %.2f", cr.getTargetXDegrees(), cr.getTargetYDegrees()); + } + } + } else { + telemetry.addData("Limelight", "No data available"); + } + + telemetry.update(); + } + limelight.stop(); + } +} diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuad.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuad.java index 71adee0..f797c6b 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuad.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuad.java @@ -52,7 +52,7 @@ import org.firstinspires.ftc.robotcore.external.Telemetry; * Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name. * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list * - * See the sensor's product page: https://www.tindie.com/products/digitalchickenlabs/octoquad-8ch-quadrature-pulse-width-decoder/ + * See the sensor's product page: https://www.tindie.com/products/35114/ */ @TeleOp(name = "OctoQuad Basic", group="OctoQuad") @Disabled @@ -60,7 +60,7 @@ public class SensorOctoQuad extends LinearOpMode { // Identify which encoder OctoQuad inputs are connected to each odometry pod. private final int ODO_LEFT = 0; // Facing forward direction on left side of robot (Axial motion) - private final int ODO_RIGHT = 1; // Facing forward direction on right side or robot (Axial motion ) + private final int ODO_RIGHT = 1; // Facing forward direction on right side or robot (Axial motion) private final int ODO_PERP = 2; // Facing perpendicular direction at the center of the robot (Lateral motion) // Declare the OctoQuad object and members to store encoder positions and velocities @@ -83,7 +83,7 @@ public class SensorOctoQuad extends LinearOpMode { telemetry.addData("OctoQuad Firmware Version ", octoquad.getFirmwareVersion()); // Reverse the count-direction of any encoder that is not what you require. - // Eg: if you push the robot forward and the left encoder counts down, then reverse it so it counts up. + // e.g. if you push the robot forward and the left encoder counts down, then reverse it so it counts up. octoquad.setSingleEncoderDirection(ODO_LEFT, OctoQuad.EncoderDirection.REVERSE); octoquad.setSingleEncoderDirection(ODO_RIGHT, OctoQuad.EncoderDirection.FORWARD); octoquad.setSingleEncoderDirection(ODO_PERP, OctoQuad.EncoderDirection.FORWARD); @@ -91,7 +91,7 @@ public class SensorOctoQuad extends LinearOpMode { // Any changes that are made should be saved in FLASH just in case there is a sensor power glitch. octoquad.saveParametersToFlash(); - telemetry.addLine("\nPress Play to read encoder values"); + telemetry.addLine("\nPress START to read encoder values"); telemetry.update(); waitForStart(); @@ -100,23 +100,23 @@ public class SensorOctoQuad extends LinearOpMode { telemetry.setDisplayFormat(Telemetry.DisplayFormat.MONOSPACE); telemetry.setMsTransmissionInterval(50); - // Set all the encoder inputs to zero + // Set all the encoder inputs to zero. octoquad.resetAllPositions(); // Loop while displaying the odometry pod positions. while (opModeIsActive()) { telemetry.addData(">", "Press X to Reset Encoders\n"); - // Check for X button to reset encoders + // Check for X button to reset encoders. if (gamepad1.x) { // Reset the position of all encoders to zero. octoquad.resetAllPositions(); } - // Read all the encoder data. Load into local members + // Read all the encoder data. Load into local members. readOdometryPods(); - // Display the values + // Display the values. telemetry.addData("Left ", "%8d counts", posLeft); telemetry.addData("Right", "%8d counts", posRight); telemetry.addData("Perp ", "%8d counts", posPerp); @@ -131,11 +131,11 @@ public class SensorOctoQuad extends LinearOpMode { // or // readAllPositions() to get all 8 encoder readings // - // Since both calls take almost the same amount of time, and the actual channels may not end up being sequential, - // we will read all of the encoder positions, and then pick out the ones we need. + // Since both calls take almost the same amount of time, and the actual channels may not end up + // being sequential, we will read all of the encoder positions, and then pick out the ones we need. int[] positions = octoquad.readAllPositions(); posLeft = positions[ODO_LEFT]; posRight = positions[ODO_RIGHT]; posPerp = positions[ODO_PERP]; } -} \ No newline at end of file +} diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuadAdv.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuadAdv.java index c87c05a..e763b9a 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuadAdv.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/SensorOctoQuadAdv.java @@ -77,7 +77,7 @@ import java.util.List; * Note: If you prefer, you can move the two support classes from this file, and place them in their own files. * But leaving them in place is simpler for this example. * - * See the sensor's product page: https://www.tindie.com/products/digitalchickenlabs/octoquad-8ch-quadrature-pulse-width-decoder/ + * See the sensor's product page: https://www.tindie.com/products/35114/ */ @TeleOp(name="OctoQuad Advanced", group="OctoQuad") @Disabled @@ -93,7 +93,7 @@ public class SensorOctoQuadAdv extends LinearOpMode { // Display the OctoQuad firmware revision telemetry.addLine("OctoQuad Firmware v" + octoquad.getFirmwareVersion()); - telemetry.addLine("\nPress Play to read encoder values"); + telemetry.addLine("\nPress START to read encoder values"); telemetry.update(); waitForStart(); @@ -275,4 +275,4 @@ class OctoSwerveModule { public void show(Telemetry telemetry) { telemetry.addData(name, "%8.0f %7.0f %7.0f %6.0f", driveCounts, driveCountsPerSec, steerDegrees, steerDegreesPerSec); } -} \ No newline at end of file +} diff --git a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/UtilityOctoQuadConfigMenu.java b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/UtilityOctoQuadConfigMenu.java index 2fd47fb..a962919 100644 --- a/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/UtilityOctoQuadConfigMenu.java +++ b/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/UtilityOctoQuadConfigMenu.java @@ -446,7 +446,7 @@ public class UtilityOctoQuadConfigMenu extends LinearOpMode StringBuilder builder = new StringBuilder(); builder.append(""); builder.append("Navigate items.....dpad up/down\n") - .append("Select.............X\n") + .append("Select.............X or Square\n") .append("Edit option........dpad left/right\n") .append("Up one level.......left bumper\n"); builder.append(""); @@ -614,7 +614,7 @@ public class UtilityOctoQuadConfigMenu extends LinearOpMode @Override public void onClick() { - onRightInput(); + //onRightInput(); } @Override @@ -669,7 +669,7 @@ public class UtilityOctoQuadConfigMenu extends LinearOpMode @Override public void onClick() { - onRightInput(); + //onRightInput(); } @Override diff --git a/README.md b/README.md index 25b8560..5353afb 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,1553 @@ -# Road Runner Quickstart +## NOTICE -Check out the [docs](https://rr.brott.dev/docs/v1-0/tuning/). +This repository contains the public FTC SDK for the INTO THE DEEP (2024-2025) competition season. +## Welcome! +This GitHub repository contains the source code that is used to build an Android app to control a *FIRST* Tech Challenge competition robot. To use this SDK, download/clone the entire project to your local computer. + +## Requirements +To use this Android Studio project, you will need Android Studio 2021.2 (codename Chipmunk) or later. + +To program your robot in Blocks or OnBot Java, you do not need Android Studio. + +## Getting Started +If you are new to robotics or new to the *FIRST* Tech Challenge, then you should consider reviewing the [FTC Blocks Tutorial](https://ftc-docs.firstinspires.org/programming_resources/blocks/Blocks-Tutorial.html) to get familiar with how to use the control system: + +      [FTC Blocks Online Tutorial](https://ftc-docs.firstinspires.org/programming_resources/blocks/Blocks-Tutorial.html) + +Even if you are an advanced Java programmer, it is helpful to start with the [FTC Blocks tutorial](https://ftc-docs.firstinspires.org/programming_resources/blocks/Blocks-Tutorial.html), and then migrate to the [OnBot Java Tool](https://ftc-docs.firstinspires.org/programming_resources/onbot_java/OnBot-Java-Tutorial.html) or to [Android Studio](https://ftc-docs.firstinspires.org/programming_resources/android_studio_java/Android-Studio-Tutorial.html) afterwards. + +## Downloading the Project +If you are an Android Studio programmer, there are several ways to download this repo. Note that if you use the Blocks or OnBot Java Tool to program your robot, then you do not need to download this repository. + +* If you are a git user, you can clone the most current version of the repository: + +

            git clone https://github.com/FIRST-Tech-Challenge/FtcRobotController.git

+ +* Or, if you prefer, you can use the "Download Zip" button available through the main repository page. Downloading the project as a .ZIP file will keep the size of the download manageable. + +* You can also download the project folder (as a .zip or .tar.gz archive file) from the Downloads subsection of the [Releases](https://github.com/FIRST-Tech-Challenge/FtcRobotController/releases) page for this repository. + +* The Releases page also contains prebuilt APKs. + +Once you have downloaded and uncompressed (if needed) your folder, you can use Android Studio to import the folder ("Import project (Eclipse ADT, Gradle, etc.)"). + +## Getting Help +### User Documentation and Tutorials +*FIRST* maintains online documentation with information and tutorials on how to use the *FIRST* Tech Challenge software and robot control system. You can access this documentation using the following link: + +      [FIRST Tech Challenge Documentation](https://ftc-docs.firstinspires.org/index.html) + +Note that the online documentation is an "evergreen" document that is constantly being updated and edited. It contains the most current information about the *FIRST* Tech Challenge software and control system. + +### Javadoc Reference Material +The Javadoc reference documentation for the FTC SDK is now available online. Click on the following link to view the FTC SDK Javadoc documentation as a live website: + +      [FTC Javadoc Documentation](https://javadoc.io/doc/org.firstinspires.ftc) + +### Online User Forum +For technical questions regarding the Control System or the FTC SDK, please visit the FIRST Tech Challenge Community site: + +      [FIRST Tech Challenge Community](https://ftc-community.firstinspires.org/) + +### Sample OpModes +This project contains a large selection of Sample OpModes (robot code examples) which can be cut and pasted into your /teamcode folder to be used as-is, or modified to suit your team's needs. + +Samples Folder:    [/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples](FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples) + +The readme.md file located in the [/TeamCode/src/main/java/org/firstinspires/ftc/teamcode](TeamCode/src/main/java/org/firstinspires/ftc/teamcode) folder contains an explanation of the sample naming convention, and instructions on how to copy them to your own project space. + +# Release Information + +## Version 10.0 (20240828-111152) + +### Breaking Changes +* Java classes and Blocks for TensorFlow Object Detection have been removed. +* `AngularVelocity.unit` which was of type `AngleUnit` has been renamed `AngularVelocity.angleUnit` of type `UnnormalizedAngleUnit` + +### Enhancements +* Sample for REV Digital Indicator has been added - ConceptRevLED +* Adds support for the [Sparkfun QWIIC LED Stick](https://www.sparkfun.com/products/18354) + * To connect it directly, you need this [cable](https://www.sparkfun.com/products/25596) +* Adds ConceptLEDStick OpMode +* Adds Blocks for colors black, blue, cyan, dkgray, gray, green, ltgray, magenta, red, white, and yellow. +* Adds an "evaluate but ignore result" Block that executes the connected block and ignores the result. Allows you to call a function and ignore the return value. +* Adds I2C driver for Maxbotix Maxsonar I2CXL sonar rangefinder +* Adds Blocks for setPwmEnable, setPwmDisable, and isPwmEnabled for servos and CR servos. +* In the Blocks editor: a \n in the ExportToBlocks annotation's comment field is displayed as a line break. +* Telemetry has new method setNumDecimalPlaces +* Telemetry now formats doubles and floats (not inside objects, just by themselves) +* Adds support for the Limelight 3A. +* Adds initial support for the REV Servo Hub + * Both the Robot Controller and Driver Station need to be updated to version 10.0 in order for Servo Hubs to be + configurable as Servo Hubs. If the app on either device is outdated, the Servo Hub will show up as an Expansion Hub, + and some functionality will not work as expected. You should wait to create a configuration that includes a Servo Hub + until both the Driver Station and Robot Controller apps have been updated to version 10.0. + * Updating the Servo Hub's firmware and changing its address can only be done using the REV Hardware Client at this time +* Adds support for the REV 9-Axis IMU (REV-31-3332) + * The REV 9-Axis IMU is only supported by the [Universal IMU interface](https://ftc-docs.firstinspires.org/en/latest/programming_resources/imu/imu.html) + * Adds `Rev9AxisImuOrientationOnRobot` Java class. + * If you mentally substitute this IMU's I2C port for the Control Hub's USB ports, `RevHubOrientationOnRobot` is also compatible with this sensor + * Adds Blocks for Rev9AxisImuOrientationOnRobot, including RevHubImuOrientationOnRobot.xyzOrientation and RevHubImuOrientationOnRobot.zyxOrientation. + * Adds Blocks samples SensorRev9AxisIMUOrthogonal and SensorRev9AxisIMUNonOrthogonal. +* Improves Blocks support for RevHubImuOrientationOnRobot. + * Adds Blocks for RevHubImuOrientationOnRobot.xyzOrientation and RevHubImuOrientationOnRobot.zyxOrientation. + * Adds Blocks samples SensorHubIMUOrthogonal (replaces SensorIMU) and SensorHubIMUNonOrthogonal. +* Updates EasyOpenCV, AprilTag, OpenCV, and `libjpeg-turbo` versions +* Adds Blocks for max and min that take two numbers. +* Adds Blocks OpModes ConceptRevSPARKMini, RobotAutoDriveByEncoder, RobotAutoDriveByGyro, RobotAutoDriveByTime, RobotAutoDriveToAprilTagOmni, and RobotAutoDriveToAprilTagTank. +* Two OpModes with the same name now automatically get renamed with the name followed by a "-" and the class name allowing them to both be on the device. +* Shows the name of the active configuration on the Manage page of the Robot Controller Console +* Updated AprilTag Library for INTO THE DEEP. Notably, `getCurrentGameTagLibrary()` now returns INTO THE DEEP tags. +* Adds Blocks for Telemetry.setMsTransmissionInterval and Telemetry.getMsTransmissionInterval. +* Adds Blocks sample SensorOctoQuad. + +### Bug Fixes +* Fixes a bug where the RevBlinkinLedDriver Blocks were under Actuators in the Blocks editor toolbox. They are now Other Devices. +* Fixes a bug where `Exception`s thrown in user code after a stop was requested by the Driver Station would be silently eaten +* Fixed a bug where if you asked for `AngularVelocity` in a unit different than the device reported it in, it would normalize it between -PI and PI for radians, and -180 and 180 for degrees. + +## Version 9.2 (20240701-085519) + +### Important Notes +* Java classes and Blocks for TensorFlow Object Detection have been deprecated and will be removed in Version 10.0. +* The samples that use TensorFlow Object Detection have been removed. + +### Enhancements +* Adds explanatory text to failed items on the inspection activities. To view the explanatory text tap the red warning icon for a failed item. +* In the Blocks editor: added a new kind of variable set block that sets the variable and also returns the new value. +* Changes the way that camera controls behave for a SwitchableCamera. Now, each method (such as getExposure, getMinExposure, getMaxExposure, setExposure for ExposureControl) acts on the currently active camera. +* Adds support for the REV USB PS4 Compatible Gamepad (REV-31-2983) +* Adds ConceptAprilTagMultiPortal OpMode +* Adds support for OctoQuad Quadrature Encoder & Pulse Width Interface Module +* Adds the ExportAprilTagLibraryToBlocks annotation that indicates that a static method that returns an AprilTagLibrary is exported to the Blocks programming environment. The corresponding block will appear in the Blocks toolbox along with the built-in tag libraries. +* Adds Blocks OpMode ConceptAprilTagOptimizeExposure. +* Adds support for the SparkFun Optical Tracking Odometry sensor. + +### Bug Fixes +* Fixes https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/942 where visionPortal.close() can cause an IndexOutOfBoundsError. +* Fixes a bug in the blocks editor where collapsed function blocks show a warning "Collapsed blocks contain warnings." when the Blocks OpMode is reopened. +* Fixes a bug where the blocks editor wouldn't warn you that you have unsaved changes when you try to leave. This bug was introduced due to a behavior change in Chrome 119. +* [Issue #764](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/764) - Get gain control returns a null pointer for a switchable camera +* Fixes a bug where the correct deadzone for certain gamepads was not applied when Advanced Gamepad Features was enabled + +## Version 9.1 (20240215-115542) + +### Enhancements +* Fixes a problem with Blocks: if the user closes a Block's warning balloon, it will still be closed next time the project is opened in the Blocks editor. +* In the Blocks editor, an alert concerning missing hardware devices is not shown if all the Blocks that use the missing hardware devices are disabled. +* Adds Blocks to support comparing property values CRServo.Direction, DCMotor.Direction, DCMotor.Mode, DCMotor.ZeroPowerBehavior, DigitalChannel.Mode, GyroSensor.HeadingMode, IrSeekerSensor.Mode, and Servo.Direction, to the corresponding enum Block. +* Improves OnBotJava auto-import to correctly import classes when used in certain situations. +* Improves OnBotJava autocomplete to provide better completion options in most cases. + * This fixes an issue where autocomplete would fail if a method with two or more formal parameters was defined. +* In OnBotJava, code folding support was added to expand and collapse code sections +* In OnBotJava, the copyright header is now automatically collapsed loading new files +* For all Blocks OpMode samples, intro comments have been moved to the RunOpMode comment balloon. +* The Clean up Blocks command in the Blocks editor now positions function Blocks so their comment balloons don't overlap other function Blocks. +* Added Blocks OpMode sample SensorTouch. +* Added Java OpMode sample SensorDigitalTouch. +* Several improvements to VisionPortal + * Adds option to control whether the stream is automatically started following a `.build()` call on a VisionPortal Builder + * Adds option to control whether the vision processing statistics overlay is rendered or not + * VisionPortals now implement the `CameraStreamSource` interface, allowing multiportal users to select which portal is routed to the DS in INIT by calling CameraStreamServer.getInstance().setSource(visionPortal). Can be selected via gamepad, between Camera Stream sessions. + * Add option to `AprilTagProcessor` to suppress calibration warnings + * Improves camera calibration warnings + * If a calibration is scaled, the resolution it was scaled from will be listed + * If calibrations exist with the wrong aspect ratio, the calibrated resolutions will be listed + * Fixes race condition which caused app crash when calling `stopStreaming()` immediately followed by `close()` on a VisionPortal + * Fixes IllegalStateException when calling `stopStreaming()` immediately after building a VisionPortal + * Added FTC Blocks counterparts to new Java methods: + * VisionPortal.Builder.setAutoStartStreamOnBuild + * VisionPortal.Builder.setShowStatsOverlay + * AprilTagProcessor.Builder.setSuppressCalibrationWarnings + * CameraStreamServer.setSource​ + +### Bug Fixes +* Fixes a problem where OnBotJava does not apply font size settings to the editor. +* Updates EasyOpenCV dependency to v1.7.1 + * Fixes inability to use EasyOpenCV CameraFactory in OnBotJava + * Fixes entire RC app crash when user pipeline throws an exception + * Fixes entire RC app crash when user user canvas annotator throws an exception + * Use the modern stacktrace display when handling user exceptions instead of the legacy ESTOP telemetry message + +## Version 9.0.1 (20230929-083754) + +### Enhancements +* Updates AprilTag samples to include Decimation and additional Comments. Also corrects misleading tag ID warnings +* Increases maximum size of Blocks inline comments to 140 characters +* Adds Blocks sample BasicOmniOpMode. +* Updated CENTERSTAGE library AprilTag orientation quaternions + * Thanks [@FromenActual](https://github.com/FromenActual) +* Updated Java Sample ConceptTensorFlowObjectDetection.java to include missing elements needed for custom model support. + +### Bug Fixes +* Fixes a problem where after October 1 the Driver Station will report as obsolete on v9.0 and prompt the user to update. + +## Version 9.0 (20230830-154348) + +### Breaking Changes +* Removes Vuforia +* Fields in `AprilTagDetection` and `AprilTagPose(ftc/raw)` objects are now `final` +* VisionPortal builder method `setCameraMonitorViewId()` has been renamed to `setLiveViewContainerId()` and `enableCameraMonitoring()` has been renamed to `enableLiveView()` + +### Enhancements +* Adds support for the DFRobot HuskyLens Vision Sensor. +* Blocks teams can now perform webcam calibration. + * Added a Block for System.currentTimeMillis (under Utilities/Time) + * Added a Block for VisionPortal.saveNextFrameRaw (under Vision/VisionPortal) + * Added a new sample Blocks OpMode called UtilityCameraFrameCapture. +* The RobotDriveByGyro sample has been updated to use the new universal IMU interface. It now supports both IMU types. +* Removed some error-prone ElapsedTime Blocks from the Blocks editor's toolbox. This is not a + breaking change: old Blocks OpModes that use these Blocks will still function, both in the + Blocks editor and at runtime. +* Standardizes on the form "OpMode" for the term OpMode. + * The preferred way to refer to OpModes that specifically extend `LinearOpMode` (including Blocks OpModes) is "linear OpMode". + * The preferred way to refer to OpModes that specifically extend `OpMode` directly is "iterative OpMode". +* Overhauls `OpMode` and `LinearOpMode` Javadoc comments to be easier to read and include more detail. +* Makes minor enhancements to Java samples + * Javadoc comments in samples that could be rendered badly in Android Studio have been converted to standard multi-line comments + * Consistency between samples has been improved + * The SensorDigitalTouch sample has been replaced with a new SensorTouch sample that uses the `TouchSensor` interface instead of `DigitalChannel`. + * The ConceptCompassCalibration, SensorMRCompass, and SensorMRIRSeeker samples have been deleted, as they are not useful for modern FTC competitions. + +### Bug Fixes +* Fixes a bug which prevented PlayStation gamepads from being used in bluetooth mode. Bluetooth is NOT legal for competition but may be useful to allow a DS device to be used while charging, or at an outreach event. +* Fixes a bug where a Blocks OpMode's Date Modified value can change to December 31, 1969, if the Control Hub is rebooted while the Blocks OpMode is being edited. +* Fixes the automatic TeleOp preselection feature (was broken in 8.2) +* Fixes a bug where passing an integer number such as 123 to the Telemetry.addData block that takes a number shows up as 123.0 in the telemetry. +* Fixes OnBotJava autocomplete issues: + * Autocomplete would incorrectly provide values for the current class when autocompleting a local variable + * `hardwareMap` autocomplete would incorrectly include lambda class entries +* Fixes OnBotJava not automatically importing classes. +* Fixes OnBotJava tabs failing to close when their file is deleted. +* Fixes a project view refresh not happening when a file is renamed in OnBotJava. +* Fixes the "Download" context menu item for external libraries in the OnBotJava interface. +* Fixes issue where Driver Station telemetry would intermittently freeze when set to Monospace mode. +* Fixes performance regression for certain REV Hub operations that was introduced in version 8.2. +* Fixes TagID comparison logic in DriveToTag samples. + +## Version 8.2 (20230707-131020) + +### Breaking Changes +* Non-linear (iterative) OpModes are no longer allowed to manipulate actuators in their `stop()` method. Attempts to do so will be ignored and logged. + * When an OpMode attempts to illegally manipulate an actuator, the Robot Controller will print a log message + including the text `CANCELLED_FOR_SAFETY`. + * Additionally, LinearOpModes are no longer able to regain the ability to manipulate actuators by removing their + thread's interrupt or using another thread. +* Removes support for Android version 6.0 (Marshmallow). The minSdkVersion is now 24. +* Increases the Robocol version. + * This means an 8.2 or later Robot Controller or Driver Station will not be able to communicate with an 8.1 or earlier Driver Station or Robot Controller. + * If you forget to update both apps at the same time, an error message will be shown explaining which app is older and should be updated. +* FTC_FieldCoordinateSystemDefinition.pdf has been moved. It is still in the git history, but has been removed from the git snapshot corresponding with the 8.2 tag. The official version now lives at [Field Coordinate System](https://ftc-docs.firstinspires.org/field-coordinate-system). +* `LynxUsbDevice.addConfiguredModule()` and `LynxUsbDevice.getConfiguredModule()` have been replaced with `LynxUsbDevice.getOrAddModule()`. +* Old Blocks for Vuforia and TensorFlow Object Detection are obsolete and have been removed from the + Blocks editor's toolbox. Existing Blocks OpModes that contain the old Blocks for Vuforia or + TensorFlow Object Detection can be opened in the Blocks editor, but running them will not work. + +### New features +* Adds new `VisionPortal` API for computer vision + * **This API may be subject to change for final kickoff release!** + * Several new samples added. + * Adds support for detecting AprilTags. + * `VisionPortal` is the new entry point for both AprilTag and TFOD processing. + * Vuforia will be removed in a future release. + * Updated TensorFlow dependencies. + * Added support for webcam camera controls to blocks. + * The Blocks editor's toolbox now has a Vision category, directly above the Utilities category. +* Related documentation for associated technologies can be found at + * [AprilTag Introduction](https://ftc-docs.firstinspires.org/apriltag-intro) + * [AprilTag SDK Guide](https://ftc-docs.firstinspires.org/apriltag-sdk) + * [AprilTag Detection Values](https://ftc-docs.firstinspires.org/apriltag-detection-values) + * [AprilTag Test Images](https://ftc-docs.firstinspires.org/apriltag-test-images) + * [Camera Calibration](https://ftc-docs.firstinspires.org/camera-calibration) +* Adds Driver Station support for Logitech Dual Action and Sony PS5 DualSense gamepads. + * This **does not** include support for the Sony PS5 DualSense Edge gamepad. + * Always refer to Game Manual 1 to determine gamepad legality in competition. +* Adds support for MJPEG payload streaming to UVC driver (external JPEG decompression routine required for use). +* Shows a hint on the Driver Station UI about how to bind a gamepad when buttons are pressed or the sticks are moved on an unbound gamepad. +* Adds option for fullscreening "Camera Stream" on Driver Station. +* OnBotJava source code is automatically saved as a ZIP file on every build with a rolling window of the last 30 builds kept; allows recovering source code from previous builds if code is accidentally deleted or corrupted. +* Adds support for changing the addresses of Expansion Hubs that are not connected directly via USB. + * The Expansion Hub Address Change screen now has an Apply button that changes the addresses without leaving the screen. + * Addresses that are assigned to other hubs connected to the same USB connection or Control Hub are no longer able to be selected. +* Increases maximum size of Blocks inline comments to 100 characters +* Saves position of open Blocks comment balloons +* Adds new AprilTag Driving samples: RobotDriveToAprilTagTank & RobotDriveToAprilTagOmni +* Adds Sample to illustrate optimizing camera exposure for AprilTags: ConceptAprilTagOptimizeExposure + +### Bug Fixes +* Corrects inspection screen to report app version using the SDK version defined in the libraries instead of the version specified in `AndroidManifest.xml`. This corrects the case where the app could show matching versions numbers to the user but still state that the versions did not match. + * If the version specified in `AndroidManifest.xml` does not match the SDK version, an SDK version entry will be displayed on the Manage webpage. +* Fixes no error being displayed when saving a configuration file with duplicate names from the Driver Station. +* Fixes a deadlock in the UVC driver which manifested in https://github.com/OpenFTC/EasyOpenCV/issues/57. +* Fixes a deadlock in the UVC driver that could occur when hot-plugging cameras. +* Fixes UVC driver compatibility with Arducam OV9281 global shutter camera. +* Fixes Emergency Stop condition when an OnBotJava build with duplicate OpMode names occurs. +* Fixes known causes of "Attempted use of a closed LynxModule instance" logspam. +* Fixes the visual identification LED pattern when configuring Expansion Hubs connected via RS-485. + +## Version 8.1.1 (20221201-150726) + +This is a bug fix only release to address the following four issues. + +* [Issue #492](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/492) - Can't create new blocks opmodes. +* [Issue #495](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/495) - Remove the final modifier from the OpMode's Telemetry object. +* [Issue #500](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/500) - Some devices cannot be configured when the Driver Station app has been updated to 8.1 + * Updating either the Robot Controller app or the Driver Station app to 8.1.1 or later will fix this issue. +* The Modern Robotics touch sensor was configurable as a Digital Device. It can only be used as an Analog Device. + +## Version 8.1 (20221121-115119) + +### Breaking Changes +* Deprecates the `OpMode` fields `msStuckDetectInit`, `msStuckDetectInitLoop`, `msStuckDetectStart`, `msStuckDetectLoop`, and `msStuckDetectStop`. + * OpModes no longer have a time limit for `init()`, `init_loop()`, `start()` or `loop()`, so the fields corresponding to those methods are no longer used. + * `stop()` still has a time limit, but it is now hardcoded to be 1 second, and cannot be changed using `msStuckDetectStop`. +* Deprecates the `OpMode` methods `internalPreInit()`, `internalPostInitLoop()`, and `internalPostLoop()`. + * Iterative `OpMode`s will continue to call these methods in case they were overridden. + * These methods will not be called at all for `LinearOpMode`s. +* Deprecates (and stops respecting) `DeviceProperties.xmlTagAliases`. + +### Enhancements +* Adds a new `IMU` interface to Blocks and Java that can be used with both the original BNO055 IMU + included in all older Control Hubs and Expansion Hubs, and the new alternative BHI260AP IMU. + * You can determine which type of IMU is in your Control Hub by navigating to the Manage page of the web interface. + * To learn how to use the new `IMU` interface, see https://ftc-docs.firstinspires.org/programming_resources/imu/imu.html. The `SensorIMU` Blocks sample was also updated to use the new `IMU` interface, and the following Java samples were added: + * `SensorIMUOrthogonal` + * Use this sample if your REV Hub is mounted so that it is parallel or perpendicular to the + bottom of your robot. + * `SensorIMUNonOrthogonal` + * Use this sample if your REV Hub is mounted to your robot in any other orientation + * `ConceptExploringIMUOrientations` + * This OpMode is a tool to help you understand how the orthogonal orientations work, and + which one applies to your robot. + * The BHI260AP IMU can only be accessed via the new `IMU` interface. The BNO055 IMU can be + programmed using the new `IMU` interface, or you can continue to program it using the old `BNO055IMU` + interface. If you want to be able to quickly switch to a new Control Hub that may contain the + BHI260AP IMU, you should migrate your code to use the new `IMU` interface. + * Unlike the old `BNO055IMU` interface, which only worked correctly when the REV Hub was mounted flat + on your robot, the `IMU` interface allows you to specify the orientation of the REV Hub on your + robot. It will account for this, and give you your orientation in a Robot Coordinate System, + instead of a special coordinate system for the REV Hub. As a result, your pitch and yaw will be + 0 when your *robot* is level, instead of when the REV Hub is level, which will result in much + more reliable orientation angle values for most mounting orientations. + * Because of the new robot-centric coordinate system, the pitch and roll angles returned by the + `IMU` interface will be different from the ones returned by the `BNO055IMU` interface. When you are + migrating your code, pay careful attention to the documentation. + * If you have calibrated your BNO055, you can provide that calibration data to the new `IMU` + interface by passing a `BNO055IMUNew.Parameters` instance to `IMU.initialize()`. + * The `IMU` interface is also suitable for implementation by third-party vendors for IMUs that + support providing the orientation in the form of a quaternion. +* Iterative `OpMode`s (as opposed to `LinearOpMode`s) now run on a dedicated thread. + * Cycle times should not be as impacted by everything else going on in the system. + * Slow `OpMode`s can no longer increase the amount of time it takes to process network commands, and vice versa. + * The `init()`, `init_loop()`, `start()` and `loop()` methods no longer need to return within a certain time frame. +* BNO055 IMU legacy driver: restores the ability to initialize in one OpMode, and then have another OpMode re-use that + initialization. This allows you to maintain the 0-yaw position between OpModes, if desired. +* Allows customized versions of device drivers in the FTC SDK to use the same XML tag. + * Before, if you wanted to customize a device driver, you had to copy it to a new class _and_ give + it a new XML tag. Giving it a new XML tag meant that to switch which driver was being used, you + had to modify your configuration file. + * Now, to use your custom driver, all you have to do is specify your custom driver's class when + calling `hardwareMap.get()`. To go back to the original driver, specify the original driver + class. If you specify an interface that is implemented by both the original driver and the + custom driver, there is no guarantee about which implementation will be returned. + +### Bug Fixes +* Fixes accessing the "Manage TensorFlow Lite Models" and "Manage Sounds" links and performing + Blocks and OnBotJava OpMode downloads from the REV Hardware Client. +* Fixes issue where an I2C device driver would be auto-initialized using the parameters assigned in + a previous OpMode run. +* Improves Driver Station popup menu placement in the landscape layout. +* Fixes NullPointerException when attempting to get a non-configured BNO055 IMU in a Blocks OpMode on an RC phone. +* Fixes problem with Blocks if a variable is named `orientation`. + +## Version 8.0 (20220907-131644) + +### Breaking Changes +* Increases the Robocol version. + * This means an 8.0 or later Robot Controller or Driver Station will not be able to communicate with a 7.2 or earlier Driver Station or Robot Controller. + * If you forget to update both apps at the same time, an error message will be shown explaining which app is older and should be updated. +* Initializing I2C devices now happens when you retrieve them from the `HardwareMap` for the first time. + * Previously, all I2C devices would be initialized before the OpMode even began executing, + whether you were actually going to use them or not. This could result in reduced performance and + unnecessary warnings. + * With this change, it is very important for Java users to retrieve all needed devices from the + `HardwareMap` **during the Init phase of the OpMode**. Namely, declare a variable for each hardware + device the OpMode will use, and assign a value to each. Do not do this during the Run phase, or your + OpMode may briefly hang while the devices you are retrieving get initialized. + * OpModes that do not use all of the I2C devices specified in the configuration file should take + less time to initialize. OpModes that do use all of the specified I2C devices should take the + same amount of time as previously. +* Fixes [issue #251](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/251) by changing the order in which axis rotation rates are read from the angular velocity vector in the BNO055 IMU driver. +* Deprecates `pitchMode` in `BNO055IMU.Parameters`. + * Setting `pitchMode` to `PitchMode.WINDOWS` would break the coordinate conventions used by the driver. +* Moves `OpModeManagerImpl` to the `com.qualcomm.robotcore.eventloop.opmode` package. + * This breaks third party libraries EasyOpenCV (version 1.5.1 and earlier) and FTC Dashboard (version 0.4.4 and earlier). +* Deletes the deprecated `OpMode` method `resetStartTime()` (use `resetRuntime()` instead). +* Deletes the protected `LinearOpMode.LinearOpModeHelper` class (which was not meant for use by OpModes). +* Removes I2C Device (Synchronous) config type (deprecated since 2018) + +### Enhancements +* Uncaught exceptions in OpModes no longer require a Restart Robot + * A blue screen popping up with a stacktrace is not an SDK error; this replaces the red text in the telemetry area. + * Since the very first SDK release, OpMode crashes have put the robot into "EMERGENCY STOP" state, only showing the first line of the exception, and requiring the user to press "Restart Robot" to continue + * Exceptions during an OpMode now open a popup window with the same color scheme as the log viewer, containing 15 lines of the exception stacktrace to allow easily tracing down the offending line without needing to connect to view logs over ADB or scroll through large amounts of logs in the log viewer. + * The exception text in the popup window is both zoomable and scrollable just like a webpage. + * Pressing the "OK" button in the popup window will return to the main screen of the Driver Station and allow an OpMode to be run again immediately, without the need to perform a "Restart Robot" +* Adds new Java sample to demonstrate using a hardware class to abstract robot actuators, and share them across multiple OpModes. + * Sample OpMode is [ConceptExternalHardwareClass.java](FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptExternalHardwareClass.java) + * Abstracted hardware class is [RobotHardware.java](FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/RobotHardware.java) +* Updates RobotAutoDriveByGyro_Linear Java sample to use REV Control/Expansion hub IMU. +* Updates Vuforia samples to reference PowerPlay assets and have correct names and field locations of image targets. +* Updates TensorFlow samples to reference PowerPlay assets. +* Adds opt-in support for Java 8 language features to the OnBotJava editor. + * To opt in, open the OnBotJava Settings, and check `Enable beta Java 8 support`. + * Note that Java 8 code will only compile when the Robot Controller runs Android 7.0 Nougat or later. + * Please report issues [here](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues). +* In OnBotJava, clicking on build errors now correctly jumps to the correct location. +* Improves OnBotJava autocomplete behavior, to provide better completion options in most cases. +* Adds a QR code to the Robot Controller Inspection Report when viewed from the Driver Station for scanning by inspectors at competition. +* Improves I2C performance and reliability in some scenarios. + +## Version 7.2 (20220723-130006) + +### Breaking Changes +* Updates the build tooling. For Android Studio users, this change requires Android Studio Chipmunk 2021.2.1. +* Removes support for devices that are not competition legal, including Modern Robotics Core Control Modules, the Matrix Controller, and HiTechnic/NXT controllers and sensors. Support remains for Modern Robotics I2C sensors. + +### Enhancements +* Increases the height of the 3-dots Landscape menu touch area on the Driver Station, making it much easier to select. +* Adds `terminateOpModeNow()` method to allow OpModes to cleanly self-exit immediately. +* Adds `opModeInInit()` method to `LinearOpMode` to facilitate init-loops. Similar to `opModeIsActive()` but for the init phase. +* Warns user if they have a Logitech F310 gamepad connected that is set to DirectInput mode. +* Allows SPARKmini motor controllers to react more quickly to speed changes. +* Hides the version number of incorrectly installed sister app (i.e. DS installed on RC device or vice-versa) on inspection screen. +* Adds support for allowing the user to edit the comment for the runOpMode block. +* Adds parameterDefaultValues field to @ExportToBlocks. This provides the ability for a java method with an @ExportToBlocks annotation to specify default values for method parameters when it is shown in the block editor. +* Make LinearOpMode blocks more readable. The opmode name is displayed on the runOpMode block, but not on the other LinearOpMode blocks. +* Added support to TensorFlow Object Detection for using a different frame generator, instead of Vuforia. + Using Vuforia to pass the camera frame to TFOD is still supported. +* Removes usage of Renderscript. +* Fixes logspam on app startup of repeated stacktraces relating to `"Failed resolution of: Landroid/net/wifi/p2p/WifiP2pManager$DeviceInfoListener"` +* Allows disabling bluetooth radio from inspection screen +* Improves warning messages when I2C devices are not responding +* Adds support for controlling the RGB LED present on PS4/Etpark gamepads from OpModes +* Removes legacy Pushbot references from OpMode samples. Renames "Pushbot" samples to "Robot". Motor directions reversed to be compatible with "direct Drive" drive train. + + +### Bug fixes +* Fixes [issue #316](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/316) (MatrixF.inverted() returned an incorrectly-sized matrix for 1x1 and 2x2 matrixes). +* Self inspect now allows for Driver Station and Robot Controller compatibility between point releases. +* Fixes bug where if the same `RumbleEffect` object instance was queued for multiple gamepads, it + could happen that both rumble commands would be sent to just one gamepad. +* Fixes bug in Driver Station where on the Driver Hub, if Advanced Gamepad Features was disabled and + an officially supported gamepad was connected, then opening the Advanced Gamepad Features or + Gamepad Type Overrides screens would cause the gamepad to be rebound by the custom USB driver even + though advanced gamepad features was disabled. +* Protects against (unlikely) null pointer exception in Vuforia Localizer. +* Harden OnBotJava and Blocks saves to protect against save issues when disconnecting from Program and Manage +* Fixes issue where the RC app would hang if a REV Hub I2C write failed because the previous I2C + operation was still in progress. This hang most commonly occurred during REV 2M Distance Sensor initialization +* Removes ConceptWebcam.java sample program. This sample is not compatible with OnBotJava. +* Fixes bug where using html tags in an @ExportToBlocks comment field prevented the blocks editor from loading. +* Fixes blocks editor so it doesn't ask you to save when you haven't modified anything. +* Fixes uploading a very large blocks project to offline blocks editor. +* Fixes bug that caused blocks for DcMotorEx to be omitted from the blocks editor toolbox. +* Fixes [Blocks Programs Stripped of Blocks (due to using TensorFlow Label block)](https://ftcforum.firstinspires.org/forum/ftc-technology/blocks-programming/87035-blocks-programs-stripped-of-blocks) + +## Version 7.1 (20211223-120805) + +* Fixes crash when calling `isPwmEnabled()` ([issue #223](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/233)). +* Fixes lint error ([issue #4](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/4)). +* Fixes Driver Station crash when attempting to use DualShock4 v1 gamepad with Advanced Gamepad Features enabled ([issue #173](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/173)). +* Fixes possible (but unlikely) Driver Station crash when connecting gamepads of any type. +* Fixes bug where Driver Station would use generic 20% deadzone for Xbox360 and Logitech F310 gamepads when Advanced Gamepad Features was disabled. +* Added SimpleOmniDrive sample OpMode. +* Adds UVC white balance control API. +* Fixes [issue #259](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/259) Most blocks samples for TensorFlow can't be used for a different model. + * The blocks previously labeled TensorFlowObjectDetectionFreightFrenzy (from the subcategory named "Optimized for Freight Frenzy") and TensorFlowObjectDetectionCustomModel (from the subcategory named "Custom Model") have been replaced with blocks labeled TensorFlowObjectDetection. Blocks in existing opmodes will be automatically updated to the new blocks when opened in the blocks editor. +* Fixes [issue #260](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/260) Blocks can't call java method that has a VuforiaLocalizer parameter. + * Blocks now has a block labeled VuforiaFreightFrenzy.getVuforiaLocalizer for this. +* Added a page to manage the TensorFlow Lite models in /sdcard/FIRST/tflitemodels. To get to the TFLite Models page: + * You can click on the link at the bottom of the the Manage page. + * You can click on the link at the upper-right the Blocks project page. +* Fixes logspam when `isBusy()` is called on a motor not in RTP mode. +* Hides the "RC Password" item on the inspection screen for phone-based Robot Controllers. (It is only applicable for Control Hubs). +* Adds channel 165 to Wi-Fi Direct channel selection menu in the settings screen. (165 was previously available through the web UI, but not locally in the app). + +## Version 7.0 (20210915-141025) + +### Enhancements and New Features +* Adds support for external libraries to OnBotJava and Blocks. + * Upload .jar and .aar files in OnBotJava. + * Known limitation - RobotController device must be running Android 7.0 or greater. + * Known limitation - .aar files with assets are not supported. + * External libraries can provide support for hardware devices by using the annotation in the + com.qualcomm.robotcore.hardware.configuration.annotations package. + * External libraries can include .so files for native code. + * External libraries can be used from OnBotJava OpModes. + * External libraries that use the following annotations can be used from Blocks OpModes. + * org.firstinspires.ftc.robotcore.external.ExportClassToBlocks + * org.firstinspires.ftc.robotcore.external.ExportToBlocks + * External libraries that use the following annotations can add new hardware devices: + * com.qualcomm.robotcore.hardware.configuration.annotations.AnalogSensorType + * com.qualcomm.robotcore.hardware.configuration.annotations.DeviceProperties + * com.qualcomm.robotcore.hardware.configuration.annotations.DigitalIoDeviceType + * com.qualcomm.robotcore.hardware.configuration.annotations.I2cDeviceType + * com.qualcomm.robotcore.hardware.configuration.annotations.MotorType + * com.qualcomm.robotcore.hardware.configuration.annotations.ServoType + * External libraries that use the following annotations can add new functionality to the Robot Controller: + * org.firstinspires.ftc.ftccommon.external.OnCreate + * org.firstinspires.ftc.ftccommon.external.OnCreateEventLoop + * org.firstinspires.ftc.ftccommon.external.OnCreateMenu + * org.firstinspires.ftc.ftccommon.external.OnDestroy + * org.firstinspires.ftc.ftccommon.external.WebHandlerRegistrar +* Adds support for REV Robotics Driver Hub. +* Adds fully custom userspace USB gamepad driver to Driver Station (see "Advanced Gamepad Features" menu in DS settings). + * Allows gamepads to work on devices without native Linux kernel support (e.g. some Romanian Motorola devices). + * Allows the DS to read the unique serial number of each gamepad, enabling auto-recovery of dropped gamepads even if two gamepads of the same model drop. *(NOTE: unfortunately this does not apply to Etpark gamepads, because they do not have a unique serial)*. + * Reading the unique serial number also provides the ability to configure the DS to assign gamepads to a certain position by default (so no need to do start+a/b at all). + * The LED ring on the Xbox360 gamepad and the RGB LED bar on the PS4 gamepad is used to indicate the driver position the gamepad is bound to. + * The rumble motors on the Xbox360, PS4, and Etpark gamepads can be controlled from OpModes. + * The 2-point touchpad on the PS4 gamepad can be read from OpModes. + * The "back" and "guide" buttons on the gamepad can now be safely bound to robot controls (Previously, on many devices, Android would intercept these buttons as home button presses and close the app). + * Advanced Gamepad features are enabled by default, but may be disabled through the settings menu in order to revert to gamepad support provided natively by Android. +* Improves accuracy of ping measurement. + * Fixes issue where the ping time showed as being higher than reality when initially connecting to or restarting the robot. + * To see the full improvement, you must update both the Robot Controller and Driver Station apps. +* Updates samples located at [/FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples](FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples). + * Added ConceptGamepadRumble and ConceptGamepadTouchpad samples to illustrate the use of these new gampad capabilities. + * Condensed existing Vuforia samples into just 2 samples (ConceptVuforiaFieldNavigation & ConceptVuforiaFieldNavigationWebcam) showing how to determine the robot's location on the field using Vuforia. These both use the current season's Target images. + * Added ConceptVuforiaDriveToTargetWebcam to illustrate an easy way to drive directly to any visible Vuforia target. +* Makes many improvements to the warning system and individual warnings. + * Warnings are now much more spaced out, so that they are easier to read. + * New warnings were added for conditions that should be resolved before competing. + * The mismatched apps warning now uses the major and minor app versions, not the version code. + * The warnings are automatically re-enabled when a Robot Controller app from a new FTC season is installed. +* Adds support for I2C transactions on the Expansion Hub / Control Hub without specifying a register address. + * See section 3 of the [TI I2C spec](https://www.ti.com/lit/an/slva704/slva704.pdf). + * Calling these new methods when using Modern Robotics hardware will result in an UnsupportedOperationException. +* Changes VuforiaLocalizer `close()` method to be public. +* Adds support for TensorFlow v2 object detection models. +* Reduces ambiguity of the Self Inspect language and graphics. +* OnBotJava now warns about potentially unintended file overwrites. +* Improves behavior of the Wi-Fi band and channel selector on the Manage webpage. + +### Bug fixes + * Fixes Robot Controller app crash on Android 9+ when a Driver Station connects. + * Fixes issue where an OpMode was responsible for calling shutdown on the + TensorFlow TFObjectDetector. Now this is done automatically. + * Fixes Vuforia initialization blocks to allow user to chose AxesOrder. Updated + relevant blocks sample opmodes. + * Fixes [FtcRobotController issue #114](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/114) + LED blocks and Java class do not work. + * Fixes match logging for OpModes that contain special characters in their names. + * Fixes Driver Station OpMode controls becoming unresponsive if the Driver Station was set to the landscape layout and an OnBotJava build was triggered while an OpMode was running. + * Fixes the Driver Station app closing itself when it is switched away from, or the screen is turned off. + * Fixes "black swirl of doom" (Infinite "configuring Wi-Fi Direct" message) on older devices. + * Updates the wiki comment on the OnBotJava intro page. + +## Version 6.2 (20210218-074821) + +### Enhancements +* Attempts to automatically fix the condition where a Control Hub's internal Expansion Hub is not + working by re-flashing its firmware +* Makes various improvements to the Wi-Fi Direct pairing screen, especially in landscape mode +* Makes the Robot Controller service no longer be categorically restarted when the main activity is brought to foreground + * (e.g. the service is no longer restarted simply by viewing the Self Inspect screen and pressing the back button) + * It is still restarted if the Settings menu or Configure Robot menu is opened + + +### Bug fixes +* Fixes [FtcRobotController issue #71](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/71) + Cannot open OpModes in v6.1 Blocks offline editor +* Fixes [FtcRobotController issue #79](https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/79) + 6.1 causes a soft reboot on the Motorola E5 Play +* Fixes issue where the Control Hub OS's watchdog would restart the Robot Controller app if + the Control Hub was not able to communicate with its internal Expansion Hub +* Fixes certain I2C devices not showing up in the appropriate `HardwareMap` fields (such as `hardwareMap.colorSensor`) +* Fixes issue where performing a Wi-Fi factory reset on the Control Hub would not set the Wi-Fi band to 2.4 GHz +* Fixes issue where OnBotJava might fail to create a new file if the option to "Setup Code for Configured Hardware" was selected +* Fixes issue where performing certain operations after an OpMode crashes would temporarily break Control/Expansion Hub communication +* Fixes issue where a Control Hub with a configured USB-connected Expansion Hub would not work if the Expansion Hub was missing at startup +* Fixes potential issues caused by having mismatched Control/Expansion Hub firmware versions +* Fixes [ftc_app issue 673](https://github.com/ftctechnh/ftc_app/issues/673) Latest matchlog is being deleted instead of old ones by RobotLog +* Fixes ConceptVuforiaUltimateGoalNavigationWebcam sample opmode by correctly orienting camera on robot. +* Fixes issue where logcat would be spammed with InterruptedExceptions when stop is requested from the Driver Station (this behavior was accidentally introduced in v5.3). This change has no impact on functionality. +* Fixes issue where the blocks editor fails to load if the name of any TeleOp opmode contains an apostrophe. + +## Version 6.1 (20201209-113742) +* Makes the scan button on the configuration screen update the list of Expansion Hubs connected via RS-485 + * Fixes [SkyStone issue #143](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/143) +* Improves web interface compatibility with older browser and Android System WebView versions. +* Fixes issue in UVC driver where some cameras (e.g. certain MS Lifecams) which reported frame intervals as rounded rather than truncated values (e.g. `666667*100ns` instead of `666666*100ns` for 15FPS) would fail to start streaming. +* Adds support in UVC driver for virtual PTZ control +* Adds support in UVC driver for gain (ISO) control +* Adds support in UVC driver for enabling/disable AE priority. This setting provides a means to tell the camera firmware either + * A) It can undershoot the requested frame rate in order to provide a theoretically better image (i.e. with a longer exposure than the inter-frame period of the selected frame rate allows) + * B) It *must* meet the inter-frame deadline for the selected frame rate, even if the image may be underexposed as a result +* Adds support for the Control Hub OS 1.1.2 Robot Controller watchdog + * The Robot Controller app will be restarted if it stops responding for more than 10 seconds +* Adds support for using the Driver Station app on Android 10+ +* Introduces an automatic TeleOp preselection feature + * For details and usage guide, please see [this wiki entry](https://github.com/FIRST-Tech-Challenge/FtcRobotController/wiki/Automatically-Loading-a-Driver-Controlled-Op-Mode) +* Shows icon next to OpMode name in the OpMode list dropdown on the Driver Station to indicate the source of the OpMode (i.e. the programming tool used to create it) +* Fixes issue where the Driver Station app would exit after displaying the Configuring Wi-Fi Direct screen +* Fixes Blocks and OnBotJava prompts when accessed via the REV Hardware Client + +## Version 6.0 (20200921-085816) + +### Important Notes +* Version 6.0 is the version for the Ultimate Goal season. +* Requires Android Studio 4.0. +* Android Studio users need to be connected to the Internet the first time they build the app (in order to download needed packages for the build). +* Version 5.5 was a moderately large off-season, August 2020, drop. It's worth reviewing those release notes below also. +* Version 5.5 and greater will not work on older Android 4.x and 5.x phones. Users must upgrade to an approved Android 6.x device or newer. +* The default PIDF values for REV motors have been reverted to the default PID values that were used in the 2018-2019 season + * This change was made because the 2018-2019 values turned out to work better for many mechanisms + * This brings the behavior of the REV motors in line with the behavior of all other motors + * If you prefer the 2019-2020 season's behavior for REV motors, here are the PIDF values that were in place, so that you can manually set them in your OpModes: +
+ **HD Hex motors (all gearboxes):** + Velocity PIDF values: `P = 1.17`, `I = 0.117`, `F = 11.7` + Position PIDF values: `P = 5.0` + **Core Hex motor:** + Velocity PIDF values: `P = 4.96`, `I = 0.496`, `F = 49.6` + Position PIDF values: `P = 5.0` + +### New features +* Includes TensorFlow inference model and sample OpModes to detect Ultimate Goal Starter Stacks (four rings vs single ring stack). +* Includes Vuforia Ultimate Goal vision targets and sample OpModes. +* Introduces a digital zoom feature for TensorFlow object detection (to detect objects more accurately at greater distances). +* Adds configuration entry for the REV UltraPlanetary HD Hex motor + +### Enhancements +* Adds setGain() and getGain() methods to the NormalizedColorSensor interface + * By setting the gain of a color sensor, you can adjust for different lighting conditions. + For example, if you detect lower color values than expected, you can increase the gain. + * The gain value is only applied to the argb() and getNormalizedColors() methods, not to the raw color methods. + The getNormalizedColors() method is recommended for ease-of-use and clarity, since argb() has to be converted. + * Updates SensorColor Java sample to demonstrate gain usage +* Merges SensorREVColorDistance Java sample into SensorColor Java sample, which showcases best practices for all color sensors +* Improves retrieving values from the REV Color Sensor V3 + * Updates the normalization calculation of the RGB channels + * Improves the calculation of the alpha channel (can be used as an overall brightness indicator) + * Fixes the default sensor resolution, which caused issues with bright environments + * Adds support for changing the resolution and measuring rate of the Broadcom sensor chip + * Removes IR readings and calculations not meant for the Broadcom sensor chip + +### Bug fixes +* Improves reliability of BNO055IMU IMU initialization to prevent random initialization failures (which manifested as `Problem with 'imu'`). + +## Version 5.5 (20200824-090813) + +Version 5.5 requires Android Studio 4.0 or later. + +### New features +* Adds support for calling custom Java classes from Blocks OpModes (fixes [SkyStone issue #161](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/161)). + * Classes must be in the org.firstinspires.ftc.teamcode package. + * To have easy access to the opMode, hardwareMap, telemetry, gamepad1, and gamepad2, classes can + extends org.firstinspires.ftc.robotcore.external.BlocksOpModeCompanion. + * Methods must be public static and have no more than 21 parameters. + * Methods must be annotated with org.firstinspires.ftc.robotcore.external.ExportToBlocks. + * Parameters declared as OpMode, LinearOpMode, Telemetry, and HardwareMap are supported and the + argument is provided automatically, regardless of the order of the parameters. On the block, + the sockets for those parameters are automatically filled in. + * Parameters declared as char or java.lang.Character will accept any block that returns text + and will only use the first character in the text. + * Parameters declared as boolean or java.lang.Boolean will accept any block that returns boolean. + * Parameters declared as byte, java.lang.Byte, short, java.lang.Short, int, java.lang.Integer, + long, or java.lang.Long, will accept any block that returns a number and will round that + value to the nearest whole number. + * Parameters declared as float, java.lang.Float, double, java.lang.Double will accept any + block that returns a number. +* Adds telemetry API method for setting display format + * Classic + * Monospace + * HTML (certain tags only) +* Adds blocks support for switching cameras. +* Adds Blocks support for TensorFlow Object Detection with a custom model. +* Adds support for uploading a custom TensorFlow Object Detection model in the Manage page, which + is especially useful for Blocks and OnBotJava users. +* Shows new Control Hub blink codes when the Wi-Fi band is switched using the Control Hub's button (only possible on Control Hub OS 1.1.2) +* Adds new warnings which can be disabled in the Advanced RC Settings + * Mismatched app versions warning + * Unnecessary 2.4 GHz Wi-Fi usage warning + * REV Hub is running outdated firmware (older than version 1.8.2) +* Adds support for Sony PS4 gamepad, and reworks how gamepads work on the Driver Station + * Removes preference which sets gamepad type based on driver position. Replaced with menu which allows specifying type for gamepads with unknown VID and PID + * Attempts to auto-detect gamepad type based on USB VID and PID + * If gamepad VID and PID is not known, use type specified by user for that VID and PID + * If gamepad VID and PID is not known AND the user has not specified a type for that VID and PID, an educated guess is made about how to map the gamepad +* Driver Station will now attempt to automatically recover from a gamepad disconnecting, and re-assign it to the position it was assigned to when it dropped + * If only one gamepad is assigned and it drops: it can be recovered + * If two gamepads are assigned, and have **different** VID/PID signatures, and only one drops: it will be recovered + * If two gamepads are assigned, and have **different** VID/PID signatures, and BOTH drop: both will be recovered + * If two gamepads are assigned, and have **the same** VID/PID signatures, and only one drops: it will be recovered + * If two gamepads are assigned, and have **the same** VID/PID signatures, and BOTH drop: **neither** will be recovered, because of the ambiguity of the gamepads when they re-appear on the USB bus. + * There is currently one known edge case: if there are **two** gamepads with **the same** VID/PID signature plugged in, **but only one is assigned**, and they BOTH drop, it's a 50-50 chance of which one will be chosen for automatic recovery to the assigned position: it is determined by whichever one is re-enumerated first by the USB bus controller. +* Adds landscape user interface to Driver Station + * New feature: practice timer with audio cues + * New feature (Control Hub only): wireless network connection strength indicator (0-5 bars) + * New feature (Control Hub only): tapping on the ping/channel display will switch to an alternate display showing radio RX dBm and link speed (tap again to switch back) + * The layout will NOT autorotate. You can switch the layout from the Driver Station's settings menu. +### Breaking changes +* Removes support for Android versions 4.4 through 5.1 (KitKat and Lollipop). The minSdkVersion is now 23. +* Removes the deprecated `LinearOpMode` methods `waitOneFullHardwareCycle()` and `waitForNextHardwareCycle()` +### Enhancements +* Handles RS485 address of Control Hub automatically + * The Control Hub is automatically given a reserved address + * Existing configuration files will continue to work + * All addresses in the range of 1-10 are still available for Expansion Hubs + * The Control Hub light will now normally be solid green, without blinking to indicate the address + * The Control Hub will not be shown on the Expansion Hub Address Change settings page +* Improves REV Hub firmware updater + * The user can now choose between all available firmware update files + * Version 1.8.2 of the REV Hub firmware is bundled into the Robot Controller app. + * Text was added to clarify that Expansion Hubs can only be updated via USB. + * Firmware update speed was reduced to improve reliability + * Allows REV Hub firmware to be updated directly from the Manage webpage +* Improves log viewer on Robot Controller + * Horizontal scrolling support (no longer word wrapped) + * Supports pinch-to-zoom + * Uses a monospaced font + * Error messages are highlighted + * New color scheme +* Attempts to force-stop a runaway/stuck OpMode without restarting the entire app + * Not all types of runaway conditions are stoppable, but if the user code attempts to talk to hardware during the runaway, the system should be able to capture it. +* Makes various tweaks to the Self Inspect screen + * Renames "OS version" entry to "Android version" + * Renames "Wi-Fi Direct Name" to "Wi-Fi Name" + * Adds Control Hub OS version, when viewing the report of a Control Hub + * Hides the airplane mode entry, when viewing the report of a Control Hub + * Removes check for ZTE Speed Channel Changer + * Shows firmware version for **all** Expansion and Control Hubs +* Reworks network settings portion of Manage page + * All network settings are now applied with a single click + * The Wi-Fi Direct channel of phone-based Robot Controllers can now be changed from the Manage page + * Wi-Fi channels are filtered by band (2.4 vs 5 GHz) and whether they overlap with other channels + * The current Wi-Fi channel is pre-selected on phone-based Robot Controllers, and Control Hubs running OS 1.1.2 or later. + * On Control Hubs running OS 1.1.2 or later, you can choose to have the system automatically select a channel on the 5 GHz band +* Improves OnBotJava + * New light and dark themes replace the old themes (chaos, github, chrome,...) + * the new default theme is `light` and will be used when you first update to this version + * OnBotJava now has a tabbed editor + * Read-only offline mode +* Improves function of "exit" menu item on Robot Controller and Driver Station + * Now guaranteed to be fully stopped and unloaded from memory +* Shows a warning message if a LinearOpMode exists prematurely due to failure to monitor for the start condition +* Improves error message shown when the Driver Station and Robot Controller are incompatible with each other +* Driver Station OpMode Control Panel now disabled while a Restart Robot is in progress +* Disables advanced settings related to Wi-Fi Direct when the Robot Controller is a Control Hub. +* Tint phone battery icons on Driver Station when low/critical. +* Uses names "Control Hub Portal" and "Control Hub" (when appropriate) in new configuration files +* Improve I2C read performance + * Very large improvement on Control Hub; up to ~2x faster with small (e.g. 6 byte) reads + * Not as apparent on Expansion Hubs connected to a phone +* Update/refresh build infrastructure + * Update to 'androidx' support library from 'com.android.support:appcompat', which is end-of-life + * Update targetSdkVersion and compileSdkVersion to 28 + * Update Android Studio's Android plugin to latest + * Fix reported build timestamp in 'About' screen +* Add sample illustrating manual webcam use: ConceptWebcam + + +### Bug fixes +* Fixes [SkyStone issue #248](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/248) +* Fixes [SkyStone issue #232](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/232) and + modifies bulk caching semantics to allow for cache-preserving MANUAL/AUTO transitions. +* Improves performance when REV 2M distance sensor is unplugged +* Improves readability of Toast messages on certain devices +* Allows a Driver Station to connect to a Robot Controller after another has disconnected +* Improves generation of fake serial numbers for UVC cameras which do not provide a real serial number + * Previously some devices would assign such cameras a serial of `0:0` and fail to open and start streaming + * Fixes [ftc_app issue #638](https://github.com/ftctechnh/ftc_app/issues/638). +* Fixes a slew of bugs with the Vuforia camera monitor including: + * Fixes bug where preview could be displayed with a wonky aspect ratio + * Fixes bug where preview could be cut off in landscape + * Fixes bug where preview got totally messed up when rotating phone + * Fixes bug where crosshair could drift off target when using webcams +* Fixes issue in UVC driver on some devices ([ftc_app 681](https://github.com/ftctechnh/ftc_app/issues/681)) if streaming was started/stopped multiple times in a row + * Issue manifested as kernel panic on devices which do not have [this kernel patch](https://lore.kernel.org/patchwork/patch/352400/). + * On affected devices which **do** have the patch, the issue was manifest as simply a failure to start streaming. + * The Tech Team believes that the root cause of the issue is a bug in the Linux kernel XHCI driver. A workaround was implemented in the SDK UVC driver. +* Fixes bug in UVC driver where often half the frames from the camera would be dropped (e.g. only 15FPS delivered during a streaming session configured for 30FPS). +* Fixes issue where TensorFlow Object Detection would show results whose confidence was lower than + the minimum confidence parameter. +* Fixes a potential exploitation issue of [CVE-2019-11358](https://www.cvedetails.com/cve/CVE-2019-11358/) in OnBotJava +* Fixes changing the address of an Expansion Hub with additional Expansion Hubs connected to it +* Preserves the Control Hub's network connection when "Restart Robot" is selected +* Fixes issue where device scans would fail while the Robot was restarting +* Fix RenderScript usage + * Use androidx.renderscript variant: increased compatibility + * Use RenderScript in Java mode, not native: simplifies build +* Fixes webcam-frame-to-bitmap conversion problem: alpha channel wasn't being initialized, only R, G, & B +* Fixes possible arithmetic overflow in Deadline +* Fixes deadlock in Vuforia webcam support which could cause 5-second delays when stopping OpMode + +## Version 5.4 (20200108-101156) +* Fixes [SkyStone issue #88](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/88) +* Adds an inspection item that notes when a robot controller (Control Hub) is using the factory default password. +* Fixes [SkyStone issue #61](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/61) +* Fixes [SkyStone issue #142](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/142) +* Fixes [ftc_app issue #417](https://github.com/ftctechnh/ftc_app/issues/417) by adding more current and voltage monitoring capabilities for REV Hubs. +* Fixes [a crash sometimes caused by OnBotJava activity](https://ftcforum.firstinspires.org/forum/ftc-technology/76217-onbotjava-crashes-robot-controller) +* Improves OnBotJava autosave functionality [ftc_app #738](https://github.com/ftctechnh/ftc_app/issues/738) +* Fixes system responsiveness issue when an Expansion Hub is disconnected +* Fixes issue where IMU initialization could prevent OpModes from stopping +* Fixes issue where AndroidTextToSpeech.speak() would fail if it was called too early +* Adds telemetry.speak() methods and blocks, which cause the Driver Station (if also updated) to speak text +* Adds and improves Expansion Hub-related warnings + * Improves Expansion Hub low battery warning + * Displays the warning immediately after the hub reports it + * Specifies whether the condition is current or occurred temporarily during an OpMode run + * Displays which hubs reported low battery + * Displays warning when hub loses and regains power during an OpMode run + * Fixes the hub's LED pattern after this condition + * Displays warning when Expansion Hub is not responding to commands + * Specifies whether the condition is current or occurred temporarily during an OpMode run + * Clarifies warning when Expansion Hub is not present at startup + * Specifies that this condition requires a Robot Restart before the hub can be used. + * The hub light will now accurately reflect this state + * Improves logging and reduces log spam during these conditions +* Syncs the Control Hub time and timezone to a connected web browser programming the robot, if a Driver Station is not available. +* Adds bulk read functionality for REV Hubs + * A bulk caching mode must be set at the Hub level with `LynxModule#setBulkCachingMode()`. This applies to all relevant SDK hardware classes that reference that Hub. + * The following following Hub bulk caching modes are available: + * `BulkCachingMode.OFF` (default): All hardware calls operate as usual. Bulk data can read through `LynxModule#getBulkData()` and processed manually. + * `BulkCachingMode.AUTO`: Applicable hardware calls are served from a bulk read cache that is cleared/refreshed automatically to ensure identical commands don't hit the same cache. The cache can also be cleared manually with `LynxModule#clearBulkCache()`, although this is not recommended. + * (advanced users) `BulkCachingMode.MANUAL`: Same as `BulkCachingMode.AUTO` except the cache is never cleared automatically. To avoid getting stale data, the cache must be manually cleared at the beginning of each loop body or as the user deems appropriate. +* Removes PIDF Annotation values added in Rev 5.3 (to AndyMark, goBILDA and TETRIX motor configurations). + * The new motor types will still be available but their Default control behavior will revert back to Rev 5.2 +* Adds new `ConceptMotorBulkRead` sample Opmode to demonstrate and compare Motor Bulk-Read modes for reducing I/O latencies. + +## Version 5.3 (20191004-112306) +* Fixes external USB/UVC webcam support +* Makes various bugfixes and improvements to Blocks page, including but not limited to: + * Many visual tweaks + * Browser zoom and window resize behave better + * Resizing the Java preview pane works better and more consistently across browsers + * The Java preview pane consistently gets scrollbars when needed + * The Java preview pane is hidden by default on phones + * Internet Explorer 11 should work + * Large dropdown lists display properly on lower res screens + * Disabled buttons are now visually identifiable as disabled + * A warning is shown if a user selects a TFOD sample, but their device is not compatible + * Warning messages in a Blocks OpMode are now visible by default. +* Adds goBILDA 5201 and 5202 motors to Robot Configurator +* Adds PIDF Annotation values to AndyMark, goBILDA and TETRIX motor configurations. + This has the effect of causing the RUN_USING_ENCODERS and RUN_TO_POSITION modes to use + PIDF vs PID closed loop control on these motors. This should provide more responsive, yet stable, speed control. + PIDF adds Feedforward control to the basic PID control loop. + Feedforward is useful when controlling a motor's speed because it "anticipates" how much the control voltage + must change to achieve a new speed set-point, rather than requiring the integrated error to change sufficiently. + The PIDF values were chosen to provide responsive, yet stable, speed control on a lightly loaded motor. + The more heavily a motor is loaded (drag or friction), the more noticable the PIDF improvement will be. +* Fixes startup crash on Android 10 +* Fixes [ftc_app issue #712](https://github.com/ftctechnh/ftc_app/issues/712) (thanks to FROGbots-4634) +* Fixes [ftc_app issue #542](https://github.com/ftctechnh/ftc_app/issues/542) +* Allows "A" and lowercase letters when naming device through RC and DS apps. + +## Version 5.2 (20190905-083277) +* Fixes extra-wide margins on settings activities, and placement of the new configuration button +* Adds Skystone Vuforia image target data. + * Includes sample Skystone Vuforia Navigation OpModes (Java). + * Includes sample Skystone Vuforia Navigation OpModes (Blocks). +* Adds TensorFlow inference model (.tflite) for Skystone game elements. + * Includes sample Skystone TensorFlow OpModes (Java). + * Includes sample Skystone TensorFlow OpModes (Blocks). +* Removes older (season-specific) sample OpModes. +* Includes 64-bit support (to comply with [Google Play requirements](https://android-developers.googleblog.com/2019/01/get-your-apps-ready-for-64-bit.html)). +* Protects against Stuck OpModes when a Restart Robot is requested. (Thanks to FROGbots-4634) ([ftc_app issue #709](https://github.com/ftctechnh/ftc_app/issues/709)) +* Blocks related changes: + * Fixes bug with blocks generated code when hardware device name is a java or javascript reserved word. + * Shows generated java code for blocks, even when hardware items are missing from the active configuration. + * Displays warning icon when outdated Vuforia and TensorFlow blocks are used ([SkyStone issue #27](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/27)) + +## Version 5.1 (20190820-222104) +* Defines default PIDF parameters for the following motors: + * REV Core Hex Motor + * REV 20:1 HD Hex Motor + * REV 40:1 HD Hex Motor +* Adds back button when running on a device without a system back button (such as a Control Hub) +* Allows a REV Control Hub to update the firmware on a REV Expansion Hub via USB +* Fixes [SkyStone issue #9](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/9) +* Fixes [ftc_app issue #715](https://github.com/ftctechnh/ftc_app/issues/715) +* Prevents extra DS User clicks by filtering based on current state. +* Prevents incorrect DS UI state changes when receiving new OpMode list from RC +* Adds support for REV Color Sensor V3 +* Adds a manual-refresh DS Camera Stream for remotely viewing RC camera frames. + * To show the stream on the DS, initialize **but do not run** a stream-enabled opmode, select the Camera Stream option in the DS menu, and tap the image to refresh. This feature is automatically enabled when using Vuforia or TFOD—no additional RC configuration is required for typical use cases. To hide the stream, select the same menu item again. + * Note that gamepads are disabled and the selected opmode cannot be started while the stream is open as a safety precaution. + * To use custom streams, consult the API docs for `CameraStreamServer#setSource` and `CameraStreamSource`. +* Adds many Star Wars sounds to RobotController resources. +* Added Skystone Sounds Chooser Sample Program. +* Switches out startup, connect chimes, and error/warning sounds for Star Wars sounds +* Updates OnBot Java to use a WebSocket for communication with the robot + * The OnBot Java page no longer has to do a full refresh when a user switches from editing one file to another + +Known issues: +* Camera Stream + * The Vuforia camera stream inherits the issues present in the phone preview (namely [ftc_app issue #574](https://github.com/ftctechnh/ftc_app/issues/574)). This problem does not affect the TFOD camera stream even though it receives frames from Vuforia. + * The orientation of the stream frames may not always match the phone preview. For now, these frames may be rotated manually via a custom `CameraStreamSource` if desired. +* OnBotJava + * Browser back button may not always work correctly + * It's possible for a build to be queued, but not started. The OnBot Java build console will display a warning if this occurs. + * A user might not realize they are editing a different file if the user inadvertently switches from one file to another since this switch is now seamless. The name of the currently open file is displayed in the browser tab. + +## Version 5.0 (built on 19.06.14) + * Support for the REV Robotics Control Hub. + * Adds a Java preview pane to the Blocks editor. + * Adds a new offline export feature to the Blocks editor. + * Display Wi-Fi channel in Network circle on Driver Station. + * Adds calibration for Logitech C270 + * Updates build tooling and target SDK. + * Compliance with Google's permissions infrastructure (Required after build tooling update). + * Keep Alives to mitigate the Motorola Wi-Fi scanning problem. Telemetry substitute no longer necessary. + * Improves Vuforia error reporting. + * Fixes ftctechnh/ftc_app issues 621, 713. + * Miscellaneous bug fixes and improvements. + +## Version 4.3 (built on 18.10.31) + * Includes missing TensorFlow-related libraries and files. + +## Version 4.2 (built on 18.10.30) + * Includes fix to avoid deadlock situation with WatchdogMonitor which could result in USB communication errors. + - Comm error appeared to require that user disconnect USB cable and restart the Robot Controller app to recover. + - robotControllerLog.txt would have error messages that included the words "E RobotCore: lynx xmit lock: #### abandoning lock:" + * Includes fix to correctly list the parent module address for a REV Robotics Expansion Hub in a configuration (.xml) file. + - Bug in versions 4.0 and 4.1 would incorrect list the address module for a parent REV Robotics device as "1". + - If the parent module had a higher address value than the daisy-chained module, then this bug would prevent the Robot Controller from communicating with the downstream Expansion Hub. + * Added requirement for ACCESS_COARSE_LOCATION to allow a Driver Station running Android Oreo to scan for Wi-Fi Direct devices. + * Added google() repo to build.gradle because aapt2 must be downloaded from the google() repository beginning with version 3.2 of the Android Gradle Plugin. + - Important Note: Android Studio users will need to be connected to the Internet the first time build the ftc_app project. + - Internet connectivity is required for the first build so the appropriate files can be downloaded from the Google repository. + - Users should not need to be connected to the Internet for subsequent builds. + - This should also fix buid issue where Android Studio would complain that it "Could not find com.android.tools.lint:lint-gradle:26.1.4" (or similar). + * Added support for REV Spark Mini motor controller as part of the configuration menu for a servo/PWM port on the REV Expansion Hub. + * Provide examples for playing audio files in an OpMode. + * Block Development Tool Changes + - Includes a fix for a problem with the Velocity blocks that were reported in the FTC Technology forum (Blocks Programming subforum). + - Change the "Save completed successfully." message to a white color so it will contrast with a green background. + - Fixed the "Download image" feature so it will work if there are text blocks in the OpMode. + * Introduce support for Google's TensorFlow Lite technology for object detetion for 2018-2019 game. + - TensorFlow lite can recognize Gold Mineral and Silver Mineral from 2018-2019 game. + - Example Java and Block OpModes are included to show how to determine the relative position of the gold block (left, center, right). + +## Version 4.1 (released on 18.09.24) + +Changes include: + * Fix to prevent crash when deprecated configuration annotations are used. + * Change to allow FTC Robot Controller APK to be auto-updated using FIRST Global Control Hub update scripts. + * Removed samples for non supported / non legal hardware. + * Improvements to Telemetry.addData block with "text" socket. + * Updated Blocks sample OpMode list to include Rover Ruckus Vuforia example. + * Update SDK library version number. + +## Version 4.0 (released on 18.09.12) + +Changes include: + * Initial support for UVC compatible cameras + - If UVC camera has a unique serial number, RC will detect and enumerate by serial number. + - If UVC camera lacks a unique serial number, RC will only support one camera of that type connected. + - Calibration settings for a few cameras are included (see TeamCode/src/main/res/xml/teamwebcamcalibrations.xml for details). + - User can upload calibration files from Program and Manage web interface. + - UVC cameras seem to draw a fair amount of electrical current from the USB bus. + + This does not appear to present any problems for the REV Robotics Control Hub. + + This does seem to create stability problems when using some cameras with an Android phone-based Robot Controller. + + FTC Tech Team is investigating options to mitigate this issue with the phone-based Robot Controllers. + - Updated sample Vuforia Navigation and VuMark OpModes to demonstrate how to use an internal phone-based camera and an external UVC webcam. + + * Support for improved motor control. + - REV Robotics Expansion Hub firmware 1.8 and greater will support a feed forward mechanism for closed loop motor control. + - FTC SDK has been modified to support PIDF coefficients (proportional, integral, derivative, and feed forward). + - FTC Blocks development tool modified to include PIDF programming blocks. + - Deprecated older PID-related methods and variables. + - REV's 1.8.x PIDF-related changes provide a more linear and accurate way to control a motor. + + * Wireless + - Added 5GHz support for wireless channel changing for those devices that support it. + + Tested with Moto G5 and E4 phones. + + Also tested with other (currently non-approved) phones such as Samsung Galaxy S8. + +* Improved Expansion Hub firmware update support in Robot Controller app + - Changes to make the system more robust during the firmware update process (when performed through Robot Controller app). + - User no longer has to disconnect a downstream daisy-chained Expansion Hub when updating an Expansion Hub's firmware. + + If user is updating an Expansion Hub's firmware through a USB connection, he/she does not have to disconnect RS485 connection to other Expansion Hubs. + + The user still must use a USB connection to update an Expansion Hub's firmware. + + The user cannot update the Expansion Hub firmware for a downstream device that is daisy chained through an RS485 connection. + - If an Expansion Hub accidentally gets "bricked" the Robot Controller app is now more likely to recognize the Hub when it scans the USB bus. + + Robot Controller app should be able to detect an Expansion Hub, even if it accidentally was bricked in a previous update attempt. + + Robot Controller app should be able to install the firmware onto the Hub, even if if accidentally was bricked in a previous update attempt. + + * Resiliency + - FTC software can detect and enable an FTDI reset feature that is available with REV Robotics v1.8 Expansion Hub firmware and greater. + + When enabled, the Expansion Hub can detect if it hasn't communicated with the Robot Controller over the FTDI (USB) connection. + + If the Hub hasn't heard from the Robot Controller in a while, it will reset the FTDI connection. + + This action helps system recover from some ESD-induced disruptions. + - Various fixes to improve reliability of FTC software. + + * Blocks + - Fixed errors with string and list indices in blocks export to java. + - Support for USB connected UVC webcams. + - Refactored optimized Blocks Vuforia code to support Rover Ruckus image targets. + - Added programming blocks to support PIDF (proportional, integral, derivative and feed forward) motor control. + - Added formatting options (under Telemetry and Miscellaneous categories) so user can set how many decimal places to display a numerical value. + - Support to play audio files (which are uploaded through Blocks web interface) on Driver Station in addition to the Robot Controller. + - Fixed bug with Download Image of Blocks feature. + - Support for REV Robotics Blinkin LED Controller. + - Support for REV Robotics 2m Distance Sensor. + - Added support for a REV Touch Sensor (no longer have to configure as a generic digital device). + - Added blocks for DcMotorEx methods. + + These are enhanced methods that you can use when supported by the motor controller hardware. + + The REV Robotics Expansion Hub supports these enhanced methods. + + Enhanced methods include methods to get/set motor velocity (in encoder pulses per second), get/set PIDF coefficients, etc.. + + * Modest Improvements in Logging + - Decrease frequency of battery checker voltage statements. + - Removed non-FTC related log statements (wherever possible). + - Introduced a "Match Logging" feature. + + Under "Settings" a user can enable/disable this feature (it's disabled by default). + + If enabled, user provides a "Match Number" through the Driver Station user interface (top of the screen). + * The Match Number is used to create a log file specifically with log statements from that particular OpMode run. + * Match log files are stored in /sdcard/FIRST/matlogs on the Robot Controller. + * Once an OpMode run is complete, the Match Number is cleared. + * This is a convenient way to create a separate match log with statements only related to a specific OpMode run. + + * New Devices + - Support for REV Robotics Blinkin LED Controller. + - Support for REV Robotics 2m Distance Sensor. + - Added configuration option for REV 20:1 HD Hex Motor. + - Added support for a REV Touch Sensor (no longer have to configure as a generic digital device). + + * Miscellaneous + - Fixed some errors in the definitions for acceleration and velocity in our javadoc documentation. + - Added ability to play audio files on Driver Station + - When user is configuring an Expansion Hub, the LED on the Expansion Hub will change blink pattern (purple-cyan) to indicate which Hub is currently being configured. + - Renamed I2cSensorType to I2cDeviceType. + - Added an external sample OpMode that demonstrates localization using 2018-2019 (Rover Ruckus presented by QualComm) Vuforia targets. + - Added an external sample OpMode that demonstrates how to use the REV Robotics 2m Laser Distance Sensor. + - Added an external sample OpMode that demonstrates how to use the REV Robotics Blinkin LED Controller. + - Re-categorized external Java sample OpModes to "TeleOp" instead of "Autonomous". + +Known issues: + * Initial support for UVC compatible cameras + - UVC cameras seem to draw significant amount of current from the USB bus. + + This does not appear to present any problems for the REV Robotics Control Hub. + + This does seem to create stability problems when using some cameras with an Android phone-based Robot Controller. + + FTC Tech Team is investigating options to mitigate this issue with the phone-based Robot Controllers. + - There might be a possible deadlock which causes the RC to become unresponsive when using a UVC webcam with a Nougat Android Robot Controller. + + * Wireless + - When user selects a wireless channel, this channel does not necessarily persist if the phone is power cycled. + + Tech Team is hoping to eventually address this issue in a future release. + + Issue has been present since apps were introduced (i.e., it is not new with the v4.0 release). + - Wireless channel is not currently displayed for Wi-Fi Direct connections. + + * Miscellaneous + - The blink indication feature that shows which Expansion Hub is currently being configured does not work for a newly created configuration file. + + User has to first save a newly created configuration file and then close and re-edit the file in order for blink indicator to work. + +## Version 3.6 (built on 17.12.18) + +Changes include: + * Blocks Changes + - Uses updated Google Blockly software to allow users to edit their OpModes on Apple iOS devices (including iPad and iPhone). + - Improvement in Blocks tool to handle corrupt OpMode files. + - Autonomous OpModes should no longer get switched back to tele-op after re-opening them to be edited. + - The system can now detect type mismatches during runtime and alert the user with a message on the Driver Station. + * Updated javadoc documentation for setPower() method to reflect correct range of values (-1 to +1). + * Modified VuforiaLocalizerImpl to allow for user rendering of frames + - Added a user-overrideable onRenderFrame() method which gets called by the class's renderFrame() method. + +## Version 3.5 (built on 17.10.30) + +Changes with version 3.5 include: + * Introduced a fix to prevent random OpMode stops, which can occur after the Robot Controller app has been paused and then resumed (for example, when a user temporarily turns off the display of the Robot Controller phone, and then turns the screen back on). + * Introduced a fix to prevent random OpMode stops, which were previously caused by random peer disconnect events on the Driver Station. + * Fixes issue where log files would be closed on pause of the RC or DS, but not re-opened upon resume. + * Fixes issue with battery handler (voltage) start/stop race. + * Fixes issue where Android Studio generated OpModes would disappear from available list in certain situations. + * Fixes problem where OnBot Java would not build on REV Robotics Control Hub. + * Fixes problem where OnBot Java would not build if the date and time on the Robot Controller device was "rewound" (set to an earlier date/time). + * Improved error message on OnBot Java that occurs when renaming a file fails. + * Removed unneeded resources from android.jar binaries used by OnBot Java to reduce final size of Robot Controller app. + * Added MR_ANALOG_TOUCH_SENSOR block to Blocks Programming Tool. + +## Version 3.4 (built on 17.09.06) + +Changes with version 3.4 include: + * Added telemetry.update() statement for BlankLinearOpMode template. + * Renamed sample Block OpModes to be more consistent with Java samples. + * Added some additional sample Block OpModes. + * Reworded OnBot Java readme slightly. + +## Version 3.3 (built on 17.09.04) + +This version of the software includes improves for the FTC Blocks Programming Tool and the OnBot Java Programming Tool. + +Changes with verion 3.3 include: + * Android Studio ftc_app project has been updated to use Gradle Plugin 2.3.3. + * Android Studio ftc_app project is already using gradle 3.5 distribution. + * Robot Controller log has been renamed to /sdcard/RobotControllerLog.txt (note that this change was actually introduced w/ v3.2). + * Improvements in I2C reliability. + * Optimized I2C read for REV Expansion Hub, with v1.7 firmware or greater. + * Updated all external/samples (available through OnBot and in Android project folder). + * Vuforia + - Added support for VuMarks that will be used for the 2017-2018 season game. + * Blocks + - Update to latest Google Blockly release. + - Sample OpModes can be selected as a template when creating new OpMode. + - Fixed bug where the blocks would disappear temporarily when mouse button is held down. + - Added blocks for Range.clip and Range.scale. + - User can now disable/enable Block OpModes. + - Fix to prevent occasional Blocks deadlock. + * OnBot Java + - Significant improvements with autocomplete function for OnBot Java editor. + - Sample OpModes can be selected as a template when creating new OpMode. + - Fixes and changes to complete hardware setup feature. + - Updated (and more useful) onBot welcome message. + +Known issues: + * Android Studio + - After updating to the new v3.3 Android Studio project folder, if you get error messages indicating "InvalidVirtualFileAccessException" then you might need to do a File->Invalidate Caches / Restart to clear the error. + * OnBot Java + - Sometimes when you push the build button to build all OpModes, the RC returns an error message that the build failed. If you press the build button a second time, the build typically suceeds. + +## Version 3.2 (built on 17.08.02) + +This version of the software introduces the "OnBot Java" Development Tool. Similar to the FTC Blocks Development Tool, the FTC OnBot Java Development Tool allows a user to create, edit and build OpModes dynamically using only a Javascript-enabled web browser. + +The OnBot Java Development Tool is an integrated development environment (IDE) that is served up by the Robot Controller. OpModes are created and edited using a Javascript-enabled browser (Google Chromse is recommended). OpModes are saved on the Robot Controller Android device directly. + +The OnBot Java Development Tool provides a Java programming environment that does NOT need Android Studio. + + + +Changes with version 3.2 include: + * Enhanced web-based development tools + - Introduction of OnBot Java Development Tool. + - Web-based programming and management features are "always on" (user no longer needs to put Robot Controller into programming mode). + - Web-based management interface (where user can change Robot Controller name and also easily download Robot Controller log file). + - OnBot Java, Blocks and Management features available from web based interface. + +* Blocks Programming Development Tool: + - Changed "LynxI2cColorRangeSensor" block to "REV Color/range sensor" block. + - Fixed tooltip for ColorSensor.isLightOn block. + Added blocks for ColorSensor.getNormalizedColors and LynxI2cColorRangeSensor.getNormalizedColors. + +* Added example OpModes for digital touch sensor and REV Robotics Color Distance sensor. +* User selectable color themes. +* Includes many minor enhancements and fixes (too numerous to list). + +Known issues: +* Auto complete function is incomplete and does not support the following (for now): + - Access via *this* keyword + - Access via *super* keyword + - Members of the super cloass, not overridden by the class + - Any methods provided in the current class + - Inner classes + - Can't handle casted objects + - Any objects coming from an parenthetically enclosed expression + +## Version 3.10 (built on 17.05.09) + +This version of the software provides support for the REV Robotics Expansion Hub. This version also includes improvements in the USB communication layer in an effort to enhance system resiliency. If you were using a 2.x version of the software previously, updating to version 3.1 requires that you also update your Driver Station software in addition to updating the Robot Controller software. + +Also note that in version 3.10 software, the setMaxSpeed and getMaxSpeed methods are no longer available (not deprecated, they have been removed from the SDK). Also note that the the new 3.x software incorporates motor profiles that a user can select as he/she configures the robot. + +Changes include: + * Blocks changes + - Added VuforiaTrackableDefaultListener.getPose and Vuforia.trackPose blocks. + - Added optimized blocks support for Vuforia extended tracking. + - Added atan2 block to the math category. + - Added useCompetitionFieldTargetLocations parameter to Vuforia.initialize block. If set to false, the target locations are placed at (0,0,0) with target orientation as specified in https://github.com/gearsincorg/FTCVuforiaDemo/blob/master/Robot_Navigation.java tutorial OpMode. + * Incorporates additional improvements to USB comm layer to improve system resiliency (to recover from a greater number of communication disruptions). + +************************************************************************************** + +Additional Notes Regarding Version 3.00 (built on 17.04.13) + +In addition to the release changes listed below (see section labeled "Version 3.00 (built on 17.04.013)"), version 3.00 has the following important changes: + +1. Version 3.00 software uses a new version of the FTC Robocol (robot protocol). If you upgrade to v3.0 on the Robot Controller and/or Android Studio side, you must also upgrade the Driver Station software to match the new Robocol. +2. Version 3.00 software removes the setMaxSpeed and getMaxSpeed methods from the DcMotor class. If you have an OpMode that formerly used these methods, you will need to remove the references/calls to these methods. Instead, v3.0 provides the max speed information through the use of motor profiles that are selected by the user during robot configuration. +3. Version 3.00 software currently does not have a mechanism to disable extra i2c sensors. We hope to re-introduce this function with a release in the near future. + +************************************************************************************** + +## Version 3.00 (built on 17.04.13) + +*** Use this version of the software at YOUR OWN RISK!!! *** + +This software is being released as an "alpha" version. Use this version at your own risk! + +This pre-release software contains SIGNIFICANT changes, including changes to the Wi-Fi Direct pairing mechanism, rewrites of the I2C sensor classes, changes to the USB/FTDI layer, and the introduction of support for the REV Robotics Expansion Hub and the REV Robotics color-range-light sensor. These changes were implemented to improve the reliability and resiliency of the FTC control system. + +Please note, however, that version 3.00 is considered "alpha" code. This code is being released so that the FIRST community will have an opportunity to test the new REV Expansion Hub electronics module when it becomes available in May. The developers do not recommend using this code for critical applications (i.e., competition use). + +*** Use this version of the software at YOUR OWN RISK!!! *** + +Changes include: + * Major rework of sensor-related infrastructure. Includes rewriting sensor classes to implement synchronous I2C communication. + * Fix to reset Autonomous timer back to 30 seconds. + * Implementation of specific motor profiles for approved 12V motors (includes Tetrix, AndyMark, Matrix and REV models). + * Modest improvements to enhance Wi-Fi P2P pairing. + * Fixes telemetry log addition race. + * Publishes all the sources (not just a select few). + * Includes Block programming improvements + - Addition of optimized Vuforia blocks. + - Auto scrollbar to projects and sounds pages. + - Fixed blocks paste bug. + - Blocks execute after while-opModeIsActive loop (to allow for cleanup before exiting OpMode). + - Added gyro integratedZValue block. + - Fixes bug with projects page for Firefox browser. + - Added IsSpeaking block to AndroidTextToSpeech. + * Implements support for the REV Robotics Expansion Hub + - Implements support for integral REV IMU (physically installed on I2C bus 0, uses same Bosch BNO055 9 axis absolute orientation sensor as Adafruit 9DOF abs orientation sensor). - Implements support for REV color/range/light sensor. + - Provides support to update Expansion Hub firmware through FTC SDK. + - Detects REV firmware version and records in log file. + - Includes support for REV Control Hub (note that the REV Control Hub is not yet approved for FTC use). + - Implements FTC Blocks programming support for REV Expansion Hub and sensor hardware. + - Detects and alerts when I2C device disconnect. + +## Version 2.62 (built on 17.01.07) + * Added null pointer check before calling modeToByte() in finishModeSwitchIfNecessary method for ModernRoboticsUsbDcMotorController class. + * Changes to enhance Modern Robotics USB protocol robustness. + +## Version 2.61 (released on 16.12.19) + * Blocks Programming mode changes: + - Fix to correct issue when an exception was thrown because an OpticalDistanceSensor object appears twice in the hardware map (the second time as a LightSensor). + +## Version 2.6 (released on 16.12.16) + * Fixes for Gyro class: + - Improve (decrease) sensor refresh latency. + - fix isCalibrating issues. + * Blocks Programming mode changes: + - Blocks now ignores a device in the configuration xml if the name is empty. Other devices work in configuration work fine. + +## Version 2.5 (internal release on released on 16.12.13) + * Blocks Programming mode changes: + - Added blocks support for AdafruitBNO055IMU. + - Added Download OpMode button to FtcBocks.html. + - Added support for copying blocks in one OpMode and pasting them in an other OpMode. The clipboard content is stored on the phone, so the programming mode server must be running. + - Modified Utilities section of the toolbox. + - In Programming Mode, display information about the active connections. + - Fixed paste location when workspace has been scrolled. + - Added blocks support for the android Accelerometer. + - Fixed issue where Blocks Upload OpMode truncated name at first dot. + - Added blocks support for Android SoundPool. + - Added type safety to blocks for Acceleration. + - Added type safety to blocks for AdafruitBNO055IMU.Parameters. + - Added type safety to blocks for AnalogInput. + - Added type safety to blocks for AngularVelocity. + - Added type safety to blocks for Color. + - Added type safety to blocks for ColorSensor. + - Added type safety to blocks for CompassSensor. + - Added type safety to blocks for CRServo. + - Added type safety to blocks for DigitalChannel. + - Added type safety to blocks for ElapsedTime. + - Added type safety to blocks for Gamepad. + - Added type safety to blocks for GyroSensor. + - Added type safety to blocks for IrSeekerSensor. + - Added type safety to blocks for LED. + - Added type safety to blocks for LightSensor. + - Added type safety to blocks for LinearOpMode. + - Added type safety to blocks for MagneticFlux. + - Added type safety to blocks for MatrixF. + - Added type safety to blocks for MrI2cCompassSensor. + - Added type safety to blocks for MrI2cRangeSensor. + - Added type safety to blocks for OpticalDistanceSensor. + - Added type safety to blocks for Orientation. + - Added type safety to blocks for Position. + - Added type safety to blocks for Quaternion. + - Added type safety to blocks for Servo. + - Added type safety to blocks for ServoController. + - Added type safety to blocks for Telemetry. + - Added type safety to blocks for Temperature. + - Added type safety to blocks for TouchSensor. + - Added type safety to blocks for UltrasonicSensor. + - Added type safety to blocks for VectorF. + - Added type safety to blocks for Velocity. + - Added type safety to blocks for VoltageSensor. + - Added type safety to blocks for VuforiaLocalizer.Parameters. + - Added type safety to blocks for VuforiaTrackable. + - Added type safety to blocks for VuforiaTrackables. + - Added type safety to blocks for enums in AdafruitBNO055IMU.Parameters. + - Added type safety to blocks for AndroidAccelerometer, AndroidGyroscope, AndroidOrientation, and AndroidTextToSpeech. + +## Version 2.4 (released on 16.11.13) + * Fix to avoid crashing for nonexistent resources. + * Blocks Programming mode changes: + - Added blocks to support OpenGLMatrix, MatrixF, and VectorF. + - Added blocks to support AngleUnit, AxesOrder, AxesReference, CameraDirection, CameraMonitorFeedback, DistanceUnit, and TempUnit. + - Added blocks to support Acceleration. + - Added blocks to support LinearOpMode.getRuntime. + - Added blocks to support MagneticFlux and Position. + - Fixed typos. + - Made blocks for ElapsedTime more consistent with other objects. + - Added blocks to support Quaternion, Velocity, Orientation, AngularVelocity. + - Added blocks to support VuforiaTrackables, VuforiaTrackable, VuforiaLocalizer, VuforiaTrackableDefaultListener. + - Fixed a few blocks. + - Added type checking to new blocks. + - Updated to latest blockly. + - Added default variable blocks to navigation and matrix blocks. + - Fixed toolbox entry for openGLMatrix_rotation_withAxesArgs. + - When user downloads Blocks-generated OpMode, only the .blk file is downloaded. + - When user uploads Blocks-generated OpMode (.blk file), Javascript code is auto generated. + - Added DbgLog support. + - Added logging when a blocks file is read/written. + - Fixed bug to properly render blocks even if missing devices from configuration file. + - Added support for additional characters (not just alphanumeric) for the block file names (for download and upload). + - Added support for OpMode flavor (“Autonomous” or “TeleOp”) and group. + * Changes to Samples to prevent tutorial issues. + * Incorporated suggested changes from public pull 216 (“Replace .. paths”). + * Remove Servo Glitches when robot stopped. + * if user hits “Cancels” when editing a configuration file, clears the unsaved changes and reverts to original unmodified configuration. + * Added log info to help diagnose why the Robot Controller app was terminated (for example, by watch dog function). + * Added ability to transfer log from the controller. + * Fixed inconsistency for AngularVelocity + * Limit unbounded growth of data for telemetry. If user does not call telemetry.update() for LinearOpMode in a timely manner, data added for telemetry might get lost if size limit is exceeded. + +## Version 2.35 (released on 16.10.06) + * Blockly programming mode - Removed unnecesary idle() call from blocks for new project. + +## Version 2.30 (released on 16.10.05) + * Blockly programming mode: + - Mechanism added to save Blockly OpModes from Programming Mode Server onto local device + - To avoid clutter, blocks are displayed in categorized folders + - Added support for DigitalChannel + - Added support for ModernRoboticsI2cCompassSensor + - Added support for ModernRoboticsI2cRangeSensor + - Added support for VoltageSensor + - Added support for AnalogInput + - Added support for AnalogOutput + - Fix for CompassSensor setMode block + * Vuforia + - Fix deadlock / make camera data available while Vuforia is running. + - Update to Vuforia 6.0.117 (recommended by Vuforia and Google to close security loophole). + * Fix for autonomous 30 second timer bug (where timer was in effect, even though it appeared to have timed out). + * opModeIsActive changes to allow cleanup after OpMode is stopped (with enforced 2 second safety timeout). + * Fix to avoid reading i2c twice. + * Updated sample OpModes. + * Improved logging and fixed intermittent freezing. + * Added digital I/O sample. + * Cleaned up device names in sample OpModes to be consistent with Pushbot guide. + * Fix to allow use of IrSeekerSensorV3. + +## Version 2.20 (released on 16.09.08) + * Support for Modern Robotics Compass Sensor. + * Support for Modern Robotics Range Sensor. + * Revise device names for Pushbot templates to match the names used in Pushbot guide. + * Fixed bug so that IrSeekerSensorV3 device is accessible as IrSeekerSensor in hardwareMap. + * Modified computer vision code to require an individual Vuforia license (per legal requirement from PTC). + * Minor fixes. + * Blockly enhancements: + - Support for Voltage Sensor. + - Support for Analog Input. + - Support for Analog Output. + - Support for Light Sensor. + - Support for Servo Controller. + +## Version 2.10 (released on 16.09.03) + * Support for Adafruit IMU. + * Improvements to ModernRoboticsI2cGyro class + - Block on reset of z axis. + - isCalibrating() returns true while gyro is calibration. + * Updated sample gyro program. + * Blockly enhancements + - support for android.graphics.Color. + - added support for ElapsedTime. + - improved look and legibility of blocks. + - support for compass sensor. + - support for ultrasonic sensor. + - support for IrSeeker. + - support for LED. + - support for color sensor. + - support for CRServo + - prompt user to configure robot before using programming mode. + * Provides ability to disable audio cues. + * various bug fixes and improvements. + +## Version 2.00 (released on 16.08.19) + * This is the new release for the upcoming 2016-2017 FIRST Tech Challenge Season. + * Channel change is enabled in the FTC Robot Controller app for Moto G 2nd and 3rd Gen phones. + * Users can now use annotations to register/disable their OpModes. + * Changes in the Android SDK, JDK and build tool requirements (minsdk=19, java 1.7, build tools 23.0.3). + * Standardized units in analog input. + * Cleaned up code for existing analog sensor classes. + * setChannelMode and getChannelMode were REMOVED from the DcMotorController class. This is important - we no longer set the motor modes through the motor controller. + * setMode and getMode were added to the DcMotor class. + * ContinuousRotationServo class has been added to the FTC SDK. + * Range.clip() method has been overloaded so it can support this operation for int, short and byte integers. + * Some changes have been made (new methods added) on how a user can access items from the hardware map. + * Users can now set the zero power behavior for a DC motor so that the motor will brake or float when power is zero. + * Prototype Blockly Programming Mode has been added to FTC Robot Controller. Users can place the Robot Controller into this mode, and then use a device (such as a laptop) that has a Javascript enabled browser to write Blockly-based OpModes directly onto the Robot Controller. + * Users can now configure the robot remotely through the FTC Driver Station app. + * Android Studio project supports Android Studio 2.1.x and compile SDK Version 23 (Marshmallow). + * Vuforia Computer Vision SDK integrated into FTC SDK. Users can use sample vision targets to get localization information on a standard FTC field. + * Project structure has been reorganized so that there is now a TeamCode package that users can use to place their local/custom OpModes into this package. + * Inspection function has been integrated into the FTC Robot Controller and Driver Station Apps (Thanks Team HazMat… 9277 & 10650!). + * Audio cues have been incorporated into FTC SDK. + * Swap mechanism added to FTC Robot Controller configuration activity. For example, if you have two motor controllers on a robot, and you misidentified them in your configuration file, you can use the Swap button to swap the devices within the configuration file (so you do not have to manually re-enter in the configuration info for the two devices). + * Fix mechanism added to all user to replace an electronic module easily. For example, suppose a servo controller dies on your robot. You replace the broken module with a new module, which has a different serial number from the original servo controller. You can use the Fix button to automatically reconfigure your configuration file to use the serial number of the new module. + * Improvements made to fix resiliency and responsiveness of the system. + * For LinearOpMode the user now must for a telemetry.update() to update the telemetry data on the driver station. This update() mechanism ensures that the driver station gets the updated data properly and at the same time. + * The Auto Configure function of the Robot Controller is now template based. If there is a commonly used robot configuration, a template can be created so that the Auto Configure mechanism can be used to quickly configure a robot of this type. + * The logic to detect a runaway OpMode (both in the LinearOpMode and OpMode types) and to abort the run, then auto recover has been improved/implemented. + * Fix has been incorporated so that Logitech F310 gamepad mappings will be correct for Marshmallow users. + +## Release 16.07.08 + + * For the ftc_app project, the gradle files have been modified to support Android Studio 2.1.x. + +## Release 16.03.30 + + * For the MIT App Inventor, the design blocks have new icons that better represent the function of each design component. + * Some changes were made to the shutdown logic to ensure the robust shutdown of some of our USB services. + * A change was made to LinearOpMode so as to allow a given instance to be executed more than once, which is required for the App Inventor. + * Javadoc improved/updated. + +## Release 16.03.09 + + * Changes made to make the FTC SDK synchronous (significant change!) + - waitOneFullHardwareCycle() and waitForNextHardwareCycle() are no longer needed and have been deprecated. + - runOpMode() (for a LinearOpMode) is now decoupled from the system's hardware read/write thread. + - loop() (for an OpMode) is now decoupled from the system's hardware read/write thread. + - Methods are synchronous. + - For example, if you call setMode(DcMotorController.RunMode.RESET_ENCODERS) for a motor, the encoder is guaranteed to be reset when the method call is complete. + - For legacy module (NXT compatible), user no longer has to toggle between read and write modes when reading from or writing to a legacy device. + * Changes made to enhance reliability/robustness during ESD event. + * Changes made to make code thread safe. + * Debug keystore added so that user-generated robot controller APKs will all use the same signed key (to avoid conflicts if a team has multiple developer laptops for example). + * Firmware version information for Modern Robotics modules are now logged. + * Changes made to improve USB comm reliability and robustness. + * Added support for voltage indicator for legacy (NXT-compatible) motor controllers. + * Changes made to provide auto stop capabilities for OpModes. + - A LinearOpMode class will stop when the statements in runOpMode() are complete. User does not have to push the stop button on the driver station. + - If an OpMode is stopped by the driver station, but there is a run away/uninterruptible thread persisting, the app will log an error message then force itself to crash to stop the runaway thread. + * Driver Station UI modified to display lowest measured voltage below current voltage (12V battery). + * Driver Station UI modified to have color background for current voltage (green=good, yellow=caution, red=danger, extremely low voltage). + * javadoc improved (edits and additional classes). + * Added app build time to About activity for driver station and robot controller apps. + * Display local IP addresses on Driver Station About activity. + * Added I2cDeviceSynchImpl. + * Added I2cDeviceSync interface. + * Added seconds() and milliseconds() to ElapsedTime for clarity. + * Added getCallbackCount() to I2cDevice. + * Added missing clearI2cPortActionFlag. + * Added code to create log messages while waiting for LinearOpMode shutdown. + * Fix so Wi-Fi Direct Config activity will no longer launch multiple times. + * Added the ability to specify an alternate i2c address in software for the Modern Robotics gyro. + +## Release 16.02.09 + + * Improved battery checker feature so that voltage values get refreshed regularly (every 250 msec) on Driver Station (DS) user interface. + * Improved software so that Robot Controller (RC) is much more resilient and “self-healing” to USB disconnects: + - If user attempts to start/restart RC with one or more module missing, it will display a warning but still start up. + - When running an OpMode, if one or more modules gets disconnected, the RC & DS will display warnings,and robot will keep on working in spite of the missing module(s). + - If a disconnected module gets physically reconnected the RC will auto detect the module and the user will regain control of the recently connected module. + - Warning messages are more helpful (identifies the type of module that’s missing plus its USB serial number). + * Code changes to fix the null gamepad reference when users try to reference the gamepads in the init() portion of their OpMode. + * NXT light sensor output is now properly scaled. Note that teams might have to readjust their light threshold values in their OpModes. + * On DS user interface, gamepad icon for a driver will disappear if the matching gamepad is disconnected or if that gamepad gets designated as a different driver. + * Robot Protocol (ROBOCOL) version number info is displayed in About screen on RC and DS apps. + * Incorporated a display filter on pairing screen to filter out devices that don’t use the “-“ format. This filter can be turned off to show all Wi-Fi Direct devices. + * Updated text in License file. + * Fixed formatting error in OpticalDistanceSensor.toString(). + * Fixed issue on with a blank (“”) device name that would disrupt Wi-Fi Direct Pairing. + * Made a change so that the Wi-Fi info and battery info can be displayed more quickly on the DS upon connecting to RC. + * Improved javadoc generation. + * Modified code to make it easier to support language localization in the future. + +## Release 16.01.04 + + * Updated compileSdkVersion for apps + * Prevent Wi-Fi from entering power saving mode + * removed unused import from driver station + * Corrrected "Dead zone" joystick code. + * LED.getDeviceName and .getConnectionInfo() return null + * apps check for ROBOCOL_VERSION mismatch + * Fix for Telemetry also has off-by-one errors in its data string sizing / short size limitations error + * User telemetry output is sorted. + * added formatting variants to DbgLog and RobotLog APIs + * code modified to allow for a long list of OpMode names. + * changes to improve thread safety of RobocolDatagramSocket + * Fix for "missing hardware leaves robot controller disconnected from driver station" error + * fix for "fast tapping of Init/Start causes problems" (toast is now only instantiated on UI thread). + * added some log statements for thread life cycle. + * moved gamepad reset logic inside of initActiveOpMode() for robustness + * changes made to mitigate risk of race conditions on public methods. + * changes to try and flag when Wi-Fi Direct name contains non-printable characters. + * fix to correct race condition between .run() and .close() in ReadWriteRunnableStandard. + * updated FTDI driver + * made ReadWriteRunnableStanard interface public. + * fixed off-by-one errors in Command constructor + * moved specific hardware implmentations into their own package. + * moved specific gamepad implemnatations to the hardware library. + * changed LICENSE file to new BSD version. + * fixed race condition when shutting down Modern Robotics USB devices. + * methods in the ColorSensor classes have been synchronized. + * corrected isBusy() status to reflect end of motion. + * corrected "back" button keycode. + * the notSupported() method of the GyroSensor class was changed to protected (it should not be public). + +## Release 15.11.04.001 + + * Added Support for Modern Robotics Gyro. + - The GyroSensor class now supports the MR Gyro Sensor. + - Users can access heading data (about Z axis) + - Users can also access raw gyro data (X, Y, & Z axes). + - Example MRGyroTest.java OpMode included. + * Improved error messages + - More descriptive error messages for exceptions in user code. + * Updated DcMotor API + * Enable read mode on new address in setI2cAddress + * Fix so that driver station app resets the gamepads when switching OpModes. + * USB-related code changes to make USB comm more responsive and to display more explicit error messages. + - Fix so that USB will recover properly if the USB bus returns garbage data. + - Fix USB initializtion race condition. + - Better error reporting during FTDI open. + - More explicit messages during USB failures. + - Fixed bug so that USB device is closed if event loop teardown method was not called. + * Fixed timer UI issue + * Fixed duplicate name UI bug (Legacy Module configuration). + * Fixed race condition in EventLoopManager. + * Fix to keep references stable when updating gamepad. + * For legacy Matrix motor/servo controllers removed necessity of appending "Motor" and "Servo" to controller names. + * Updated HT color sensor driver to use constants from ModernRoboticsUsbLegacyModule class. + * Updated MR color sensor driver to use constants from ModernRoboticsUsbDeviceInterfaceModule class. + * Correctly handle I2C Address change in all color sensors + * Updated/cleaned up OpModes. + - Updated comments in LinearI2cAddressChange.java example OpMode. + - Replaced the calls to "setChannelMode" with "setMode" (to match the new of the DcMotor method). + - Removed K9AutoTime.java OpMode. + - Added MRGyroTest.java OpMode (demonstrates how to use MR Gyro Sensor). + - Added MRRGBExample.java OpMode (demonstrates how to use MR Color Sensor). + - Added HTRGBExample.java OpMode (demonstrates how to use HT legacy color sensor). + - Added MatrixControllerDemo.java (demonstrates how to use legacy Matrix controller). + * Updated javadoc documentation. + * Updated release .apk files for Robot Controller and Driver Station apps. + +## Release 15.10.06.002 + + * Added support for Legacy Matrix 9.6V motor/servo controller. + * Cleaned up build.gradle file. + * Minor UI and bug fixes for driver station and robot controller apps. + * Throws error if Ultrasonic sensor (NXT) is not configured for legacy module port 4 or 5. + + +## Release 15.08.03.001 + + * New user interfaces for FTC Driver Station and FTC Robot Controller apps. + * An init() method is added to the OpMode class. + - For this release, init() is triggered right before the start() method. + - Eventually, the init() method will be triggered when the user presses an "INIT" button on driver station. + - The init() and loop() methods are now required (i.e., need to be overridden in the user's OpMode). + - The start() and stop() methods are optional. + * A new LinearOpMode class is introduced. + - Teams can use the LinearOpMode mode to create a linear (not event driven) program model. + - Teams can use blocking statements like Thread.sleep() within a linear OpMode. + * The API for the Legacy Module and Core Device Interface Module have been updated. + - Support for encoders with the Legacy Module is now working. + * The hardware loop has been updated for better performance. diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index b42f0fe..d845fd6 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -23,18 +23,10 @@ android { } } -repositories { - maven { - url = 'https://maven.brott.dev/' - } -} - dependencies { implementation project(':FtcRobotController') annotationProcessor files('lib/OpModeAnnotationProcessor.jar') - implementation "com.acmerobotics.roadrunner:ftc:0.1.13" - implementation "com.acmerobotics.roadrunner:core:1.0.0" - implementation "com.acmerobotics.roadrunner:actions:1.0.0" - implementation "com.acmerobotics.dashboard:dashboard:0.4.14" + implementation 'com.fasterxml.jackson.core:jackson-databind:2.12.7' + implementation 'org.jetbrains.kotlin:kotlin-stdlib:1.4.21' } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drawing.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/Drawing.java similarity index 93% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drawing.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/Drawing.java index 38114d8..b3f9260 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Drawing.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/Drawing.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode; +package org.firstinspires.ftc.classic; import com.acmerobotics.dashboard.canvas.Canvas; import com.acmerobotics.roadrunner.Pose2d; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Localizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/Localizer.java similarity index 79% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Localizer.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/Localizer.java index 974ab79..19647c5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Localizer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/Localizer.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode; +package org.firstinspires.ftc.classic; import com.acmerobotics.roadrunner.Time; import com.acmerobotics.roadrunner.Twist2dDual; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/MecanumDrive.java similarity index 97% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/MecanumDrive.java index 8675eb2..103e119 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/MecanumDrive.java @@ -1,6 +1,6 @@ -package org.firstinspires.ftc.teamcode; +package org.firstinspires.ftc.classic; -import static org.firstinspires.ftc.teamcode.MecanumDriveParameters.*; +import static org.firstinspires.ftc.classic.MecanumDriveParameters.*; import androidx.annotation.NonNull; @@ -36,17 +36,16 @@ import com.qualcomm.hardware.lynx.LynxModule; import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; -import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.IMU; import com.qualcomm.robotcore.hardware.VoltageSensor; import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles; -import org.firstinspires.ftc.teamcode.messages.DriveCommandMessage; -import org.firstinspires.ftc.teamcode.messages.MecanumCommandMessage; -import org.firstinspires.ftc.teamcode.messages.MecanumLocalizerInputsMessage; -import org.firstinspires.ftc.teamcode.messages.PoseMessage; +import org.firstinspires.ftc.classic.messages.DriveCommandMessage; +import org.firstinspires.ftc.classic.messages.MecanumCommandMessage; +import org.firstinspires.ftc.classic.messages.MecanumLocalizerInputsMessage; +import org.firstinspires.ftc.classic.messages.PoseMessage; import java.lang.Math; import java.util.Arrays; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDriveParameters.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/MecanumDriveParameters.java similarity index 90% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDriveParameters.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/MecanumDriveParameters.java index cf20752..85d6d52 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDriveParameters.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/MecanumDriveParameters.java @@ -1,6 +1,4 @@ -package org.firstinspires.ftc.teamcode; - -import com.qualcomm.robotcore.hardware.DcMotorEx; +package org.firstinspires.ftc.classic; public class MecanumDriveParameters { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/SensorIMUOrthogonal.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/SensorIMUOrthogonal.java similarity index 99% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/SensorIMUOrthogonal.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/SensorIMUOrthogonal.java index f143267..28df67f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/SensorIMUOrthogonal.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/SensorIMUOrthogonal.java @@ -27,7 +27,7 @@ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ -package org.firstinspires.ftc.teamcode; +package org.firstinspires.ftc.classic; import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; import com.qualcomm.robotcore.eventloop.opmode.Disabled; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TankDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/TankDrive.java similarity index 98% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TankDrive.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/TankDrive.java index 4f1ade9..1aa2e9f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TankDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/TankDrive.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode; +package org.firstinspires.ftc.classic; import androidx.annotation.NonNull; @@ -43,14 +43,13 @@ import com.qualcomm.hardware.lynx.LynxModule; import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; -import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.VoltageSensor; -import org.firstinspires.ftc.teamcode.messages.DriveCommandMessage; -import org.firstinspires.ftc.teamcode.messages.PoseMessage; -import org.firstinspires.ftc.teamcode.messages.TankCommandMessage; -import org.firstinspires.ftc.teamcode.messages.TankLocalizerInputsMessage; +import org.firstinspires.ftc.classic.messages.DriveCommandMessage; +import org.firstinspires.ftc.classic.messages.PoseMessage; +import org.firstinspires.ftc.classic.messages.TankCommandMessage; +import org.firstinspires.ftc.classic.messages.TankLocalizerInputsMessage; import java.util.ArrayList; import java.util.Arrays; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/ThreeDeadWheelLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/ThreeDeadWheelLocalizer.java similarity index 96% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/ThreeDeadWheelLocalizer.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/ThreeDeadWheelLocalizer.java index 9643b2f..c5cfd0d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/ThreeDeadWheelLocalizer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/ThreeDeadWheelLocalizer.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode; +package org.firstinspires.ftc.classic; import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.roadrunner.DualNum; @@ -12,10 +12,9 @@ import com.acmerobotics.roadrunner.ftc.OverflowEncoder; import com.acmerobotics.roadrunner.ftc.PositionVelocityPair; import com.acmerobotics.roadrunner.ftc.RawEncoder; import com.qualcomm.robotcore.hardware.DcMotorEx; -import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; -import org.firstinspires.ftc.teamcode.messages.ThreeDeadWheelInputsMessage; +import org.firstinspires.ftc.classic.messages.ThreeDeadWheelInputsMessage; @Config public final class ThreeDeadWheelLocalizer implements Localizer { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TwoDeadWheelLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/TwoDeadWheelLocalizer.java similarity index 96% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TwoDeadWheelLocalizer.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/TwoDeadWheelLocalizer.java index edc4e85..fd8837b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TwoDeadWheelLocalizer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/TwoDeadWheelLocalizer.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode; +package org.firstinspires.ftc.classic; import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.roadrunner.DualNum; @@ -13,14 +13,13 @@ import com.acmerobotics.roadrunner.ftc.OverflowEncoder; import com.acmerobotics.roadrunner.ftc.PositionVelocityPair; import com.acmerobotics.roadrunner.ftc.RawEncoder; import com.qualcomm.robotcore.hardware.DcMotorEx; -import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.IMU; import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; import org.firstinspires.ftc.robotcore.external.navigation.AngularVelocity; import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles; -import org.firstinspires.ftc.teamcode.messages.TwoDeadWheelInputsMessage; +import org.firstinspires.ftc.classic.messages.TwoDeadWheelInputsMessage; @Config public final class TwoDeadWheelLocalizer implements Localizer { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/DriveCommandMessage.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/DriveCommandMessage.java similarity index 94% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/DriveCommandMessage.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/DriveCommandMessage.java index 01565c3..a1378f8 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/DriveCommandMessage.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/DriveCommandMessage.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.messages; +package org.firstinspires.ftc.classic.messages; import com.acmerobotics.roadrunner.PoseVelocity2dDual; import com.acmerobotics.roadrunner.Time; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/MecanumCommandMessage.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/MecanumCommandMessage.java similarity index 92% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/MecanumCommandMessage.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/MecanumCommandMessage.java index bfc3c58..100d78e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/MecanumCommandMessage.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/MecanumCommandMessage.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.messages; +package org.firstinspires.ftc.classic.messages; public final class MecanumCommandMessage { public long timestamp; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/MecanumLocalizerInputsMessage.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/MecanumLocalizerInputsMessage.java similarity index 95% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/MecanumLocalizerInputsMessage.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/MecanumLocalizerInputsMessage.java index a48078f..ad2a937 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/MecanumLocalizerInputsMessage.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/MecanumLocalizerInputsMessage.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.messages; +package org.firstinspires.ftc.classic.messages; import com.acmerobotics.roadrunner.ftc.PositionVelocityPair; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/PoseMessage.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/PoseMessage.java similarity index 88% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/PoseMessage.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/PoseMessage.java index c87bfa0..79a577e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/PoseMessage.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/PoseMessage.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.messages; +package org.firstinspires.ftc.classic.messages; import com.acmerobotics.roadrunner.Pose2d; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/TankCommandMessage.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/TankCommandMessage.java similarity index 89% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/TankCommandMessage.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/TankCommandMessage.java index c9ea1df..67672e3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/TankCommandMessage.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/TankCommandMessage.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.messages; +package org.firstinspires.ftc.classic.messages; public final class TankCommandMessage { public long timestamp; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/TankLocalizerInputsMessage.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/TankLocalizerInputsMessage.java similarity index 91% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/TankLocalizerInputsMessage.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/TankLocalizerInputsMessage.java index 96cc009..6572b4c 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/TankLocalizerInputsMessage.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/TankLocalizerInputsMessage.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.messages; +package org.firstinspires.ftc.classic.messages; import com.acmerobotics.roadrunner.ftc.PositionVelocityPair; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/ThreeDeadWheelInputsMessage.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/ThreeDeadWheelInputsMessage.java similarity index 91% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/ThreeDeadWheelInputsMessage.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/ThreeDeadWheelInputsMessage.java index d291250..535a21e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/ThreeDeadWheelInputsMessage.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/ThreeDeadWheelInputsMessage.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.messages; +package org.firstinspires.ftc.classic.messages; import com.acmerobotics.roadrunner.ftc.PositionVelocityPair; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/TwoDeadWheelInputsMessage.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/TwoDeadWheelInputsMessage.java similarity index 96% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/TwoDeadWheelInputsMessage.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/TwoDeadWheelInputsMessage.java index ef0b692..7f4481b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/messages/TwoDeadWheelInputsMessage.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/messages/TwoDeadWheelInputsMessage.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.messages; +package org.firstinspires.ftc.classic.messages; import com.acmerobotics.roadrunner.ftc.PositionVelocityPair; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/LocalizationTest.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/LocalizationTest.java similarity index 93% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/LocalizationTest.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/LocalizationTest.java index 803ea15..1d945ca 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/LocalizationTest.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/LocalizationTest.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.tuning; +package org.firstinspires.ftc.classic.tuning; import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; @@ -8,9 +8,9 @@ import com.acmerobotics.roadrunner.PoseVelocity2d; import com.acmerobotics.roadrunner.Vector2d; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import org.firstinspires.ftc.teamcode.Drawing; -import org.firstinspires.ftc.teamcode.MecanumDrive; -import org.firstinspires.ftc.teamcode.TankDrive; +import org.firstinspires.ftc.classic.Drawing; +import org.firstinspires.ftc.classic.MecanumDrive; +import org.firstinspires.ftc.classic.TankDrive; public class LocalizationTest extends LinearOpMode { @Override diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/ManualFeedbackTuner.java similarity index 91% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/ManualFeedbackTuner.java index 0b6f193..f658126 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/ManualFeedbackTuner.java @@ -1,13 +1,13 @@ -package org.firstinspires.ftc.teamcode.tuning; +package org.firstinspires.ftc.classic.tuning; import com.acmerobotics.roadrunner.Pose2d; import com.acmerobotics.roadrunner.ftc.Actions; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import org.firstinspires.ftc.teamcode.MecanumDrive; -import org.firstinspires.ftc.teamcode.TankDrive; -import org.firstinspires.ftc.teamcode.ThreeDeadWheelLocalizer; -import org.firstinspires.ftc.teamcode.TwoDeadWheelLocalizer; +import org.firstinspires.ftc.classic.MecanumDrive; +import org.firstinspires.ftc.classic.TankDrive; +import org.firstinspires.ftc.classic.ThreeDeadWheelLocalizer; +import org.firstinspires.ftc.classic.TwoDeadWheelLocalizer; public final class ManualFeedbackTuner extends LinearOpMode { public static double DISTANCE = 64; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/SplineTest.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/SplineTest.java similarity index 89% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/SplineTest.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/SplineTest.java index d70825e..98b4c64 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/SplineTest.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/SplineTest.java @@ -1,12 +1,12 @@ -package org.firstinspires.ftc.teamcode.tuning; +package org.firstinspires.ftc.classic.tuning; import com.acmerobotics.roadrunner.Pose2d; import com.acmerobotics.roadrunner.Vector2d; import com.acmerobotics.roadrunner.ftc.Actions; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; -import org.firstinspires.ftc.teamcode.MecanumDrive; -import org.firstinspires.ftc.teamcode.TankDrive; +import org.firstinspires.ftc.classic.MecanumDrive; +import org.firstinspires.ftc.classic.TankDrive; public final class SplineTest extends LinearOpMode { @Override diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/TuningOpModes.java similarity index 96% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/TuningOpModes.java index b95e872..647ea0f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/classic/tuning/TuningOpModes.java @@ -1,4 +1,4 @@ -package org.firstinspires.ftc.teamcode.tuning; +package org.firstinspires.ftc.classic.tuning; import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.config.reflection.ReflectionConfig; @@ -22,10 +22,10 @@ import com.qualcomm.robotcore.eventloop.opmode.OpModeManager; import com.qualcomm.robotcore.eventloop.opmode.OpModeRegistrar; import org.firstinspires.ftc.robotcore.internal.opmode.OpModeMeta; -import org.firstinspires.ftc.teamcode.MecanumDrive; -import org.firstinspires.ftc.teamcode.TankDrive; -import org.firstinspires.ftc.teamcode.ThreeDeadWheelLocalizer; -import org.firstinspires.ftc.teamcode.TwoDeadWheelLocalizer; +import org.firstinspires.ftc.classic.MecanumDrive; +import org.firstinspires.ftc.classic.TankDrive; +import org.firstinspires.ftc.classic.ThreeDeadWheelLocalizer; +import org.firstinspires.ftc.classic.TwoDeadWheelLocalizer; import java.util.ArrayList; import java.util.Arrays; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/LOCALIZATION.md b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/LOCALIZATION.md new file mode 100644 index 0000000..18d1206 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/LOCALIZATION.md @@ -0,0 +1,260 @@ +## Overview +This is the localization system developed for the Pedro Pathing path follower. These localizers use +the pose exponential method of localization. It's basically a way of turning movements from the +robot's coordinate frame to the global coordinate frame. If you're interested in reading more about +it, then check out pages 177 - 183 of [Controls Engineering in the FIRST Robotics Competition](https://file.tavsys.net/control/controls-engineering-in-frc.pdf) +by Tyler Veness. However, the OTOS localizer uses its own onboard system for calculating localization, +which I do not know about. + +## Setting Your Localizer +Go to line `70` in the `PoseUpdater` class, and replace the `new ThreeWheelLocalizer(hardwareMap)` +with the localizer that applies to you: +* If you're using drive encoders, put `new DriveEncoderLocalizer(hardwareMap)` +* If you're using two wheel odometry, put `new TwoWheelLocalizer(hardwareMap)` +* If you're using three wheel odometry, put `new ThreeWheelLocalizer(hardwareMap)`, so basically + don't change it from the default +* If you're using three wheel odometry with the IMU, put `new ThreeWheelIMULocalizer(hardwareMap)` +* If you're using OTOS, put `new OTOSLocalizer(hardwareMap)` + +## Tuning +To start, you'll want to select your localizer of choice. Below, I'll have instructions for the drive +encoder localizer, two tracking wheel localizer, the three tracking wheel localizer, the three +wheel with IMU localizer, and the OTOS localizer offered in Pedro Pathing. Scroll down to the section +that applies to you and follow the directions there. + +# Drive Encoders +* First, you'll need all of your drive motors to have encoders attached. +* Then, go to `DriveEncoderLocalizer.java`. The motor names are already set, so you don't have to do + anything to change the encoder names there. +* Then, reverse the direction of any encoders so that all encoders tick up when the robot is moving forward. +* Now, you'll have to tune the multipliers. These convert your measurements from encoder ticks into + inches or radians, essentially scaling your localizer so that your numbers are accurate to the real + world. +* First, start with the `Turn Localizer Tuner`. You'll want to position your robot to be facing + in a direction you can easily find again, like lining up an edge of the robot against a field tile edge. + By default, you should spin the robot for one rotation going counterclockwise. Once you've spun + exactly that one rotation, or whatever you set that value to, then the turn multiplier will be shown + as the second number shown. The first number is how far the robot thinks you've spun, and the second + number is the multiplier you need to have to scale your current readings to your goal of one rotation, + or the custom set angle. Feel free to run a few more tests and average the results. Once you have + this multiplier, then replace `TURN_TICKS_TO_RADIANS` in the localizer with your multiplier. Make sure + you replace the number, not add on or multiply it to the previous number. The tuner takes into + account your current multiplier. +* Next, go on to `Forward Localizer Tuner`. You'll want to position a ruler alongside your robot. + By default, you'll want to push the robot 30 inches forward. Once you've pushed that far, or whatever + you set that value to, then the forward multiplier will be shown as the second number shown. The + first number is how far the robot thinks you've gone, and the second number is the multiplier you + need to have to scale your current readings to your goal of 30 inches, or the custom set distance. + Feel free to run a few more tests and average the results. Once you have this multiplier, then + replace `FORWARD_TICKS_TO_INCHES` in the localizer with your multiplier. Make sure you replace the number, + not add on or multiply it to the previous number. The tuner takes into account your current multiplier. +* Finally, go to `Lateral Localizer Tuner`. You'll want to position a ruler alongside your robot. + By default, you'll want to push the robot 30 inches to the right. Once you've pushed that far, or whatever + you set that value to, then the lateral multiplier will be shown as the second number shown. The + first number is how far the robot thinks you've gone, and the second number is the multiplier you + need to have to scale your current readings to your goal of 30 inches, or the custom set distance. + Feel free to run a few more tests and average the results. Once you have this multiplier, then + replace `STRAFE_TICKS_TO_INCHES` in the localizer with your multiplier. Make sure you replace the number, + not add on or multiply it to the previous number. The tuner takes into account your current multiplier. +* Once you're done with all this, your localizer should be tuned. To test it out, you can go to + `Localization Test` and push around or drive around your robot. Go to [FTC Dashboard](http://192.168.43.1:8080/dash) + and on the top right, switch the drop down from the default view to the field view. Then, on the bottom + left corner, you should see a field and the robot being drawn on the field. You can then move your + robot around and see if the movements look accurate on FTC Dashboard. If they don't, then you'll + want to re-run some of the previous steps. Otherwise, congrats on tuning your localizer! + +# Two Wheel Localizer +* First, you'll need a Control Hub with a working IMU, and two odometry wheels connected to motor + encoder ports on a hub. +* Then, go to `TwoWheelLocalizer.java`. First, in the constructor, enter in the positions of your + tracking wheels relative to the center of the wheels of the robot. The positions are in inches, so + convert measurements accordingly. Use the comment above the class declaration to help you with the + coordinates. +* Next, go to where it tells you to replace the current statements with your encoder ports in the constructor. + Replace the `deviceName` parameter with the name of the port that the encoder is connected to. The + variable names correspond to which tracking wheel should be connected. +* After that, go to the instantiation of the IMU and change the orientation of the IMU to match that + of your robot's. +* Then, reverse the direction of any encoders so that the forward encoder ticks up when the robot + is moving forward and the strafe encoder ticks up when the robot moves right. +* Now, you'll have to tune the multipliers. These convert your measurements from encoder ticks into + inches or radians, essentially scaling your localizer so that your numbers are accurate to the real + world. +* You actually won't need the turning tuner for this one, since the IMU in the Control Hub will take + care of the heading readings. +* First, start with the `Forward Localizer Tuner`. You'll want to position a ruler alongside your robot. + By default, you'll want to push the robot 30 inches forward. Once you've pushed that far, or whatever + you set that value to, then the forward multiplier will be shown as the second number shown. The + first number is how far the robot thinks you've gone, and the second number is the multiplier you + need to have to scale your current readings to your goal of 30 inches, or the custom set distance. + Feel free to run a few more tests and average the results. Once you have this multiplier, then + replace `FORWARD_TICKS_TO_INCHES` in the localizer with your multiplier. Make sure you replace the number, + not add on or multiply it to the previous number. The tuner takes into account your current multiplier. +* Finally, go to `Lateral Localizer Tuner`. You'll want to position a ruler alongside your robot. + By default, you'll want to push the robot 30 inches to the right. Once you've pushed that far, or whatever + you set that value to, then the lateral multiplier will be shown as the second number shown. The + first number is how far the robot thinks you've gone, and the second number is the multiplier you + need to have to scale your current readings to your goal of 30 inches, or the custom set distance. + Feel free to run a few more tests and average the results. Once you have this multiplier, then + replace `STRAFE_TICKS_TO_INCHES` in the localizer with your multiplier. Make sure you replace the number, + not add on or multiply it to the previous number. The tuner takes into account your current multiplier. +* Once you're done with all this, your localizer should be tuned. To test it out, you can go to + `Localization Test` and push around or drive around your robot. Go to [FTC Dashboard](http://192.168.43.1:8080/dash) + and on the top right, switch the drop down from the default view to the field view. Then, on the bottom + left corner, you should see a field and the robot being drawn on the field. You can then move your + robot around and see if the movements look accurate on FTC Dashboard. If they don't, then you'll + want to re-run some of the previous steps. Otherwise, congrats on tuning your localizer! + +# Three Wheel Localizer +* First, you'll need three odometry wheels connected to motor encoder ports on a hub. +* Then, go to `ThreeWheelLocalizer.java`. First, in the constructor, enter in the positions of your + tracking wheels relative to the center of the wheels of the robot. The positions are in inches, so + convert measurements accordingly. Use the comment above the class declaration to help you with the + coordinates. +* Next, go to where it tells you to replace the current statements with your encoder ports in the constructor. + Replace the `deviceName` parameter with the name of the port that the encoder is connected to. The + variable names correspond to which tracking wheel should be connected. +* Then, reverse the direction of any encoders so that the forward encoders tick up when the robot + is moving forward and the strafe encoder ticks up when the robot moves right. +* First, start with the `Turn Localizer Tuner`. You'll want to position your robot to be facing + in a direction you can easily find again, like lining up an edge of the robot against a field tile edge. + By default, you should spin the robot for one rotation going counterclockwise. Once you've spun + exactly that one rotation, or whatever you set that value to, then the turn multiplier will be shown + as the second number shown. The first number is how far the robot thinks you've spun, and the second + number is the multiplier you need to have to scale your current readings to your goal of one rotation, + or the custom set angle. Feel free to run a few more tests and average the results. Once you have + this multiplier, then replace `TURN_TICKS_TO_RADIANS` in the localizer with your multiplier. Make sure + you replace the number, not add on or multiply it to the previous number. The tuner takes into + account your current multiplier. +* Next, go on to `Forward Localizer Tuner`. You'll want to position a ruler alongside your robot. + By default, you'll want to push the robot 30 inches forward. Once you've pushed that far, or whatever + you set that value to, then the forward multiplier will be shown as the second number shown. The + first number is how far the robot thinks you've gone, and the second number is the multiplier you + need to have to scale your current readings to your goal of 30 inches, or the custom set distance. + Feel free to run a few more tests and average the results. Once you have this multiplier, then + replace `FORWARD_TICKS_TO_INCHES` in the localizer with your multiplier. Make sure you replace the number, + not add on or multiply it to the previous number. The tuner takes into account your current multiplier. +* Finally, go to `Lateral Localizer Tuner`. You'll want to position a ruler alongside your robot. + By default, you'll want to push the robot 30 inches to the right. Once you've pushed that far, or whatever + you set that value to, then the lateral multiplier will be shown as the second number shown. The + first number is how far the robot thinks you've gone, and the second number is the multiplier you + need to have to scale your current readings to your goal of 30 inches, or the custom set distance. + Feel free to run a few more tests and average the results. Once you have this multiplier, then + replace `STRAFE_TICKS_TO_INCHES` in the localizer with your multiplier. Make sure you replace the number, + not add on or multiply it to the previous number. The tuner takes into account your current multiplier. +* Once you're done with all this, your localizer should be tuned. To test it out, you can go to + `Localization Test` and push around or drive around your robot. Go to [FTC Dashboard](http://192.168.43.1:8080/dash) + and on the top right, switch the drop down from the default view to the field view. Then, on the bottom + left corner, you should see a field and the robot being drawn on the field. You can then move your + robot around and see if the movements look accurate on FTC Dashboard. If they don't, then you'll + want to re-run some of the previous steps. Otherwise, congrats on tuning your localizer! + +# Three Wheel Localizer with IMU +* First, you'll need three odometry wheels connected to motor encoder ports on a hub. +* Then, go to `ThreeWheelIMULocalizer.java`. First, in the constructor, enter in the positions of your + tracking wheels relative to the center of the wheels of the robot. The positions are in inches, so + convert measurements accordingly. Use the comment above the class declaration to help you with the + coordinates. +* Next, go to where it tells you to replace the current statements with your encoder ports in the constructor. + Replace the `deviceName` parameter with the name of the port that the encoder is connected to. The + variable names correspond to which tracking wheel should be connected. +* After that, go to the instantiation of the IMU and change the orientation of the IMU to match that + of your robot's. +* Then, reverse the direction of any encoders so that the forward encoders tick up when the robot + is moving forward and the strafe encoder ticks up when the robot moves right. +* Although heading localization is done mostly through the IMU, the tracking wheels are still used for + small angle adjustments for better stability. So, you will still need to tune your turning multiplier. +* First, start with the `Turn Localizer Tuner`. Before doing any tuning, go to FTC Dashboard and find + the `ThreeWheelIMULocalizer` dropdown and deselect `useIMU`. You'll want to position your robot to be facing + in a direction you can easily find again, like lining up an edge of the robot against a field tile edge. + By default, you should spin the robot for one rotation going counterclockwise. Once you've spun + exactly that one rotation, or whatever you set that value to, then the turn multiplier will be shown + as the second number shown. The first number is how far the robot thinks you've spun, and the second + number is the multiplier you need to have to scale your current readings to your goal of one rotation, + or the custom set angle. Feel free to run a few more tests and average the results. Once you have + this multiplier, then replace `TURN_TICKS_TO_RADIANS` in the localizer with your multiplier. Make sure + you replace the number, not add on or multiply it to the previous number. The tuner takes into + account your current multiplier. +* Next, go on to `Forward Localizer Tuner`. You should re-enable `useIMU` at this time. You'll want to position a ruler alongside your robot. + By default, you'll want to push the robot 30 inches forward. Once you've pushed that far, or whatever + you set that value to, then the forward multiplier will be shown as the second number shown. The + first number is how far the robot thinks you've gone, and the second number is the multiplier you + need to have to scale your current readings to your goal of 30 inches, or the custom set distance. + Feel free to run a few more tests and average the results. Once you have this multiplier, then + replace `FORWARD_TICKS_TO_INCHES` in the localizer with your multiplier. Make sure you replace the number, + not add on or multiply it to the previous number. The tuner takes into account your current multiplier. +* Finally, go to `Lateral Localizer Tuner`. `useIMU` should be enabled for this step. You'll want to position a ruler alongside your robot. + By default, you'll want to push the robot 30 inches to the right. Once you've pushed that far, or whatever + you set that value to, then the lateral multiplier will be shown as the second number shown. The + first number is how far the robot thinks you've gone, and the second number is the multiplier you + need to have to scale your current readings to your goal of 30 inches, or the custom set distance. + Feel free to run a few more tests and average the results. Once you have this multiplier, then + replace `STRAFE_TICKS_TO_INCHES` in the localizer with your multiplier. Make sure you replace the number, + not add on or multiply it to the previous number. The tuner takes into account your current multiplier. +* Once you're done with all this, your localizer should be tuned. Make sure that `useIMU` is turned back on. To test it out, you can go to + `Localization Test` and push around or drive around your robot. Go to [FTC Dashboard](http://192.168.43.1:8080/dash) + and on the top right, switch the drop down from the default view to the field view. Then, on the bottom + left corner, you should see a field and the robot being drawn on the field. You can then move your + robot around and see if the movements look accurate on FTC Dashboard. If they don't, then you'll + want to re-run some of the previous steps. Otherwise, congrats on tuning your localizer! + +# OTOS Localizer +* First, you'll need the OTOS connected to an I2C port on a hub. Make sure the film on the sensor is removed. +* Then, go to `OTOSLocalizer.java`. First, in the constructor, go to where it tells you to replace + the current statement with your OTOS port in the constructor. Replace the `deviceName` parameter + with the name of the port that the OTOS is connected to. +* Next, enter in the position of your OTOS relative to the center of the wheels of the robot. The + positions are in inches, so convert measurements accordingly. Use the comment above the class + declaration as well as to help you with the coordinates. +* First, start with the `Turn Localizer Tuner`. You'll want to position your robot to be facing + in a direction you can easily find again, like lining up an edge of the robot against a field tile edge. + By default, you should spin the robot for one rotation going counterclockwise. Once you've spun + exactly that one rotation, or whatever you set that value to, then the angular scalar will be shown + as the second number shown. The first number is how far the robot thinks you've spun, and the second + number is the scalar you need to have to scale your current readings to your goal of one rotation, + or the custom set angle. Feel free to run a few more tests and average the results. Once you have + this scalar, then replace the angular scalar on line `78` in the localizer with your scalar. + Make sure you replace the number, not add on or multiply it to the previous number. The tuner takes into + account your current angular scalar. +* For this next step, since OTOS only has one linear scalar, you can run either the forward or lateral + localizer tuner and the result should be the same. So, you choose which one you want to run. +* Option 1: go on to `Forward Localizer Tuner`. You'll want to position a ruler alongside your robot. + By default, you'll want to push the robot 30 inches forward. Once you've pushed that far, or whatever + you set that value to, then the linear scalar will be shown as the second number shown. The + first number is how far the robot thinks you've gone, and the second number is the scalar you + need to have to scale your current readings to your goal of 30 inches, or the custom set distance. + Feel free to run a few more tests and average the results. Once you have this scalar, then + replace the linear scalar on line `77` in the localizer with your scalar. Make sure you replace the number, + not add on or multiply it to the previous number. The tuner takes into account your current scalar. +* Option 2: go to `Lateral Localizer Tuner`. You'll want to position a ruler alongside your robot. + By default, you'll want to push the robot 30 inches to the right. Once you've pushed that far, or whatever + you set that value to, then the linear scalar will be shown as the second number shown. The + first number is how far the robot thinks you've gone, and the second number is the scalar you + need to have to scale your current readings to your goal of 30 inches, or the custom set distance. + Feel free to run a few more tests and average the results. Once you have this scalar, then + replace the linear scalar on line `77` in the localizer with your scalar. Make sure you replace the number, + not add on or multiply it to the previous number. The tuner takes into account your current scalar. +* Once you're done with all this, your localizer should be tuned. To test it out, you can go to + `Localization Test` and push around or drive around your robot. Go to [FTC Dashboard](http://192.168.43.1:8080/dash) + and on the top right, switch the drop down from the default view to the field view. Then, on the bottom + left corner, you should see a field and the robot being drawn on the field. You can then move your + robot around and see if the movements look accurate on FTC Dashboard. If they don't, then you'll + want to re-run some of the previous steps. Otherwise, congrats on tuning your localizer! + +## Using Road Runner's Localizer +Of course, many teams have experience using Road Runner in the past and so have localizers from Road +Runner that are tuned. There is an adapter for the Road Runner three wheel localizer to the Pedro +Pathing localization system in Pedro Pathing, but it is commented out by default to reduce the number +of imports in gradle. + +To re-enable it, go to `RoadRunnerEncoder.java`, `RoadRunnerThreeWheelLocalizer.java`, and `RRToPedroThreeWheelLocalizer.java` +and hit `ctrl` + `a` to select everything within the files. Then, press `ctrl` + `/` to uncomment the code. + +Afterwards, go to `build.gradle` file under the `teamcode` folder and add the following dependencies: +``` +implementation 'org.apache.commons:commons-math3:3.6.1' +implementation 'com.acmerobotics.com.roadrunner:core:0.5.6' +``` + +After that, you should be good to go. If you want to use a different localizer from Road Runner, then +you can adapt it in the same process that's used for the Road Runner three wheel localizer. \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/OVERVIEW.md b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/OVERVIEW.md new file mode 100644 index 0000000..a0dbca1 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/OVERVIEW.md @@ -0,0 +1,108 @@ +## Basic Ideas +Pedro Pathing is a reactive vector based follower. What this means is that the robot dynamically +calculates a set of vectors that are required to correct error as well as to move forward and applies them. + +The robot calculates: + +* centripetal force correction +* translational correction +* heading correction +* drive vector + +These are then applied to the robot in this order until either the robot's power is maxed out or all +the vectors are applied. + +## Why Pedro Pathing? +Why use Pedro Pathing? Why not something else like Road Runner or Pure Pursuit? + +* Why not Pure Pursuit? + * Pure Pursuit searches for the farthest point on the path that's within a certain radius from the robot. Pure Pursuit will then go in a straight line to that point. This poses several problems, as a small search radius will cause some oscillations on corners, and a large search radius will cut corners on paths, which makes the paths inaccurate to real life. + * Pedro Pathing instead corrects to the closest point on the path while still following the path. This ensures that the follower will stay on the path while still being able to move forward along the path without cutting corners or encountering oscillation issues. +* Why not Road Runner? + * Road Runner is a motion profile based follower, which means that a set of instructions for motor powers are calculated for each path beforehand and then run. After reaching the end of this motion profile, Road Runner corrects. This can be sufficient for most situations, but if the robot encounters an obstacle or wheel slippage, it may be unable to correct in time. + * Pedro Pathing instead dynamically corrects throughout the path. The movement vectors are calculated at every point along the path, and because of this, the path can even be changed midway through and Pedro Pathing will still be able to correct. Since correction occurs throughout the path, the error correction isn't concentrated on the end of the path and therefore the robot is able to better minimize error. + +## How Does Pedro Path? +As mentioned in the *Basic Ideas* section, Pedro Pathing calculates a set of vectors to move the +robot along a path, which is defined with Bezier curves. Here, we'll go more in-depth on how these +vectors are calculated and used in path following. + +### The Hierarchy +While following paths, sometimes all these motion vectors are demanding more power from the robot +than it actually has. How do we deal with this? + +Our motion vectors are applied in order of importance, which is the order they appear in within the +list in *Basic Ideas*. The centripetal force vector is the highest importance, since it ensures the +robot sticks to the path. If the robot is far off the path, then the robot will not drive along the +path, and so the centripetal force vector will be reduced in magnitude. This is why ranking the +centripetal force correction above the translational correction doesn't produce issues. The next +highest, of course, is the translational correction. This corrects strictly the robot's position to +the closest point on the path. The reasoning behind this is that it is usually much more important +that the robot be on the path, and so avoid potential obstacles, rather than facing the correct +direction. The third highest important vector is the heading correction, which turns the robot to +the correct angle. This is higher than the drive vector since we don't want to drive forward if the +robot isn't facing the correct direction. Finally, the drive vector is applied. This ensures that +the robot only continues on the path when there aren't any major issues with the following. + +As each vector is applied, the robot checks to see if the sum of the applied vectors is greater than +the power that the drivetrain can produce, which would be 1 motor power. If the magnitude of the +combined vectors is greater than 1, then the most recently added vector is scaled down until the +combined vectors' magnitude is equal to 1. If all vectors are able to be applied without exceeding +the power limit, then all the vectors can just be applied without issue. + +### Centripetal Force Correction +Have you ever noticed that your robot seems to want to swing outwards when taking corners? This is +due to a lack of centripetal force correction. In order to take curves effectively, your robot must +accelerate towards the inside of the curve. If we can approximate the region of the path the robot +is at with a circle, then we can use the formula for centripetal force to calculate how much power +we need to allocate to approximate a centripetal force. + +Because paths are defined with Bezier curves, we can easily take the first and second derivative of +the path, expressed as vectors. We can use that to calculate the curvature of the path, which is the +inverse of the length of the radius of the circle we can use to approximate the path. The actual +formula for the calculations of the curvature is the cross product of the first derivative and +second derivative, divided by the magnitude of the first derivative raised to the power of 3. + +With this, along with the weight of the robot and the velocity of the robot along the path, we can +calculate the force necessary to keep the robot on the path, and then tune a scaling factor to turn +that force into a corresponding power for the robot. + +### Translational Correction +This is as simple as it sounds: this corrects error in the robot's position only. The robot's translational +error is corrected with a PID control. The translational correction does not act along the path the +robot takes, but instead moves the robot back to the closest point on the path. + +### Heading Correction +The heading correction operates very similarly to the translational correction, except this corrects +the direction the robot is facing. The heading correction will turn in the closest direction from the +robot's current heading to the target heading. + +### Drive Vector +The drive vector points in the direction of the tangent of the path and it is responsible for moving +the robot along the path. Using basic kinematics equations, we can use the velocity of the robot +along the path, the length of path left, and a specified target rate of deceleration to calculate +the velocity we should be moving at. Additionally, after finding out the rate of deceleration of the +robot under 0 power, we can compensate for that with another kinematics equation. Combining these +two lets us control our velocity to both move along the path quickly and brake without overshooting. + +## Additional Capabilities +In addition to following paths, Pedro Pathing can be used for a few other purposes. + +### Holding Points +Pedro Pathing is also capable of holding a specified position and direction. This can be useful for +improving on the end accuracy of paths, providing additional correction time if possible. It can +also be useful in cases where contact with other robots might occur. For instance, in the 2022-2023 +FTC season challenge, Power Play, robots might come into contact when scoring on a contested middle +junction. Pedro Pathing would be able to recover and correct from a robot collision, allowing for +more consistent scoring. + +### TeleOp Enhancements +Finally, Pedro Pathing can be used in TeleOp to enhance driving. With regular mecanum drive, robots +will tend to swing out when taking corners. Pedro Pathing can account for that, allowing the robot +to take corners more smoothly and efficiently. Using the same localizer as is used in autonomous, a +first and second derivative can be estimated from previous positions. Then, with a modified version +of the curvature formula, we can estimate a centripetal force correction and apply it under driver +control. + +## Questions? +If you still have more questions, feel free to contact us at `scottsbots10158@gmail.com` \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/README.md b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/README.md new file mode 100644 index 0000000..0b23ad5 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/README.md @@ -0,0 +1,28 @@ +## Welcome! +This is the Pedro Pathing path following program developed by FTC team 10158 Scott's Bots with Logan +Nash in the 2023-2024 Centerstage season. + +## Installation +The quickest way to get started is with the quickstart [here](https://github.com/AnyiLin/Pedro-Pathing-Quickstart). + +Otherwise, take the `pedroPathing` folder and put it under the `teamcode` folder in your project. +You can do this from either downloading the project from the above quickstart link or the 10158 +CENTERSTAGE repository [here](https://github.com/AnyiLin/10158-Centerstage). + +For this version of Pedro Pathing, the localizer used is the Road Runner localizer. To install its +dependencies: +1. Find `build.dependencies.gradle` in the main folder of your project. +2. Add the following code to the end of the `repositories` block: +``` +maven { url = 'https://maven.brott.dev/' } +``` +3. Then, add the following code to the end of your `dependencies` block: +``` +implementation 'com.acmerobotics.dashboard:dashboard:0.4.5' +``` +4. Find the `build.gradle` file under the `teamcode` folder. +5. In this gradle file, add the following dependency: +``` +implementation 'com.fasterxml.jackson.core:jackson-databind:2.12.7' +implementation 'org.jetbrains.kotlin:kotlin-stdlib:1.4.21' +``` \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/TUNING.md b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/TUNING.md new file mode 100644 index 0000000..bd22f46 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/TUNING.md @@ -0,0 +1,119 @@ +## Prerequisites +Obviously, you have to have a robot to use Pedro Pathing. Also, Pedro Pathing is only able to work +with omnidirectional drives, like mecanum drive. There is currently no support for swerve drives. +You must also have a localizer of some sort. Pedro Pathing has a drive encoder, a two tracking wheel, +and a three tracking wheel localizer. You will need to have your localizer tuned before starting to +tune PedroPathing. Check out the tuning guide under the localization tab if you're planning on using one of the +localizers available in Pedro Pathing. Additionally, using [FTC Dashboard](http://192.168.43.1:8080/dash) +will help a lot in tuning. Team 16166 Watt'S Up made a path visualizer linked [here](https://pedro-path-generator.vercel.app). +The old Desmos visualizer is [here](https://www.desmos.com/calculator/3so1zx0hcd), but the one by +Watt'S Up is honestly a lot better. +One last thing to note is that Pedro Pathing operates in inches and radians. You can use centimeters +instead of inches, but you'll have to input all your measurement in centimeters, and any distances +that the tuners require you to push the robot or the tuners output will say "inches" when the actual +measurements will be in centimeters. + +## Tuning +* To start with, we need the mass of the robot in kg. This is used for the centripetal force correction, + and the mass, with the variable name `mass`, should be put on line `86` in the `FollowerConstants` + class under the `tuning` package. + +* Next, we need to find the preferred mecanum drive vectors. The rollers on mecanum wheels point at a + 45 degree angle from the forward direction, but the actual direction the force is output is actually + closer to forward. To find the direction your wheels will go, you will need to run the + `Forward Velocity Tuner` and `Strafe Velocity Tuner` OpModes. These will run your robot at full + power for 40 inches forward and to the right, respectively. The distance can be changed through FTC + Dashboard under the dropdown for each respective class, but higher distances work better. After the + distance has finished running, the end velocity will be output to telemetry. The robot may continue + to drift a little bit after the robot has finished running the distance, so make sure you have + plenty of room. Once you're done, put the velocity for the `Forward Velocity Tuner` on line `33` in + the `FollowerConstants` class, and the velocity for the `Strafe Velocity Tuner` on line `34` in the + `FollowerConstants` class. The variable names should be `xMovement` and `yMovement`, respectively. + +* The last set of automatic tuners you'll need to run are the zero power acceleration tuners. These + find the rate at which your robot decelerates when power is cut from the drivetrain. This is used to + get a more accurate estimation of the drive vector. To find this, you will need to run the + `Forward Zero Power Acceleration Tuner` and the `Lateral Zero Power Acceleration Tuner` OpModes. + These will run your robot until it hits a velocity of 10 inches/second forward and to the right, + respectively. The velocity can be changed through FTC Dashboard under the dropdown for each + respective class, but higher velocities work better. After the velocity has been reached, power will + be cut from the drivetrain and the robot's deceleration will be tracked until the robot stops, at + which point it will display the deceleration in telemetry. This robot will need to drift to a stop + to properly work, and the higher the velocity the greater the drift distance, so make sure you have + enough room. Once you're done, put the zero power acceleration for the + `Forward Zero Power Acceleration Tuner` on line `94` in the `FollowerConstants` class and the zero + power acceleration for the `Lateral Zero Power Acceleration Tuner` on line `98` in the + `FollowerConstants` class. The variable names should be `forwardZeroPowerAcceleration` and + `lateralZeroPowerAcceleration`, respectively. + +* After this, we will want to tune the translational PID. Go to FTC Dashboard and disable all but + the `useTranslational` checkboxes under the `Follower` tab. Then, run `StraightBackAndForth`. Make + sure you disable the timer on autonomous OpModes. The PID for the translational error is called + `translationalPIDF`. If you need to add a feedforward value, use the `translationalPIDFFeedForward` + since that will add the feedforward in the direction the robot is trying to move, rather than the + feedforward in the PIDF itself, since those will only add the feedforward one way. You can change + the PIDF constants and feedforward values, under the `FollowerConstants` tab in FTC Dashboard. + To tune the PID, push the robot off the path and see how corrects. You will want to alternate sides + you push to reduce field wear and tear as well as push with varying power and distance. I would + recommend tuning the PID so that it is capable of correcting while minimizing oscillations and still + achieving a satisfactory level of accuracy. Overall, try to tune for fewer oscillations rather than + higher speeds or perfect accuracy, since this will make the robot run more smoothly under actual + pathing conditions. + +* Next, we will tune the heading PID. The process is essentially the same as above, except you will + want to only enable `useHeading` under `Follower` on FTC Dashboard, as well as turn the robot from + opposing corners instead of pushing the robot. Naturally, instead of changing the stuff with + "translational" in the name, you will instead want to look for stuff with "heading" in the name. + Otherwise, these two PIDs are functionally very similar. The same tips from above will apply to this. + +* Afterwards, we will tune the drive PID. Before we continue, we will need to set the + `zeroPowerAccelerationMultiplier`. This determines how fast your robot will decelerate as a factor + of how fast your robot will coast to a stop. Honestly, this is up to you. I personally used 4, but + what works best for you is most important. Higher numbers will cause a faster brake, but increase + oscillations at the end. Lower numbers will do the opposite. This can be found on line `107` in + `FollowerConstants`, named `zeroPowerAccelerationMultiplier`. The drive PID is much, much more sensitive than the others. For reference, + my P values were in the hundredths and thousandths place values, and my D values were in the hundred + thousandths and millionths place values. To tune this, enable `useDrive`, `useHeading`, and + `useTranslational` in the `Follower` dropdown in FTC Dashboard. Next, run `StraightBackAndForth` + and don't forget to turn off the timer on the OpMode. Then, tune the PID following the tips from + earlier. For this, it is very important to try to reduce oscillations. Additionally, I would + absolutely not recommend using the I, or integral, part of the PID for this. Using integral in + drivetrain PIDs is already not ideal, but it will continuously build up error in this PID, causing + major issues when it gets too strong. Don't use I; P and D are enough. In the versions of Pedro Pathing + from after late July 2024, there is a Kalman filter on the drive error and the drive PID has a + filter as well. These smooth out the drive error and PID response so that there is not as much + oscillation during the braking portion of each path. The Kalman filter is tuned to have 6 for the + model covariance and 1 for the data covariance. These values should work, but if you feel inclined + to tune the Kalman filter yourself, a higher ratio of model covariance to data covariance means that + the filter will rely more on its previous output rather than the data, and the opposite ratio will + mean that the filter will rely more so on the data input (the raw drive error) rather than the model. + The filtered PID functions like a normal PID, except the derivative term is a weighted average of the + current derivative and the previous derivative. Currently, the weighting, or time constant for the + drive filtered PID is 0.6, so the derivative output is 0.6 times the previous derivative plus 0.4 + times the current derivative. Feel free to mess around with these values and find what works best + for your robot! + +* Finally, we will want to tune the centripetal force correction. This is a pretty simple tune. Open + up FTC Dashboard and enable everything under the `Follower` tab. Then, run `CurvedBackAndForth` + and turn off its timer. If you notice the robot is correcting towards the inside of the curve + as/after running a path, then increase `centripetalScaling`, which can be found on line `89` of + `FollowerConstants`. If the robot is correcting towards the outside of the curve, then decrease + `centripetalScaling`. + +* Once you've found satisfactory tunings for everything, run the robot around in + `StraightBackAndForth`, `CurvedBackAndForth`, or some paths of your own making. There's also + `Circle`, but that's more so for fun than anything else. If you notice something could be improved, + feel free to mess around more with your PIDs. That should be all! If you have any more questions, + refer to the OVERVIEW readme file or the README readme file. Best of luck to your team this season! :) + +## Note About the PIDs +In versions of Pedro Pathing before early August 2024, there were 2 PIDs used in the translational, +heading, and drive control. However, now there is only one main PID. The old system can still be used. +Scroll down to the bottom of `FollowerConstants` and set all the booleans from lines `157` to `159` +to true. They should be named `useSecondaryTranslationalPID`, `useSecondaryHeadingPID`, and `useSecondaryDrivePID`. +This will enable the two PID system that Pedro Pathing originally used. From there, scroll +down and all the values pertaining to the secondary PIDs will be there. The two PID system works with +a PID that handles larger errors (the main PID) and a second PID to handle smaller errors (the +secondary PID). The main PID should be tuned to move the error within the secondary PID's range +without providing too much momentum that could cause an overshoot. The secondary PID should be tuned +to correct within its range quickly and accurately while minimizing oscillations. \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/examples/TeleOpEnhancements.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/examples/TeleOpEnhancements.java new file mode 100644 index 0000000..9f35ef4 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/examples/TeleOpEnhancements.java @@ -0,0 +1,62 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.examples; + +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName; + +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; + +import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower; + +/** + * This is the TeleOpEnhancements OpMode. It is an example usage of the TeleOp enhancements that + * Pedro Pathing is capable of. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/21/2024 + */ +@TeleOp(name = "Pedro Pathing TeleOp Enhancements", group = "Test") +public class TeleOpEnhancements extends OpMode { + private Follower follower; + + private DcMotorEx leftFront; + private DcMotorEx leftRear; + private DcMotorEx rightFront; + private DcMotorEx rightRear; + + /** + * This initializes the drive motors as well as the Follower and motion Vectors. + */ + @Override + public void init() { + follower = new Follower(hardwareMap); + + leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName); + leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName); + rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName); + rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName); + + leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); + leftRear.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); + rightRear.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); + rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); + + follower.startTeleopDrive(); + } + + /** + * This runs the OpMode. This is only drive control with Pedro Pathing live centripetal force + * correction. + */ + @Override + public void loop() { + follower.setTeleOpMovementVectors(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x); + follower.update(); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/follower/DriveVectorScaler.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/follower/DriveVectorScaler.java new file mode 100644 index 0000000..f2cfcfd --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/follower/DriveVectorScaler.java @@ -0,0 +1,152 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.follower; + +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; + +/** + * This is the DriveVectorScaler class. This class takes in inputs Vectors for driving, heading + * correction, and translational/centripetal correction and returns an array with wheel powers. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/4/2024 + */ +public class DriveVectorScaler { + // This is ordered left front, left back, right front, right back. These are also normalized. + private Vector[] mecanumVectors; + + /** + * This creates a new DriveVectorScaler, which takes in various movement vectors and outputs + * the wheel drive powers necessary to move in the intended direction, given the true movement + * vector for the front left mecanum wheel. + * + * @param frontLeftVector this is the front left mecanum wheel's preferred drive vector. + */ + public DriveVectorScaler(Vector frontLeftVector) { + Vector copiedFrontLeftVector = MathFunctions.normalizeVector(frontLeftVector); + mecanumVectors = new Vector[]{ + new Vector(copiedFrontLeftVector.getMagnitude(), copiedFrontLeftVector.getTheta()), + new Vector(copiedFrontLeftVector.getMagnitude(), 2*Math.PI-copiedFrontLeftVector.getTheta()), + new Vector(copiedFrontLeftVector.getMagnitude(), 2*Math.PI-copiedFrontLeftVector.getTheta()), + new Vector(copiedFrontLeftVector.getMagnitude(), copiedFrontLeftVector.getTheta())}; + } + + /** + * This takes in vectors for corrective power, heading power, and pathing power and outputs + * an Array of four doubles, one for each wheel's motor power. + * + * IMPORTANT NOTE: all vector inputs are clamped between 0 and 1 inclusive in magnitude. + * + * @param correctivePower this Vector includes the centrifugal force scaling Vector as well as a + * translational power Vector to correct onto the Bezier curve the Follower + * is following. + * @param headingPower this Vector points in the direction of the robot's current heaing, and + * the magnitude tells the robot how much it should turn and in which + * direction. + * @param pathingPower this Vector points in the direction the robot needs to go to continue along + * the Path. + * @param robotHeading this is the current heading of the robot, which is used to calculate how + * much power to allocate to each wheel. + * @return this returns an Array of doubles with a length of 4, which contains the wheel powers. + */ + public double[] getDrivePowers(Vector correctivePower, Vector headingPower, Vector pathingPower, double robotHeading) { + // clamps down the magnitudes of the input vectors + if (correctivePower.getMagnitude() > 1) correctivePower.setMagnitude(1); + if (headingPower.getMagnitude() > 1) headingPower.setMagnitude(1); + if (pathingPower.getMagnitude() > 1) pathingPower.setMagnitude(1); + + // the powers for the wheel vectors + double [] wheelPowers = new double[4]; + + // This contains a copy of the mecanum wheel vectors + Vector[] mecanumVectorsCopy = new Vector[4]; + + // this contains the pathing vectors, one for each side (heading control requires 2) + Vector[] truePathingVectors = new Vector[2]; + + if (correctivePower.getMagnitude() == 1) { + // checks for corrective power equal to 1 in magnitude. if equal to one, then set pathing power to that + truePathingVectors[0] = MathFunctions.copyVector(correctivePower); + truePathingVectors[1] = MathFunctions.copyVector(correctivePower); + } else { + // corrective power did not take up all the power, so add on heading power + Vector leftSideVector = MathFunctions.subtractVectors(correctivePower, headingPower); + Vector rightSideVector = MathFunctions.addVectors(correctivePower, headingPower); + + if (leftSideVector.getMagnitude() > 1 || rightSideVector.getMagnitude() > 1) { + //if the combined corrective and heading power is greater than 1, then scale down heading power + double headingScalingFactor = Math.min(findNormalizingScaling(correctivePower, headingPower), findNormalizingScaling(correctivePower, MathFunctions.scalarMultiplyVector(headingPower, -1))); + truePathingVectors[0] = MathFunctions.subtractVectors(correctivePower, MathFunctions.scalarMultiplyVector(headingPower, headingScalingFactor)); + truePathingVectors[1] = MathFunctions.addVectors(correctivePower, MathFunctions.scalarMultiplyVector(headingPower, headingScalingFactor)); + } else { + // if we're here then we can add on some drive power but scaled down to 1 + Vector leftSideVectorWithPathing = MathFunctions.addVectors(leftSideVector, pathingPower); + Vector rightSideVectorWithPathing = MathFunctions.addVectors(rightSideVector, pathingPower); + + if (leftSideVectorWithPathing.getMagnitude() > 1 || rightSideVectorWithPathing.getMagnitude() > 1) { + // too much power now, so we scale down the pathing vector + double pathingScalingFactor = Math.min(findNormalizingScaling(leftSideVector, pathingPower), findNormalizingScaling(rightSideVector, pathingPower)); + truePathingVectors[0] = MathFunctions.addVectors(leftSideVector, MathFunctions.scalarMultiplyVector(pathingPower, pathingScalingFactor)); + truePathingVectors[1] = MathFunctions.addVectors(rightSideVector, MathFunctions.scalarMultiplyVector(pathingPower, pathingScalingFactor)); + } else { + // just add the vectors together and you get the final vector + truePathingVectors[0] = MathFunctions.copyVector(leftSideVectorWithPathing); + truePathingVectors[1] = MathFunctions.copyVector(rightSideVectorWithPathing); + } + } + } + + truePathingVectors[0] = MathFunctions.scalarMultiplyVector(truePathingVectors[0], 2.0); + truePathingVectors[1] = MathFunctions.scalarMultiplyVector(truePathingVectors[1], 2.0); + + for (int i = 0; i < mecanumVectorsCopy.length; i++) { + // this copies the vectors from mecanumVectors but creates new references for them + mecanumVectorsCopy[i] = MathFunctions.copyVector(mecanumVectors[i]); + + mecanumVectorsCopy[i].rotateVector(robotHeading); + } + + wheelPowers[0] = (mecanumVectorsCopy[1].getXComponent()*truePathingVectors[0].getYComponent() - truePathingVectors[0].getXComponent()*mecanumVectorsCopy[1].getYComponent()) / (mecanumVectorsCopy[1].getXComponent()*mecanumVectorsCopy[0].getYComponent() - mecanumVectorsCopy[0].getXComponent()*mecanumVectorsCopy[1].getYComponent()); + wheelPowers[1] = (mecanumVectorsCopy[0].getXComponent()*truePathingVectors[0].getYComponent() - truePathingVectors[0].getXComponent()*mecanumVectorsCopy[0].getYComponent()) / (mecanumVectorsCopy[0].getXComponent()*mecanumVectorsCopy[1].getYComponent() - mecanumVectorsCopy[1].getXComponent()*mecanumVectorsCopy[0].getYComponent()); + wheelPowers[2] = (mecanumVectorsCopy[3].getXComponent()*truePathingVectors[1].getYComponent() - truePathingVectors[1].getXComponent()*mecanumVectorsCopy[3].getYComponent()) / (mecanumVectorsCopy[3].getXComponent()*mecanumVectorsCopy[2].getYComponent() - mecanumVectorsCopy[2].getXComponent()*mecanumVectorsCopy[3].getYComponent()); + wheelPowers[3] = (mecanumVectorsCopy[2].getXComponent()*truePathingVectors[1].getYComponent() - truePathingVectors[1].getXComponent()*mecanumVectorsCopy[2].getYComponent()) / (mecanumVectorsCopy[2].getXComponent()*mecanumVectorsCopy[3].getYComponent() - mecanumVectorsCopy[3].getXComponent()*mecanumVectorsCopy[2].getYComponent()); + + double wheelPowerMax = Math.max(Math.max(Math.abs(wheelPowers[0]), Math.abs(wheelPowers[1])), Math.max(Math.abs(wheelPowers[2]), Math.abs(wheelPowers[3]))); + if (wheelPowerMax > 1) { + wheelPowers[0] /= wheelPowerMax; + wheelPowers[1] /= wheelPowerMax; + wheelPowers[2] /= wheelPowerMax; + wheelPowers[3] /= wheelPowerMax; + } + + return wheelPowers; + } + + /** + * This takes in two Vectors, one static and one variable, and returns the scaling factor that, + * when multiplied to the variable Vector, results in magnitude of the sum of the static Vector + * and the scaled variable Vector being 1. + * + * IMPORTANT NOTE: I did not intend for this to be used for anything other than the method above + * this one in this class, so there will be errors if you input Vectors of length greater than 1, + * and it will scale up the variable Vector if the magnitude of the sum of the two input Vectors + * isn't greater than 1. So, just don't use this elsewhere. There's gotta be a better way to do + * whatever you're trying to do. + * + * I know that this is used outside of this class, however, I created this method so I get to + * use it if I want to. Also, it's only used once outside of the DriveVectorScaler class, and + * it's used to scale Vectors, as intended. + * + * @param staticVector the Vector that is held constant. + * @param variableVector the Vector getting scaled to make the sum of the input Vectors have a + * magnitude of 1. + * @return returns the scaling factor for the variable Vector. + */ + public double findNormalizingScaling(Vector staticVector, Vector variableVector) { + double a = Math.pow(variableVector.getXComponent(), 2) + Math.pow(variableVector.getYComponent(), 2); + double b = staticVector.getXComponent() * variableVector.getXComponent() + staticVector.getYComponent() * variableVector.getYComponent(); + double c = Math.pow(staticVector.getXComponent(), 2) + Math.pow(staticVector.getYComponent(), 2) - 1.0; + return (-b + Math.sqrt(Math.pow(b, 2) - a*c))/(a); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/follower/Follower.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/follower/Follower.java new file mode 100644 index 0000000..fe9d153 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/follower/Follower.java @@ -0,0 +1,999 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.follower; + +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.drivePIDFSwitch; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.forwardZeroPowerAcceleration; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.headingPIDFSwitch; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.drivePIDFFeedForward; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.headingPIDFFeedForward; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.translationalPIDFFeedForward; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.lateralZeroPowerAcceleration; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.secondaryDrivePIDFFeedForward; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.secondaryHeadingPIDFFeedForward; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.secondaryTranslationalPIDFFeedForward; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.translationalPIDFSwitch; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.useSecondaryDrivePID; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.useSecondaryHeadingPID; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.useSecondaryTranslationalPID; + +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.HardwareMap; +import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.PoseUpdater; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierPoint; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Path; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathBuilder; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathCallback; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; +import org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants; +import org.firstinspires.ftc.teamcode.pedroPathing.util.DashboardPoseTracker; +import org.firstinspires.ftc.teamcode.pedroPathing.util.Drawing; +import org.firstinspires.ftc.teamcode.pedroPathing.util.FilteredPIDFController; +import org.firstinspires.ftc.teamcode.pedroPathing.util.KalmanFilter; +import org.firstinspires.ftc.teamcode.pedroPathing.util.PIDFController; + +import java.util.ArrayList; +import java.util.Arrays; +import java.util.List; + +/** + * This is the Follower class. It handles the actual following of the paths and all the on-the-fly + * calculations that are relevant for movement. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/4/2024 + */ +@Config +public class Follower { + private HardwareMap hardwareMap; + + private DcMotorEx leftFront; + private DcMotorEx leftRear; + private DcMotorEx rightFront; + private DcMotorEx rightRear; + private List motors; + + private DriveVectorScaler driveVectorScaler; + + private PoseUpdater poseUpdater; + private DashboardPoseTracker dashboardPoseTracker; + + private Pose closestPose; + + private Path currentPath; + + private PathChain currentPathChain; + + private final int BEZIER_CURVE_BINARY_STEP_LIMIT = FollowerConstants.BEZIER_CURVE_BINARY_STEP_LIMIT; + private final int AVERAGED_VELOCITY_SAMPLE_NUMBER = FollowerConstants.AVERAGED_VELOCITY_SAMPLE_NUMBER; + + private int chainIndex; + + private long[] pathStartTimes; + + private boolean followingPathChain; + private boolean holdingPosition; + private boolean isBusy; + private boolean reachedParametricPathEnd; + private boolean holdPositionAtEnd; + private boolean teleopDrive; + + private double maxPower = 1; + private double previousSecondaryTranslationalIntegral; + private double previousTranslationalIntegral; + private double holdPointTranslationalScaling = FollowerConstants.holdPointTranslationalScaling; + private double holdPointHeadingScaling = FollowerConstants.holdPointHeadingScaling; + public double driveError; + public double headingError; + + private long reachedParametricPathEndTime; + + private double[] drivePowers; + private double[] teleopDriveValues; + + private ArrayList velocities = new ArrayList<>(); + private ArrayList accelerations = new ArrayList<>(); + + private Vector averageVelocity; + private Vector averagePreviousVelocity; + private Vector averageAcceleration; + private Vector secondaryTranslationalIntegralVector; + private Vector translationalIntegralVector; + private Vector teleopDriveVector; + private Vector teleopHeadingVector; + public Vector driveVector; + public Vector headingVector; + public Vector translationalVector; + public Vector centripetalVector; + public Vector correctiveVector; + + private PIDFController secondaryTranslationalPIDF = new PIDFController(FollowerConstants.secondaryTranslationalPIDFCoefficients); + private PIDFController secondaryTranslationalIntegral = new PIDFController(FollowerConstants.secondaryTranslationalIntegral); + private PIDFController translationalPIDF = new PIDFController(FollowerConstants.translationalPIDFCoefficients); + private PIDFController translationalIntegral = new PIDFController(FollowerConstants.translationalIntegral); + private PIDFController secondaryHeadingPIDF = new PIDFController(FollowerConstants.secondaryHeadingPIDFCoefficients); + private PIDFController headingPIDF = new PIDFController(FollowerConstants.headingPIDFCoefficients); + private FilteredPIDFController secondaryDrivePIDF = new FilteredPIDFController(FollowerConstants.secondaryDrivePIDFCoefficients); + private FilteredPIDFController drivePIDF = new FilteredPIDFController(FollowerConstants.drivePIDFCoefficients); + + private KalmanFilter driveKalmanFilter = new KalmanFilter(FollowerConstants.driveKalmanFilterParameters); + private double[] driveErrors; + private double rawDriveError; + private double previousRawDriveError; + + public static boolean drawOnDashboard = true; + public static boolean useTranslational = true; + public static boolean useCentripetal = true; + public static boolean useHeading = true; + public static boolean useDrive = true; + + /** + * This creates a new Follower given a HardwareMap. + * + * @param hardwareMap HardwareMap required + */ + public Follower(HardwareMap hardwareMap) { + this.hardwareMap = hardwareMap; + initialize(); + } + + /** + * This initializes the follower. + * In this, the DriveVectorScaler and PoseUpdater is instantiated, the drive motors are + * initialized and their behavior is set, and the variables involved in approximating first and + * second derivatives for teleop are set. + */ + public void initialize() { + driveVectorScaler = new DriveVectorScaler(FollowerConstants.frontLeftVector); + poseUpdater = new PoseUpdater(hardwareMap); + + leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName); + leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName); + rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName); + rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName); + + // TODO: Make sure that this is the direction your motors need to be reversed in. + leftFront.setDirection(DcMotorSimple.Direction.REVERSE); + leftRear.setDirection(DcMotorSimple.Direction.REVERSE); + + motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear); + + for (DcMotorEx motor : motors) { + MotorConfigurationType motorConfigurationType = motor.getMotorType().clone(); + motorConfigurationType.setAchieveableMaxRPMFraction(1.0); + motor.setMotorType(motorConfigurationType); + } + + for (DcMotorEx motor : motors) { + motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); + } + + dashboardPoseTracker = new DashboardPoseTracker(poseUpdater); + + breakFollowing(); + } + + /** + * This sets the maximum power the motors are allowed to use. + * + * @param set This caps the motor power from [0, 1]. + */ + public void setMaxPower(double set) { + maxPower = MathFunctions.clamp(set, 0, 1); + } + + /** + * This handles the limiting of the drive powers array to the max power. + */ + public void limitDrivePowers() { + for (int i = 0; i < drivePowers.length; i++) { + if (Math.abs(drivePowers[i]) > maxPower) { + drivePowers[i] = maxPower * MathFunctions.getSign(drivePowers[i]); + } + } + } + + /** + * This gets a Point from the current Path from a specified t-value. + * + * @return returns the Point. + */ + public Point getPointFromPath(double t) { + if (currentPath != null) { + return currentPath.getPoint(t); + } else { + return null; + } + } + + /** + * This returns the current pose from the PoseUpdater. + * + * @return returns the pose + */ + public Pose getPose() { + return poseUpdater.getPose(); + } + + /** + * This sets the current pose in the PoseUpdater without using offsets. + * + * @param pose The pose to set the current pose to. + */ + public void setPose(Pose pose) { + poseUpdater.setPose(pose); + } + + /** + * This returns the current velocity of the robot as a Vector. + * + * @return returns the current velocity as a Vector. + */ + public Vector getVelocity() { + return poseUpdater.getVelocity(); + } + + /** + * This returns the current acceleration of the robot as a Vector. + * + * @return returns the current acceleration as a Vector. + */ + public Vector getAcceleration() { + return poseUpdater.getAcceleration(); + } + + /** + * This returns the magnitude of the current velocity. For when you only need the magnitude. + * + * @return returns the magnitude of the current velocity. + */ + public double getVelocityMagnitude() { + return poseUpdater.getVelocity().getMagnitude(); + } + + /** + * This sets the starting pose. Do not run this after moving at all. + * + * @param pose the pose to set the starting pose to. + */ + public void setStartingPose(Pose pose) { + poseUpdater.setStartingPose(pose); + } + + /** + * This sets the current pose, using offsets so no reset time delay. This is better than the + * Road Runner reset, in general. Think of using offsets as setting trim in an aircraft. This can + * be reset as well, so beware of using the resetOffset() method. + * + * @param set The pose to set the current pose to. + */ + public void setCurrentPoseWithOffset(Pose set) { + poseUpdater.setCurrentPoseWithOffset(set); + } + + /** + * This sets the offset for only the x position. + * + * @param xOffset This sets the offset. + */ + public void setXOffset(double xOffset) { + poseUpdater.setXOffset(xOffset); + } + + /** + * This sets the offset for only the y position. + * + * @param yOffset This sets the offset. + */ + public void setYOffset(double yOffset) { + poseUpdater.setYOffset(yOffset); + } + + /** + * This sets the offset for only the heading. + * + * @param headingOffset This sets the offset. + */ + public void setHeadingOffset(double headingOffset) { + poseUpdater.setHeadingOffset(headingOffset); + } + + /** + * This returns the x offset. + * + * @return returns the x offset. + */ + public double getXOffset() { + return poseUpdater.getXOffset(); + } + + /** + * This returns the y offset. + * + * @return returns the y offset. + */ + public double getYOffset() { + return poseUpdater.getYOffset(); + } + + /** + * This returns the heading offset. + * + * @return returns the heading offset. + */ + public double getHeadingOffset() { + return poseUpdater.getHeadingOffset(); + } + + /** + * This resets all offsets set to the PoseUpdater. If you have reset your pose using the + * setCurrentPoseUsingOffset(Pose set) method, then your pose will be returned to what the + * PoseUpdater thinks your pose would be, not the pose you reset to. + */ + public void resetOffset() { + poseUpdater.resetOffset(); + } + + /** + * This holds a Point. + * + * @param point the Point to stay at. + * @param heading the heading to face. + */ + public void holdPoint(BezierPoint point, double heading) { + breakFollowing(); + holdingPosition = true; + isBusy = false; + followingPathChain = false; + currentPath = new Path(point); + currentPath.setConstantHeadingInterpolation(heading); + closestPose = currentPath.getClosestPoint(poseUpdater.getPose(), 1); + } + + /** + * This follows a Path. + * This also makes the Follower hold the last Point on the Path. + * + * @param path the Path to follow. + */ + public void followPath(Path path, boolean holdEnd) { + breakFollowing(); + holdPositionAtEnd = holdEnd; + isBusy = true; + followingPathChain = false; + currentPath = path; + closestPose = currentPath.getClosestPoint(poseUpdater.getPose(), BEZIER_CURVE_BINARY_STEP_LIMIT); + } + + /** + * This follows a Path. + * + * @param path the Path to follow. + */ + public void followPath(Path path) { + followPath(path, false); + } + + /** + * This follows a PathChain. Drive vector projection is only done on the last Path. + * This also makes the Follower hold the last Point on the PathChain. + * + * @param pathChain the PathChain to follow. + */ + public void followPath(PathChain pathChain, boolean holdEnd) { + breakFollowing(); + holdPositionAtEnd = holdEnd; + pathStartTimes = new long[pathChain.size()]; + pathStartTimes[0] = System.currentTimeMillis(); + isBusy = true; + followingPathChain = true; + chainIndex = 0; + currentPathChain = pathChain; + currentPath = pathChain.getPath(chainIndex); + closestPose = currentPath.getClosestPoint(poseUpdater.getPose(), BEZIER_CURVE_BINARY_STEP_LIMIT); + } + + /** + * This follows a PathChain. Drive vector projection is only done on the last Path. + * + * @param pathChain the PathChain to follow. + */ + public void followPath(PathChain pathChain) { + followPath(pathChain, false); + } + + /** + * This starts teleop drive control. + */ + public void startTeleopDrive() { + breakFollowing(); + teleopDrive = true; + } + + /** + * This calls an update to the PoseUpdater, which updates the robot's current position estimate. + * This also updates all the Follower's PIDFs, which updates the motor powers. + */ + public void update() { + poseUpdater.update(); + + if (drawOnDashboard) { + dashboardPoseTracker.update(); + } + + if (!teleopDrive) { + if (currentPath != null) { + if (holdingPosition) { + closestPose = currentPath.getClosestPoint(poseUpdater.getPose(), 1); + + drivePowers = driveVectorScaler.getDrivePowers(MathFunctions.scalarMultiplyVector(getTranslationalCorrection(), holdPointTranslationalScaling), MathFunctions.scalarMultiplyVector(getHeadingVector(), holdPointHeadingScaling), new Vector(), poseUpdater.getPose().getHeading()); + + limitDrivePowers(); + + for (int i = 0; i < motors.size(); i++) { + motors.get(i).setPower(drivePowers[i]); + } + } else { + if (isBusy) { + closestPose = currentPath.getClosestPoint(poseUpdater.getPose(), BEZIER_CURVE_BINARY_STEP_LIMIT); + + if (followingPathChain) updateCallbacks(); + + drivePowers = driveVectorScaler.getDrivePowers(getCorrectiveVector(), getHeadingVector(), getDriveVector(), poseUpdater.getPose().getHeading()); + + limitDrivePowers(); + + for (int i = 0; i < motors.size(); i++) { + motors.get(i).setPower(drivePowers[i]); + } + } + if (currentPath.isAtParametricEnd()) { + if (followingPathChain && chainIndex < currentPathChain.size() - 1) { + // Not at last path, keep going + breakFollowing(); + pathStartTimes[chainIndex] = System.currentTimeMillis(); + isBusy = true; + followingPathChain = true; + chainIndex++; + currentPath = currentPathChain.getPath(chainIndex); + closestPose = currentPath.getClosestPoint(poseUpdater.getPose(), BEZIER_CURVE_BINARY_STEP_LIMIT); + } else { + // At last path, run some end detection stuff + // set isBusy to false if at end + if (!reachedParametricPathEnd) { + reachedParametricPathEnd = true; + reachedParametricPathEndTime = System.currentTimeMillis(); + } + + if ((System.currentTimeMillis() - reachedParametricPathEndTime > currentPath.getPathEndTimeoutConstraint()) || (poseUpdater.getVelocity().getMagnitude() < currentPath.getPathEndVelocityConstraint() && MathFunctions.distance(poseUpdater.getPose(), closestPose) < currentPath.getPathEndTranslationalConstraint() && MathFunctions.getSmallestAngleDifference(poseUpdater.getPose().getHeading(), currentPath.getClosestPointHeadingGoal()) < currentPath.getPathEndHeadingConstraint())) { + if (holdPositionAtEnd) { + holdPositionAtEnd = false; + holdPoint(new BezierPoint(currentPath.getLastControlPoint()), currentPath.getHeadingGoal(1)); + } else { + breakFollowing(); + } + } + } + } + } + } + } else { + velocities.add(poseUpdater.getVelocity()); + velocities.remove(velocities.get(velocities.size() - 1)); + + calculateAveragedVelocityAndAcceleration(); + + drivePowers = driveVectorScaler.getDrivePowers(getCentripetalForceCorrection(), teleopHeadingVector, teleopDriveVector, poseUpdater.getPose().getHeading()); + + limitDrivePowers(); + + for (int i = 0; i < motors.size(); i++) { + motors.get(i).setPower(drivePowers[i]); + } + } + } + + /** + * This sets the teleop drive vectors. This defaults to robot centric. + * + * @param forwardDrive determines the forward drive vector for the robot in teleop. In field centric + * movement, this is the x-axis. + * @param lateralDrive determines the lateral drive vector for the robot in teleop. In field centric + * movement, this is the y-axis. + * @param heading determines the heading vector for the robot in teleop. + */ + public void setTeleOpMovementVectors(double forwardDrive, double lateralDrive, double heading) { + setTeleOpMovementVectors(forwardDrive, lateralDrive, heading, true); + } + + /** + * This sets the teleop drive vectors. + * + * @param forwardDrive determines the forward drive vector for the robot in teleop. In field centric + * movement, this is the x-axis. + * @param lateralDrive determines the lateral drive vector for the robot in teleop. In field centric + * movement, this is the y-axis. + * @param heading determines the heading vector for the robot in teleop. + * @param robotCentric sets if the movement will be field or robot centric + */ + public void setTeleOpMovementVectors(double forwardDrive, double lateralDrive, double heading, boolean robotCentric) { + teleopDriveValues[0] = MathFunctions.clamp(forwardDrive, -1, 1); + teleopDriveValues[1] = MathFunctions.clamp(lateralDrive, -1, 1); + teleopDriveValues[2] = MathFunctions.clamp(heading, -1, 1); + teleopDriveVector.setOrthogonalComponents(teleopDriveValues[0], teleopDriveValues[1]); + teleopDriveVector.setMagnitude(MathFunctions.clamp(teleopDriveVector.getMagnitude(), 0, 1)); + + if (robotCentric) { + teleopDriveVector.rotateVector(getPose().getHeading()); + } + + teleopHeadingVector.setComponents(teleopDriveValues[2], getPose().getHeading()); + } + + /** + * This calculates an averaged approximate velocity and acceleration. This is used for a + * real-time correction of centripetal force, which is used in teleop. + */ + public void calculateAveragedVelocityAndAcceleration() { + averageVelocity = new Vector(); + averagePreviousVelocity = new Vector(); + + for (int i = 0; i < velocities.size() / 2; i++) { + averageVelocity = MathFunctions.addVectors(averageVelocity, velocities.get(i)); + } + averageVelocity = MathFunctions.scalarMultiplyVector(averageVelocity, 1.0 / ((double) velocities.size() / 2)); + + for (int i = velocities.size() / 2; i < velocities.size(); i++) { + averagePreviousVelocity = MathFunctions.addVectors(averagePreviousVelocity, velocities.get(i)); + } + averagePreviousVelocity = MathFunctions.scalarMultiplyVector(averagePreviousVelocity, 1.0 / ((double) velocities.size() / 2)); + + accelerations.add(MathFunctions.subtractVectors(averageVelocity, averagePreviousVelocity)); + accelerations.remove(accelerations.size() - 1); + + averageAcceleration = new Vector(); + + for (int i = 0; i < accelerations.size(); i++) { + averageAcceleration = MathFunctions.addVectors(averageAcceleration, accelerations.get(i)); + } + averageAcceleration = MathFunctions.scalarMultiplyVector(averageAcceleration, 1.0 / accelerations.size()); + } + + /** + * This checks if any PathCallbacks should be run right now, and runs them if applicable. + */ + public void updateCallbacks() { + for (PathCallback callback : currentPathChain.getCallbacks()) { + if (!callback.hasBeenRun()) { + if (callback.getType() == PathCallback.PARAMETRIC) { + // parametric call back + if (chainIndex == callback.getIndex() && (getCurrentTValue() >= callback.getStartCondition() || MathFunctions.roughlyEquals(getCurrentTValue(), callback.getStartCondition()))) { + callback.run(); + } + } else { + // time based call back + if (chainIndex >= callback.getIndex() && System.currentTimeMillis() - pathStartTimes[callback.getIndex()] > callback.getStartCondition()) { + callback.run(); + } + + } + } + } + } + + /** + * This resets the PIDFs and stops following the current Path. + */ + public void breakFollowing() { + teleopDrive = false; + holdingPosition = false; + isBusy = false; + reachedParametricPathEnd = false; + secondaryDrivePIDF.reset(); + drivePIDF.reset(); + secondaryHeadingPIDF.reset(); + headingPIDF.reset(); + secondaryTranslationalPIDF.reset(); + secondaryTranslationalIntegral.reset(); + secondaryTranslationalIntegralVector = new Vector(); + previousSecondaryTranslationalIntegral = 0; + translationalPIDF.reset(); + translationalIntegral.reset(); + translationalIntegralVector = new Vector(); + previousTranslationalIntegral = 0; + driveVector = new Vector(); + headingVector = new Vector(); + translationalVector = new Vector(); + centripetalVector = new Vector(); + correctiveVector = new Vector(); + driveError = 0; + headingError = 0; + rawDriveError = 0; + previousRawDriveError = 0; + driveErrors = new double[2]; + for (int i = 0; i < driveErrors.length; i++) { + driveErrors[i] = 0; + } + driveKalmanFilter.reset(); + + for (int i = 0; i < AVERAGED_VELOCITY_SAMPLE_NUMBER; i++) { + velocities.add(new Vector()); + } + for (int i = 0; i < AVERAGED_VELOCITY_SAMPLE_NUMBER / 2; i++) { + accelerations.add(new Vector()); + } + calculateAveragedVelocityAndAcceleration(); + teleopDriveValues = new double[3]; + teleopDriveVector = new Vector(); + teleopHeadingVector = new Vector(); + + for (int i = 0; i < motors.size(); i++) { + motors.get(i).setPower(0); + } + } + + /** + * This returns if the Follower is currently following a Path or a PathChain. + * + * @return returns if the Follower is busy. + */ + public boolean isBusy() { + return isBusy; + } + + /** + * This returns a Vector in the direction the robot must go to move along the path. This Vector + * takes into account the projected position of the robot to calculate how much power is needed. + *

+ * Note: This vector is clamped to be at most 1 in magnitude. + * + * @return returns the drive vector. + */ + public Vector getDriveVector() { + if (!useDrive) return new Vector(); + if (followingPathChain && chainIndex < currentPathChain.size() - 1) { + return new Vector(1, currentPath.getClosestPointTangentVector().getTheta()); + } + + driveError = getDriveVelocityError(); + + if (Math.abs(driveError) < drivePIDFSwitch && useSecondaryDrivePID) { + secondaryDrivePIDF.updateError(driveError); + driveVector = new Vector(MathFunctions.clamp(secondaryDrivePIDF.runPIDF() + secondaryDrivePIDFFeedForward * MathFunctions.getSign(driveError), -1, 1), currentPath.getClosestPointTangentVector().getTheta()); + return MathFunctions.copyVector(driveVector); + } + + drivePIDF.updateError(driveError); + driveVector = new Vector(MathFunctions.clamp(drivePIDF.runPIDF() + drivePIDFFeedForward * MathFunctions.getSign(driveError), -1, 1), currentPath.getClosestPointTangentVector().getTheta()); + return MathFunctions.copyVector(driveVector); + } + + /** + * This returns the velocity the robot needs to be at to make it to the end of the Path + * at some specified deceleration (well technically just some negative acceleration). + * + * @return returns the projected velocity. + */ + public double getDriveVelocityError() { + double distanceToGoal; + if (!currentPath.isAtParametricEnd()) { + distanceToGoal = currentPath.length() * (1 - currentPath.getClosestPointTValue()); + } else { + Vector offset = new Vector(); + offset.setOrthogonalComponents(getPose().getX() - currentPath.getLastControlPoint().getX(), getPose().getY() - currentPath.getLastControlPoint().getY()); + distanceToGoal = MathFunctions.dotProduct(currentPath.getEndTangent(), offset); + } + + Vector distanceToGoalVector = MathFunctions.scalarMultiplyVector(MathFunctions.normalizeVector(currentPath.getClosestPointTangentVector()), distanceToGoal); + Vector velocity = new Vector(MathFunctions.dotProduct(getVelocity(), MathFunctions.normalizeVector(currentPath.getClosestPointTangentVector())), currentPath.getClosestPointTangentVector().getTheta()); + + Vector forwardHeadingVector = new Vector(1.0, poseUpdater.getPose().getHeading()); + double forwardVelocity = MathFunctions.dotProduct(forwardHeadingVector, velocity); + double forwardDistanceToGoal = MathFunctions.dotProduct(forwardHeadingVector, distanceToGoalVector); + double forwardVelocityGoal = MathFunctions.getSign(forwardDistanceToGoal) * Math.sqrt(Math.abs(-2 * currentPath.getZeroPowerAccelerationMultiplier() * forwardZeroPowerAcceleration * forwardDistanceToGoal)); + double forwardVelocityZeroPowerDecay = forwardVelocity - MathFunctions.getSign(forwardDistanceToGoal) * Math.sqrt(Math.abs(Math.pow(forwardVelocity, 2) + 2 * forwardZeroPowerAcceleration * forwardDistanceToGoal)); + + Vector lateralHeadingVector = new Vector(1.0, poseUpdater.getPose().getHeading() - Math.PI / 2); + double lateralVelocity = MathFunctions.dotProduct(lateralHeadingVector, velocity); + double lateralDistanceToGoal = MathFunctions.dotProduct(lateralHeadingVector, distanceToGoalVector); + double lateralVelocityGoal = MathFunctions.getSign(lateralDistanceToGoal) * Math.sqrt(Math.abs(-2 * currentPath.getZeroPowerAccelerationMultiplier() * lateralZeroPowerAcceleration * lateralDistanceToGoal)); + double lateralVelocityZeroPowerDecay = lateralVelocity - MathFunctions.getSign(lateralDistanceToGoal) * Math.sqrt(Math.abs(Math.pow(lateralVelocity, 2) + 2 * lateralZeroPowerAcceleration * lateralDistanceToGoal)); + + Vector forwardVelocityError = new Vector(forwardVelocityGoal - forwardVelocityZeroPowerDecay - forwardVelocity, forwardHeadingVector.getTheta()); + Vector lateralVelocityError = new Vector(lateralVelocityGoal - lateralVelocityZeroPowerDecay - lateralVelocity, lateralHeadingVector.getTheta()); + Vector velocityErrorVector = MathFunctions.addVectors(forwardVelocityError, lateralVelocityError); + + previousRawDriveError = rawDriveError; + rawDriveError = velocityErrorVector.getMagnitude() * MathFunctions.getSign(MathFunctions.dotProduct(velocityErrorVector, currentPath.getClosestPointTangentVector())); + + double projection = 2 * driveErrors[1] - driveErrors[0]; + + driveKalmanFilter.update(rawDriveError - previousRawDriveError, projection); + + for (int i = 0; i < driveErrors.length - 1; i++) { + driveErrors[i] = driveErrors[i + 1]; + } + driveErrors[1] = driveKalmanFilter.getState(); + + return driveKalmanFilter.getState(); + } + + /** + * This returns a Vector in the direction of the robot that contains the heading correction + * as its magnitude. Positive heading correction turns the robot counter-clockwise, and negative + * heading correction values turn the robot clockwise. So basically, Pedro Pathing uses a right- + * handed coordinate system. + *

+ * Note: This vector is clamped to be at most 1 in magnitude. + * + * @return returns the heading vector. + */ + public Vector getHeadingVector() { + if (!useHeading) return new Vector(); + headingError = MathFunctions.getTurnDirection(poseUpdater.getPose().getHeading(), currentPath.getClosestPointHeadingGoal()) * MathFunctions.getSmallestAngleDifference(poseUpdater.getPose().getHeading(), currentPath.getClosestPointHeadingGoal()); + if (Math.abs(headingError) < headingPIDFSwitch && useSecondaryHeadingPID) { + secondaryHeadingPIDF.updateError(headingError); + headingVector = new Vector(MathFunctions.clamp(secondaryHeadingPIDF.runPIDF() + secondaryHeadingPIDFFeedForward * MathFunctions.getTurnDirection(poseUpdater.getPose().getHeading(), currentPath.getClosestPointHeadingGoal()), -1, 1), poseUpdater.getPose().getHeading()); + return MathFunctions.copyVector(headingVector); + } + headingPIDF.updateError(headingError); + headingVector = new Vector(MathFunctions.clamp(headingPIDF.runPIDF() + headingPIDFFeedForward * MathFunctions.getTurnDirection(poseUpdater.getPose().getHeading(), currentPath.getClosestPointHeadingGoal()), -1, 1), poseUpdater.getPose().getHeading()); + return MathFunctions.copyVector(headingVector); + } + + /** + * This returns a combined Vector in the direction the robot must go to correct both translational + * error as well as centripetal force. + *

+ * Note: This vector is clamped to be at most 1 in magnitude. + * + * @return returns the corrective vector. + */ + public Vector getCorrectiveVector() { + Vector centripetal = getCentripetalForceCorrection(); + Vector translational = getTranslationalCorrection(); + Vector corrective = MathFunctions.addVectors(centripetal, translational); + + if (corrective.getMagnitude() > 1) { + return MathFunctions.addVectors(centripetal, MathFunctions.scalarMultiplyVector(translational, driveVectorScaler.findNormalizingScaling(centripetal, translational))); + } + + correctiveVector = MathFunctions.copyVector(corrective); + + return corrective; + } + + /** + * This returns a Vector in the direction the robot must go to account for only translational + * error. + *

+ * Note: This vector is clamped to be at most 1 in magnitude. + * + * @return returns the translational correction vector. + */ + public Vector getTranslationalCorrection() { + if (!useTranslational) return new Vector(); + Vector translationalVector = new Vector(); + double x = closestPose.getX() - poseUpdater.getPose().getX(); + double y = closestPose.getY() - poseUpdater.getPose().getY(); + translationalVector.setOrthogonalComponents(x, y); + + if (!(currentPath.isAtParametricEnd() || currentPath.isAtParametricStart())) { + translationalVector = MathFunctions.subtractVectors(translationalVector, new Vector(MathFunctions.dotProduct(translationalVector, MathFunctions.normalizeVector(currentPath.getClosestPointTangentVector())), currentPath.getClosestPointTangentVector().getTheta())); + + secondaryTranslationalIntegralVector = MathFunctions.subtractVectors(secondaryTranslationalIntegralVector, new Vector(MathFunctions.dotProduct(secondaryTranslationalIntegralVector, MathFunctions.normalizeVector(currentPath.getClosestPointTangentVector())), currentPath.getClosestPointTangentVector().getTheta())); + translationalIntegralVector = MathFunctions.subtractVectors(translationalIntegralVector, new Vector(MathFunctions.dotProduct(translationalIntegralVector, MathFunctions.normalizeVector(currentPath.getClosestPointTangentVector())), currentPath.getClosestPointTangentVector().getTheta())); + } + + if (MathFunctions.distance(poseUpdater.getPose(), closestPose) < translationalPIDFSwitch && useSecondaryTranslationalPID) { + secondaryTranslationalIntegral.updateError(translationalVector.getMagnitude()); + secondaryTranslationalIntegralVector = MathFunctions.addVectors(secondaryTranslationalIntegralVector, new Vector(secondaryTranslationalIntegral.runPIDF() - previousSecondaryTranslationalIntegral, translationalVector.getTheta())); + previousSecondaryTranslationalIntegral = secondaryTranslationalIntegral.runPIDF(); + + secondaryTranslationalPIDF.updateError(translationalVector.getMagnitude()); + translationalVector.setMagnitude(secondaryTranslationalPIDF.runPIDF() + secondaryTranslationalPIDFFeedForward); + translationalVector = MathFunctions.addVectors(translationalVector, secondaryTranslationalIntegralVector); + } else { + translationalIntegral.updateError(translationalVector.getMagnitude()); + translationalIntegralVector = MathFunctions.addVectors(translationalIntegralVector, new Vector(translationalIntegral.runPIDF() - previousTranslationalIntegral, translationalVector.getTheta())); + previousTranslationalIntegral = translationalIntegral.runPIDF(); + + translationalPIDF.updateError(translationalVector.getMagnitude()); + translationalVector.setMagnitude(translationalPIDF.runPIDF() + translationalPIDFFeedForward); + translationalVector = MathFunctions.addVectors(translationalVector, translationalIntegralVector); + } + + translationalVector.setMagnitude(MathFunctions.clamp(translationalVector.getMagnitude(), 0, 1)); + + this.translationalVector = MathFunctions.copyVector(translationalVector); + + return translationalVector; + } + + /** + * This returns the raw translational error, or how far off the closest point the robot is. + * + * @return This returns the raw translational error as a Vector. + */ + public Vector getTranslationalError() { + Vector error = new Vector(); + double x = closestPose.getX() - poseUpdater.getPose().getX(); + double y = closestPose.getY() - poseUpdater.getPose().getY(); + error.setOrthogonalComponents(x, y); + return error; + } + + /** + * This returns a Vector in the direction the robot must go to account for only centripetal + * force. + *

+ * Note: This vector is clamped to be between [0, 1] in magnitude. + * + * @return returns the centripetal force correction vector. + */ + public Vector getCentripetalForceCorrection() { + if (!useCentripetal) return new Vector(); + double curvature; + if (!teleopDrive) { + curvature = currentPath.getClosestPointCurvature(); + } else { + double yPrime = averageVelocity.getYComponent() / averageVelocity.getXComponent(); + double yDoublePrime = averageAcceleration.getYComponent() / averageVelocity.getXComponent(); + curvature = (yDoublePrime) / (Math.pow(Math.sqrt(1 + Math.pow(yPrime, 2)), 3)); + } + if (Double.isNaN(curvature)) return new Vector(); + centripetalVector = new Vector(MathFunctions.clamp(FollowerConstants.centripetalScaling * FollowerConstants.mass * Math.pow(MathFunctions.dotProduct(poseUpdater.getVelocity(), MathFunctions.normalizeVector(currentPath.getClosestPointTangentVector())), 2) * curvature, -1, 1), currentPath.getClosestPointTangentVector().getTheta() + Math.PI / 2 * MathFunctions.getSign(currentPath.getClosestPointNormalVector().getTheta())); + return centripetalVector; + } + + /** + * This returns the closest pose to the robot on the Path the Follower is currently following. + * This closest pose is calculated through a binary search method with some specified number of + * steps to search. By default, 10 steps are used, which should be more than enough. + * + * @return returns the closest pose. + */ + public Pose getClosestPose() { + return closestPose; + } + + /** + * This returns whether the follower is at the parametric end of its current Path. + * The parametric end is determined by if the closest Point t-value is greater than some specified + * end t-value. + * If running a PathChain, this returns true only if at parametric end of last Path in the PathChain. + * + * @return returns whether the Follower is at the parametric end of its Path. + */ + public boolean atParametricEnd() { + if (followingPathChain) { + if (chainIndex == currentPathChain.size() - 1) return currentPath.isAtParametricEnd(); + return false; + } + return currentPath.isAtParametricEnd(); + } + + /** + * This returns the t value of the closest point on the current Path to the robot + * In the absence of a current Path, it returns 1.0. + * + * @return returns the current t value. + */ + public double getCurrentTValue() { + if (isBusy) return currentPath.getClosestPointTValue(); + return 1.0; + } + + /** + * This returns the current path number. For following Paths, this will return 0. For PathChains, + * this will return the current path number. For holding Points, this will also return 0. + * + * @return returns the current path number. + */ + public double getCurrentPathNumber() { + if (!followingPathChain) return 0; + return chainIndex; + } + + /** + * This returns a new PathBuilder object for easily building PathChains. + * + * @return returns a new PathBuilder object. + */ + public PathBuilder pathBuilder() { + return new PathBuilder(); + } + + /** + * This writes out information about the various motion Vectors to the Telemetry specified. + * + * @param telemetry this is an instance of Telemetry or the FTC Dashboard telemetry that this + * method will use to output the debug data. + */ + public void telemetryDebug(MultipleTelemetry telemetry) { + telemetry.addData("follower busy", isBusy()); + telemetry.addData("heading error", headingError); + telemetry.addData("heading vector magnitude", headingVector.getMagnitude()); + telemetry.addData("corrective vector magnitude", correctiveVector.getMagnitude()); + telemetry.addData("corrective vector heading", correctiveVector.getTheta()); + telemetry.addData("translational error magnitude", getTranslationalError().getMagnitude()); + telemetry.addData("translational error direction", getTranslationalError().getTheta()); + telemetry.addData("translational vector magnitude", translationalVector.getMagnitude()); + telemetry.addData("translational vector heading", translationalVector.getMagnitude()); + telemetry.addData("centripetal vector magnitude", centripetalVector.getMagnitude()); + telemetry.addData("centripetal vector heading", centripetalVector.getTheta()); + telemetry.addData("drive error", driveError); + telemetry.addData("drive vector magnitude", driveVector.getMagnitude()); + telemetry.addData("drive vector heading", driveVector.getTheta()); + telemetry.addData("x", getPose().getX()); + telemetry.addData("y", getPose().getY()); + telemetry.addData("heading", getPose().getHeading()); + telemetry.addData("total heading", poseUpdater.getTotalHeading()); + telemetry.addData("velocity magnitude", getVelocity().getMagnitude()); + telemetry.addData("velocity heading", getVelocity().getTheta()); + driveKalmanFilter.debug(telemetry); + telemetry.update(); + if (drawOnDashboard) { + Drawing.drawDebug(this); + } + } + + /** + * This writes out information about the various motion Vectors to the Telemetry specified. + * + * @param telemetry this is an instance of Telemetry or the FTC Dashboard telemetry that this + * method will use to output the debug data. + */ + public void telemetryDebug(Telemetry telemetry) { + telemetryDebug(new MultipleTelemetry(telemetry)); + } + + /** + * This returns the total number of radians the robot has turned. + * + * @return the total heading. + */ + public double getTotalHeading() { + return poseUpdater.getTotalHeading(); + } + + /** + * This returns the current Path the Follower is following. This can be null. + * + * @return returns the current Path. + */ + public Path getCurrentPath() { + return currentPath; + } + + /** + * This returns the pose tracker for the robot to draw on the Dashboard. + * + * @return returns the pose tracker + */ + public DashboardPoseTracker getDashboardPoseTracker() { + return dashboardPoseTracker; + } + + /** + * This resets the IMU, if applicable. + */ + public void resetIMU() { + poseUpdater.resetIMU(); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Encoder.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Encoder.java new file mode 100644 index 0000000..573c4cf --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Encoder.java @@ -0,0 +1,83 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization; + +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.DcMotorSimple; + +/** + * This is the Encoder class. This tracks the position of a motor of class DcMotorEx. The motor + * must have an encoder attached. It can also get changes in position. + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 4/2/2024 + */ +public class Encoder { + private DcMotorEx motor; + private double previousPosition; + private double currentPosition; + private double multiplier; + + public final static double FORWARD = 1, REVERSE = -1; + + /** + * This creates a new Encoder from a DcMotorEx. + * + * @param setMotor the motor this will be tracking + */ + public Encoder(DcMotorEx setMotor) { + motor = setMotor; + multiplier = FORWARD; + reset(); + } + + /** + * This sets the direction/multiplier of the Encoder. Setting 1 or -1 will make the Encoder track + * forward or in reverse, respectively. Any multiple of either one will scale the Encoder's output + * by that amount. + * + * @param setMultiplier the multiplier/direction to set + */ + public void setDirection(double setMultiplier) { + multiplier = setMultiplier; + } + + /** + * This resets the Encoder's position and the current and previous position in the code. + */ + public void reset() { + motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); + previousPosition = motor.getCurrentPosition(); + currentPosition = motor.getCurrentPosition(); + motor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); + } + + /** + * This updates the Encoder's tracked current position and previous position. + */ + public void update() { + previousPosition = currentPosition; + currentPosition = motor.getCurrentPosition(); + } + + /** + * This returns the multiplier/direction of the Encoder. + * + * @return returns the multiplier + */ + public double getMultiplier() { + return multiplier * (motor.getDirection() == DcMotorSimple.Direction.FORWARD ? 1 : -1); + } + + /** + * This returns the change in position from the previous position to the current position. One + * important thing to note is that this encoder does not track velocity, only change in position. + * This is because I am using a pose exponential method of localization, which doesn't need the + * velocity of the encoders. Velocity of the robot is calculated in the localizer using an elapsed + * time timer there. + * + * @return returns the change in position of the Encoder + */ + public double getDeltaPosition() { + return getMultiplier() * (currentPosition - previousPosition); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Localizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Localizer.java new file mode 100644 index 0000000..8f9687f --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Localizer.java @@ -0,0 +1,94 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization; + +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; + +/** + * This is the Localizer class. It is an abstract superclass of all localizers used in Pedro Pathing, + * so it contains abstract methods that will have a concrete implementation in the subclasses. Any + * method that all localizers will need will be in this class. + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 4/2/2024 + */ +public abstract class Localizer { + + /** + * This returns the current pose estimate from the Localizer. + * + * @return returns the pose as a Pose object. + */ + public abstract Pose getPose(); + + /** + * This returns the current velocity estimate from the Localizer. + * + * @return returns the velocity as a Pose object. + */ + public abstract Pose getVelocity(); + + /** + * This returns the current velocity estimate from the Localizer as a Vector. + * + * @return returns the velocity as a Vector. + */ + public abstract Vector getVelocityVector(); + + /** + * This sets the start pose of the Localizer. Changing the start pose should move the robot as if + * all its previous movements were displacing it from its new start pose. + * + * @param setStart the new start pose + */ + public abstract void setStartPose(Pose setStart); + + /** + * This sets the current pose estimate of the Localizer. Changing this should just change the + * robot's current pose estimate, not anything to do with the start pose. + * + * @param setPose the new current pose estimate + */ + public abstract void setPose(Pose setPose); + + /** + * This calls an update to the Localizer, updating the current pose estimate and current velocity + * estimate. + */ + public abstract void update(); + + /** + * This returns how far the robot has turned in radians, in a number not clamped between 0 and + * 2 * pi radians. This is used for some tuning things and nothing actually within the following. + * + * @return returns how far the robot has turned in total, in radians. + */ + public abstract double getTotalHeading(); + + /** + * This returns the multiplier applied to forward movement measurement to convert from encoder + * ticks to inches. This is found empirically through a tuner. + * + * @return returns the forward ticks to inches multiplier + */ + public abstract double getForwardMultiplier(); + + /** + * This returns the multiplier applied to lateral/strafe movement measurement to convert from + * encoder ticks to inches. This is found empirically through a tuner. + * + * @return returns the lateral/strafe ticks to inches multiplier + */ + public abstract double getLateralMultiplier(); + + /** + * This returns the multiplier applied to turning movement measurement to convert from encoder + * ticks to radians. This is found empirically through a tuner. + * + * @return returns the turning ticks to radians multiplier + */ + public abstract double getTurningMultiplier(); + + /** + * This resets the IMU of the localizer, if applicable. + */ + public abstract void resetIMU(); +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Matrix.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Matrix.java new file mode 100644 index 0000000..c93ab7e --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Matrix.java @@ -0,0 +1,273 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization; + +import java.util.Arrays; + +/** + * This is the Matrix class. This defines matrices, primarily for use in the localizers. However, if + * matrices and matrix operations are necessary, this class as well as some operations in the + * MathFunctions class can absolutely be used there as well. It's similar to Mats in OpenCV if you've + * used them before, but with more limited functionality. + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 4/2/2024 + */ +public class Matrix { + private double[][] matrix; + + /** + * This creates a new Matrix of width and height 0. + */ + public Matrix() { + matrix = new double[0][0]; + } + + /** + * This creates a new Matrix with a specified width and height. + * + * @param rows the number of rows, or height + * @param columns the number of columns, or width + */ + public Matrix(int rows, int columns) { + matrix = new double[rows][columns]; + } + + /** + * This creates a new Matrix from a 2D matrix of doubles. Please only enter rectangular 2D + * Arrays of doubles or else things mess up. + * + * @param setMatrix the 2D Array of doubles + */ + public Matrix(double[][] setMatrix) { + setMatrix(setMatrix); + } + + /** + * This creates a new Matrix from another Matrix. + * + * @param setMatrix the Matrix input. + */ + public Matrix(Matrix setMatrix) { + setMatrix(setMatrix); + } + + /** + * This creates a copy of a 2D Array of doubles that references entirely new memory locations + * from the original 2D Array of doubles, so no issues with mutability. + * + * @param copyMatrix the 2D Array of doubles to copy + * @return returns a deep copy of the input Array + */ + public static double[][] deepCopy(double[][] copyMatrix) { + double[][] returnMatrix = new double[copyMatrix.length][copyMatrix[0].length]; + for (int i = 0; i < copyMatrix.length; i++) { + returnMatrix[i] = Arrays.copyOf(copyMatrix[i], copyMatrix[i].length); + } + return returnMatrix; + } + + /** + * This returns a deep copy of the 2D Array that this Matrix is based on. + * + * @return returns the 2D Array of doubles this Matrix is built on + */ + public double[][] getMatrix() { + return deepCopy(matrix); + } + + /** + * This returns a specified row of the Matrix in the form of an Array of doubles. + * + * @param row the index of the row to return + * @return returns the row of the Matrix specified + */ + public double[] get(int row) { + return Arrays.copyOf(matrix[row], matrix[row].length); + } + + /** + * This returns a specified element of the Matrix as a double. + * + * @param row the index of the row of the element + * @param column the index of the column of the element + * @return returns the element of the Matrix specified + */ + public double get(int row, int column) { + return get(row)[column]; + } + + /** + * This returns the number of rows of the Matrix, as determined by the length of the 2D Array. + * If the Matrix/2D Array is not rectangular, issues arise. + * + * @return returns the number of rows in the Matrix + */ + public int getRows() { + return matrix.length; + } + + /** + * This returns the number of columns of the Matrix, as determined by the length of the first Array + * in the 2D Array. If the Matrix/2D Array is not rectangular, issues arise. + * + * @return returns the number of columns in the Matrix + */ + public int getColumns() { + return matrix[0].length; + } + + /** + * This sets the 2D Array of this Matrix to a copy of the 2D Array of another Matrix. + * + * @param setMatrix the Matrix to copy from + * @return returns if the operation was successful + */ + public boolean setMatrix(Matrix setMatrix) { + return setMatrix(setMatrix.getMatrix()); + } + + /** + * This sets the 2D Array of this Matrix to a copy of a specified 2D Array. + * + * @param setMatrix the 2D Array to copy from + * @return returns if the operation was successful + */ + public boolean setMatrix(double[][] setMatrix) { + int columns = setMatrix[0].length; + for (int i = 0; i < setMatrix.length; i++) { + if (setMatrix[i].length != columns) { + return false; + } + } + matrix = deepCopy(setMatrix); + return true; + } + + /** + * This sets a row of the Matrix to a copy of a specified Array of doubles. + * + * @param row the row to be written over + * @param input the Array input + * @return returns if the operation was successful + */ + public boolean set(int row, double[] input) { + if (input.length != getColumns()) { + return false; + } + matrix[row] = Arrays.copyOf(input, input.length); + return true; + } + + /** + * This sets a specified element of the Matrix to an input value. + * + * @param row the index of the row of the specified element + * @param column the index of the column of the specified element + * @param input the input value + * @return returns if the operation was successful + */ + public boolean set(int row, int column, double input) { + matrix[row][column] = input; + return true; + } + + /** + * This adds a Matrix to this Matrix. + * + * @param input the Matrix to add to this. Nothing will change in this Matrix + * @return returns if the operation was successful + */ + public boolean add(Matrix input) { + if (input.getRows() == getRows() && input.getColumns() == getColumns()) { + for (int i = 0; i < getRows(); i++) { + for (int j = 0; j < getColumns(); j++) { + set(i, j, get(i,j) + input.get(i,j)); + } + } + return true; + } + return false; + } + + /** + * This subtracts a Matrix from this Matrix. + * + * @param input the Matrix to subtract from this. Nothing will change in this Matrix + * @return returns if the operation was successful + */ + public boolean subtract(Matrix input) { + if (input.getRows() == getRows() && input.getColumns() == getColumns()) { + for (int i = 0; i < getRows(); i++) { + for (int j = 0; j < getColumns(); j++) { + set(i, j, get(i,j) - input.get(i,j)); + } + } + return true; + } + return false; + } + + /** + * This multiplies this Matrix with a scalar. + * + * @param scalar the scalar number + * @return returns if the operation was successful + */ + public boolean scalarMultiply(double scalar) { + for (int i = 0; i < getRows(); i++) { + for (int j = 0; j < getColumns(); j++) { + set(i, j, scalar * get(i,j)); + } + } + return true; + } + + /** + * This multiplies the Matrix by -1, flipping the signs of all the elements within. + * + * @return returns if the operation was successful + */ + public boolean flipSigns() { + return scalarMultiply(-1); + } + + /** + * This multiplies a Matrix to this Matrix. + * + * @param input the Matrix to multiply to this. Nothing will change in this Matrix + * @return returns if the operation was successful + */ + public boolean multiply(Matrix input) { + if (getColumns() == input.getRows()) { + Matrix product = new Matrix(getRows(), input.getColumns()); + for (int i = 0; i < product.getRows(); i++) { + for (int j = 0; j < product.getColumns(); j++) { + double value = 0; + for (int k = 0; k < get(i).length; k++) { + value += get(i, k) * input.get(k, j); + } + product.set(i, j, value); + } + } + setMatrix(product); + return true; + } + return false; + } + + /** + * This multiplies a Matrix to another Matrix. This will not change any data in the two input + * Matrices. + * + * @param one the first Matrix to multiply. + * @param two the second Matrix to multiply + * @return returns if the operation was successful + */ + public static Matrix multiply(Matrix one, Matrix two) { + Matrix returnMatrix = new Matrix(one); + if (returnMatrix.multiply(two)) { + return returnMatrix; + } else { + return new Matrix(); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Pose.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Pose.java new file mode 100644 index 0000000..d5ac720 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/Pose.java @@ -0,0 +1,211 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization; + +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; + +/** + * This is the Pose class. It defines poses in 2D space, like the Pose2D class in Road Runner except + * in the Pedro Pathing code so I don't have to import the Road Runner library. A Pose consists of + * two coordinates defining a position and a third value for the heading, so basically just defining + * any position and orientation the robot can be at, unless your robot can fly for whatever reason. + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 4/2/2024 + */ +public class Pose { + private double x; + private double y; + private double heading; + + /** + * This creates a new Pose from a x, y, and heading inputs. + * + * @param setX the initial x value + * @param setY the initial y value + * @param setHeading the initial heading value + */ + public Pose(double setX, double setY, double setHeading) { + setX(setX); + setY(setY); + setHeading(setHeading); + } + + /** + * This creates a new Pose from x and y inputs. The heading is set to 0. + * + * @param setX the initial x value + * @param setY the initial y value + */ + public Pose(double setX, double setY) { + this(setX, setY, 0); + } + + /** + * This creates a new Pose with no inputs and 0 for all values. + */ + public Pose() { + this(0,0,0); + } + + /** + * This sets the x value. + * + * @param set the x value + */ + public void setX(double set) { + x = set; + } + + /** + * This sets the y value. + * + * @param set the y value + */ + public void setY(double set) { + y = set; + } + + /** + * This sets the heading value. + * + * @param set the heading value + */ + public void setHeading(double set) { + heading = MathFunctions.normalizeAngle(set); + } + + /** + * This returns the x value. + * + * @return returns the x value + */ + public double getX() { + return x; + } + + /** + * This returns the y value. + * + * @return returns the y value + */ + public double getY() { + return y; + } + + /** + * This returns the heading value. + * + * @return returns the heading value + */ + public double getHeading() { + return heading; + } + + /** + * This returns the Pose as a Vector. Naturally, the heading data in the Pose cannot be included + * in the Vector. + * + * @return returns the Pose as a Vector + */ + public Vector getVector() { + Vector returnVector = new Vector(); + returnVector.setOrthogonalComponents(x, y); + return returnVector; + } + + /** + * This returns a new Vector with magnitude 1 pointing in the direction of the heading. + * + * @return returns a unit Vector in the direction of the heading + */ + public Vector getHeadingVector() { + return new Vector(1, heading); + } + + /** + * This adds all the values of an input Pose to this Pose. The input Pose's data will not be + * changed. + * + * @param pose the input Pose + */ + public void add(Pose pose) { + setX(x + pose.getX()); + setY(y + pose.getY()); + setHeading(heading + pose.getHeading()); + } + + /** + * This subtracts all the values of an input Pose from this Pose. The input Pose's data will not + * be changed. + * + * @param pose the input Pose + */ + public void subtract(Pose pose) { + setX(x - pose.getX()); + setY(y - pose.getY()); + setHeading(heading - pose.getHeading()); + } + + /** + * This multiplies all the values of this Pose by a scalar. + * + * @param scalar the scalar + */ + public void scalarMultiply(double scalar) { + setX(x * scalar); + setY(y * scalar); + setHeading(heading * scalar); + } + + /** + * This divides all the values of this Pose by a scalar. + * + * @param scalar the scalar + */ + public void scalarDivide(double scalar) { + setX(x / scalar); + setY(y / scalar); + setHeading(heading / scalar); + } + + /** + * This flips the signs of all values in this Pose by multiplying them by -1. Heading values are + * still normalized to be between 0 and 2 * pi in value. + */ + public void flipSigns() { + setX(-x); + setY(-y); + setHeading(-heading); + } + + /** + * This returns if a Pose is within a specified accuracy of this Pose in terms of x position, + * y position, and heading. + * + * @param pose the input Pose to check + * @param accuracy the specified accuracy necessary to return true + * @return returns if the input Pose is within the specified accuracy of this Pose + */ + public boolean roughlyEquals(Pose pose, double accuracy) { + return MathFunctions.roughlyEquals(x, pose.getX(), accuracy) && MathFunctions.roughlyEquals(y, pose.getY(), accuracy) && MathFunctions.roughlyEquals(MathFunctions.getSmallestAngleDifference(heading, pose.getHeading()), 0, accuracy); + } + + /** + * This checks if the input Pose is within 0.0001 in all values to this Pose. + * + * @param pose the input Pose + * @return returns if the input Pose is within 0.0001 of this Pose + */ + public boolean roughlyEquals(Pose pose) { + return roughlyEquals(pose, 0.0001); + } + + /** + * This creates a copy of this Pose that points to a new memory location. + * + * @return returns a deep copy of this Pose + */ + public Pose copy() { + return new Pose(getX(), getY(), getHeading()); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/PoseUpdater.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/PoseUpdater.java new file mode 100644 index 0000000..ce2a8f2 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/PoseUpdater.java @@ -0,0 +1,348 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization; + +import com.qualcomm.hardware.lynx.LynxModule; +import com.qualcomm.robotcore.hardware.HardwareMap; +import com.qualcomm.robotcore.hardware.IMU; + +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.localizers.ThreeWheelIMULocalizer; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.localizers.ThreeWheelLocalizer; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.localizers.TwoWheelLocalizer; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; + +/** + * This is the PoseUpdater class. This class handles getting pose data from the localizer and returning + * the information in a useful way to the Follower. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/4/2024 + */ +public class PoseUpdater { + private HardwareMap hardwareMap; + + private IMU imu; + + private Localizer localizer; + + private Pose startingPose = new Pose(0,0,0); + + private Pose currentPose = startingPose; + + private Pose previousPose = startingPose; + + private Vector currentVelocity = new Vector(); + + private Vector previousVelocity = new Vector(); + + private Vector currentAcceleration = new Vector(); + + private double xOffset = 0; + private double yOffset = 0; + private double headingOffset = 0; + + private long previousPoseTime; + private long currentPoseTime; + + /** + * Creates a new PoseUpdater from a HardwareMap and a Localizer. + * + * @param hardwareMap the HardwareMap + * @param localizer the Localizer + */ + public PoseUpdater(HardwareMap hardwareMap, Localizer localizer) { + this.hardwareMap = hardwareMap; + + for (LynxModule module : hardwareMap.getAll(LynxModule.class)) { + module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO); + } + + this.localizer = localizer; + } + + /** + * Creates a new PoseUpdater from a HardwareMap. + * + * @param hardwareMap the HardwareMap + */ + public PoseUpdater(HardwareMap hardwareMap) { + // TODO: replace the second argument with your preferred localizer + this(hardwareMap, new ThreeWheelLocalizer(hardwareMap)); + } + + /** + * This updates the robot's pose, as well as updating the previous pose, velocity, and + * acceleration. The cache for the current pose, velocity, and acceleration is cleared, and + * the time stamps are updated as well. + */ + public void update() { + previousVelocity = getVelocity(); + previousPose = applyOffset(getRawPose()); + currentPose = null; + currentVelocity = null; + currentAcceleration = null; + previousPoseTime = currentPoseTime; + currentPoseTime = System.nanoTime(); + localizer.update(); + } + + /** + * This sets the starting pose. Do not run this after moving at all. + * + * @param set the Pose to set the starting pose to. + */ + public void setStartingPose(Pose set) { + startingPose = set; + previousPose = startingPose; + previousPoseTime = System.nanoTime(); + currentPoseTime = System.nanoTime(); + localizer.setStartPose(set); + } + + /** + * This sets the current pose, using offsets. Think of using offsets as setting trim in an + * aircraft. This can be reset as well, so beware of using the resetOffset() method. + * + * + * @param set The pose to set the current pose to. + */ + public void setCurrentPoseWithOffset(Pose set) { + Pose currentPose = getRawPose(); + setXOffset(set.getX() - currentPose.getX()); + setYOffset(set.getY() - currentPose.getY()); + setHeadingOffset(MathFunctions.getTurnDirection(currentPose.getHeading(), set.getHeading()) * MathFunctions.getSmallestAngleDifference(currentPose.getHeading(), set.getHeading())); + } + + /** + * This sets the offset for only the x position. + * + * @param offset This sets the offset. + */ + public void setXOffset(double offset) { + xOffset = offset; + } + + /** + * This sets the offset for only the y position. + * + * @param offset This sets the offset. + */ + public void setYOffset(double offset) { + yOffset = offset; + } + + /** + * This sets the offset for only the heading. + * + * @param offset This sets the offset. + */ + public void setHeadingOffset(double offset) { + headingOffset = offset; + } + + /** + * This returns the x offset. + * + * @return returns the x offset. + */ + public double getXOffset() { + return xOffset; + } + + /** + * This returns the y offset. + * + * @return returns the y offset. + */ + public double getYOffset() { + return yOffset; + } + + /** + * This returns the heading offset. + * + * @return returns the heading offset. + */ + public double getHeadingOffset() { + return headingOffset; + } + + /** + * This applies the offset to a specified Pose. + * + * @param pose The pose to be offset. + * @return This returns a new Pose with the offset applied. + */ + public Pose applyOffset(Pose pose) { + return new Pose(pose.getX()+xOffset, pose.getY()+yOffset, pose.getHeading()+headingOffset); + } + + /** + * This resets all offsets set to the PoseUpdater. If you have reset your pose using the + * setCurrentPoseUsingOffset(Pose2d set) method, then your pose will be returned to what the + * PoseUpdater thinks your pose would be, not the pose you reset to. + */ + public void resetOffset() { + setXOffset(0); + setYOffset(0); + setHeadingOffset(0); + } + + /** + * This returns the current pose, with offsets applied. If this is called multiple times in + * a single update, the current pose is cached so that subsequent calls don't have to repeat + * localizer calls or calculations. + * + * @return returns the current pose. + */ + public Pose getPose() { + if (currentPose == null) { + currentPose = localizer.getPose(); + return applyOffset(currentPose); + } else { + return applyOffset(currentPose); + } + } + + /** + * This returns the current raw pose, without any offsets applied. If this is called multiple times in + * a single update, the current pose is cached so that subsequent calls don't have to repeat + * localizer calls or calculations. + * + * @return returns the raw pose. + */ + public Pose getRawPose() { + if (currentPose == null) { + currentPose = localizer.getPose(); + return currentPose; + } else { + return currentPose; + } + } + + /** + * This sets the current pose without using resettable offsets. + * + * @param set the pose to set the current pose to. + */ + public void setPose(Pose set) { + resetOffset(); + localizer.setPose(set); + } + + /** + * Returns the robot's pose from the previous update. + * + * @return returns the robot's previous pose. + */ + public Pose getPreviousPose() { + return previousPose; + } + + /** + * Returns the robot's change in pose from the previous update. + * + * @return returns the robot's delta pose. + */ + public Pose getDeltaPose() { + Pose returnPose = getPose(); + returnPose.subtract(previousPose); + return returnPose; + } + + /** + * This returns the velocity of the robot as a Vector. If this is called multiple times in + * a single update, the velocity Vector is cached so that subsequent calls don't have to repeat + * localizer calls or calculations. + * + * @return returns the velocity of the robot. + */ + public Vector getVelocity() { + if (currentVelocity == null) { + currentVelocity = new Vector(); + currentVelocity.setOrthogonalComponents(getPose().getX() - previousPose.getX(), getPose().getY() - previousPose.getY()); + currentVelocity.setMagnitude(MathFunctions.distance(getPose(), previousPose) / ((currentPoseTime - previousPoseTime) / Math.pow(10.0, 9))); + return MathFunctions.copyVector(currentVelocity); + } else { + return MathFunctions.copyVector(currentVelocity); + } + } + + /** + * This returns the angular velocity of the robot as a double. + * + * @return returns the angular velocity of the robot. + */ + public double getAngularVelocity() { + return MathFunctions.getTurnDirection(previousPose.getHeading(), getPose().getHeading()) * MathFunctions.getSmallestAngleDifference(getPose().getHeading(), previousPose.getHeading()) / ((currentPoseTime-previousPoseTime)/Math.pow(10.0, 9)); + } + + /** + * This returns the acceleration of the robot as a Vector. If this is called multiple times in + * a single update, the acceleration Vector is cached so that subsequent calls don't have to + * repeat localizer calls or calculations. + * + * @return returns the acceleration of the robot. + */ + public Vector getAcceleration() { + if (currentAcceleration == null) { + currentAcceleration = MathFunctions.subtractVectors(getVelocity(), previousVelocity); + currentAcceleration.setMagnitude(currentAcceleration.getMagnitude() / ((currentPoseTime - previousPoseTime) / Math.pow(10.0, 9))); + return MathFunctions.copyVector(currentAcceleration); + } else { + return MathFunctions.copyVector(currentAcceleration); + } + } + + /** + * This resets the heading of the robot to the IMU's heading, using Road Runner's pose reset. + */ + public void resetHeadingToIMU() { + localizer.setPose(new Pose(getPose().getX(), getPose().getY(), getNormalizedIMUHeading() + startingPose.getHeading())); + } + + /** + * This resets the heading of the robot to the IMU's heading, using offsets instead of Road + * Runner's pose reset. This way, it's faster, but this can be wiped with the resetOffsets() + * method. + */ + public void resetHeadingToIMUWithOffsets() { + setCurrentPoseWithOffset(new Pose(getPose().getX(), getPose().getY(), getNormalizedIMUHeading() + startingPose.getHeading())); + } + + /** + * This returns the IMU heading normalized to be between [0, 2 PI] radians. + * + * @return returns the normalized IMU heading. + */ + public double getNormalizedIMUHeading() { + return MathFunctions.normalizeAngle(-imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS)); + } + + /** + * This returns the total number of radians the robot has turned. + * + * @return the total heading. + */ + public double getTotalHeading() { + return localizer.getTotalHeading(); + } + + /** + * This returns the Localizer. + * + * @return the Localizer + */ + public Localizer getLocalizer() { + return localizer; + } + + /** + * + */ + public void resetIMU() { + localizer.resetIMU(); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/SparkFunOTOSCorrected.kt b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/SparkFunOTOSCorrected.kt new file mode 100644 index 0000000..76d825c --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/SparkFunOTOSCorrected.kt @@ -0,0 +1,46 @@ +package com.acmerobotics.roadrunner.ftc + +import com.qualcomm.hardware.sparkfun.SparkFunOTOS +import com.qualcomm.robotcore.hardware.I2cDeviceSynch +import com.qualcomm.robotcore.hardware.configuration.annotations.DeviceProperties +import com.qualcomm.robotcore.hardware.configuration.annotations.I2cDeviceType +import java.util.* +@I2cDeviceType +@DeviceProperties( + name = "SparkFun OTOS Corrected", + xmlTag = "SparkFunOTOS2", + description = "SparkFun Qwiic Optical Tracking Odometry Sensor Corrected" +) +class SparkFunOTOSCorrected(deviceClient: I2cDeviceSynch) : SparkFunOTOS(deviceClient) { + /** + * Gets only the position and velocity measured by the + * OTOS in a single burst read + * @param pos Position measured by the OTOS + * @param vel Velocity measured by the OTOS + */ + fun getPosVel(pos: Pose2D, vel: Pose2D) { + // Read all pose registers + val rawData = deviceClient.read(REG_POS_XL.toInt(), 12) + + // Convert raw data to pose units + pos.set(regsToPose(Arrays.copyOfRange(rawData, 0, 6), INT16_TO_METER, INT16_TO_RAD)) + vel.set(regsToPose(Arrays.copyOfRange(rawData, 6, 12), INT16_TO_MPS, INT16_TO_RPS)) + } + + // Modified version of poseToRegs to fix pose setting issue + // see https://discord.com/channels/225450307654647808/1246977443030368349/1271702497659977760 + override fun poseToRegs(rawData: ByteArray, pose: Pose2D, xyToRaw: Double, hToRaw: Double) { + // Convert pose units to raw data + val rawX = (_distanceUnit.toMeters(pose.x) * xyToRaw).toInt().toShort() + val rawY = (_distanceUnit.toMeters(pose.y) * xyToRaw).toInt().toShort() + val rawH = (_angularUnit.toRadians(pose.h) * hToRaw).toInt().toShort() + + // Store raw data in buffer + rawData[0] = (rawX.toInt() and 0xFF).toByte() + rawData[1] = ((rawX.toInt() shr 8) and 0xFF).toByte() + rawData[2] = (rawY.toInt() and 0xFF).toByte() + rawData[3] = ((rawY.toInt() shr 8) and 0xFF).toByte() + rawData[4] = (rawH.toInt() and 0xFF).toByte() + rawData[5] = ((rawH.toInt() shr 8) and 0xFF).toByte() + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/DriveEncoderLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/DriveEncoderLocalizer.java new file mode 100644 index 0000000..a8e3902 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/DriveEncoderLocalizer.java @@ -0,0 +1,272 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization.localizers; + +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName; + +import com.acmerobotics.dashboard.config.Config; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.HardwareMap; + +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Encoder; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Localizer; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Matrix; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; +import org.firstinspires.ftc.teamcode.pedroPathing.util.NanoTimer; + +/** + * This is the DriveEncoderLocalizer class. This class extends the Localizer superclass and is a + * localizer that uses the drive encoder set up. + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 4/2/2024 + */ +@Config +public class DriveEncoderLocalizer extends Localizer { + private HardwareMap hardwareMap; + private Pose startPose; + private Pose displacementPose; + private Pose currentVelocity; + private Matrix prevRotationMatrix; + private NanoTimer timer; + private long deltaTimeNano; + private Encoder leftFront; + private Encoder rightFront; + private Encoder leftRear; + private Encoder rightRear; + private double totalHeading; + public static double FORWARD_TICKS_TO_INCHES = 1; + public static double STRAFE_TICKS_TO_INCHES = 1; + public static double TURN_TICKS_TO_RADIANS = 1; + public static double ROBOT_WIDTH = 1; + public static double ROBOT_LENGTH = 1; + + /** + * This creates a new DriveEncoderLocalizer from a HardwareMap, with a starting Pose at (0,0) + * facing 0 heading. + * + * @param map the HardwareMap + */ + public DriveEncoderLocalizer(HardwareMap map) { + this(map, new Pose()); + } + + /** + * This creates a new DriveEncoderLocalizer from a HardwareMap and a Pose, with the Pose + * specifying the starting pose of the localizer. + * + * @param map the HardwareMap + * @param setStartPose the Pose to start from + */ + public DriveEncoderLocalizer(HardwareMap map, Pose setStartPose) { + hardwareMap = map; + + leftFront = new Encoder(hardwareMap.get(DcMotorEx.class, leftFrontMotorName)); + leftRear = new Encoder(hardwareMap.get(DcMotorEx.class, leftRearMotorName)); + rightRear = new Encoder(hardwareMap.get(DcMotorEx.class, rightRearMotorName)); + rightFront = new Encoder(hardwareMap.get(DcMotorEx.class, rightFrontMotorName)); + + // TODO: reverse any encoders necessary + leftFront.setDirection(Encoder.REVERSE); + rightRear.setDirection(Encoder.REVERSE); + leftRear.setDirection(Encoder.FORWARD); + rightRear.setDirection(Encoder.FORWARD); + + setStartPose(setStartPose); + timer = new NanoTimer(); + deltaTimeNano = 1; + displacementPose = new Pose(); + currentVelocity = new Pose(); + } + + /** + * This returns the current pose estimate. + * + * @return returns the current pose estimate as a Pose + */ + @Override + public Pose getPose() { + return MathFunctions.addPoses(startPose, displacementPose); + } + + /** + * This returns the current velocity estimate. + * + * @return returns the current velocity estimate as a Pose + */ + @Override + public Pose getVelocity() { + return currentVelocity.copy(); + } + + /** + * This returns the current velocity estimate. + * + * @return returns the current velocity estimate as a Vector + */ + @Override + public Vector getVelocityVector() { + return currentVelocity.getVector(); + } + + /** + * This sets the start pose. Changing the start pose should move the robot as if all its + * previous movements were displacing it from its new start pose. + * + * @param setStart the new start pose + */ + @Override + public void setStartPose(Pose setStart) { + startPose = setStart; + } + + /** + * This sets the Matrix that contains the previous pose's heading rotation. + * + * @param heading the rotation of the Matrix + */ + public void setPrevRotationMatrix(double heading) { + prevRotationMatrix = new Matrix(3,3); + prevRotationMatrix.set(0, 0, Math.cos(heading)); + prevRotationMatrix.set(0, 1, -Math.sin(heading)); + prevRotationMatrix.set(1, 0, Math.sin(heading)); + prevRotationMatrix.set(1, 1, Math.cos(heading)); + prevRotationMatrix.set(2, 2, 1.0); + } + + /** + * This sets the current pose estimate. Changing this should just change the robot's current + * pose estimate, not anything to do with the start pose. + * + * @param setPose the new current pose estimate + */ + @Override + public void setPose(Pose setPose) { + displacementPose = MathFunctions.subtractPoses(setPose, startPose); + resetEncoders(); + } + + /** + * This updates the elapsed time timer that keeps track of time between updates, as well as the + * change position of the Encoders. Then, the robot's global change in position is calculated + * using the pose exponential method. + */ + @Override + public void update() { + deltaTimeNano = timer.getElapsedTime(); + timer.resetTimer(); + + updateEncoders(); + Matrix robotDeltas = getRobotDeltas(); + Matrix globalDeltas; + setPrevRotationMatrix(getPose().getHeading()); + + Matrix transformation = new Matrix(3,3); + if (Math.abs(robotDeltas.get(2, 0)) < 0.001) { + transformation.set(0, 0, 1.0 - (Math.pow(robotDeltas.get(2, 0), 2) / 6.0)); + transformation.set(0, 1, -robotDeltas.get(2, 0) / 2.0); + transformation.set(1, 0, robotDeltas.get(2, 0) / 2.0); + transformation.set(1, 1, 1.0 - (Math.pow(robotDeltas.get(2, 0), 2) / 6.0)); + transformation.set(2, 2, 1.0); + } else { + transformation.set(0, 0, Math.sin(robotDeltas.get(2, 0)) / robotDeltas.get(2, 0)); + transformation.set(0, 1, (Math.cos(robotDeltas.get(2, 0)) - 1.0) / robotDeltas.get(2, 0)); + transformation.set(1, 0, (1.0 - Math.cos(robotDeltas.get(2, 0))) / robotDeltas.get(2, 0)); + transformation.set(1, 1, Math.sin(robotDeltas.get(2, 0)) / robotDeltas.get(2, 0)); + transformation.set(2, 2, 1.0); + } + + globalDeltas = Matrix.multiply(Matrix.multiply(prevRotationMatrix, transformation), robotDeltas); + + displacementPose.add(new Pose(globalDeltas.get(0, 0), globalDeltas.get(1, 0), globalDeltas.get(2, 0))); + currentVelocity = new Pose(globalDeltas.get(0, 0) / (deltaTimeNano * Math.pow(10.0, 9)), globalDeltas.get(1, 0) / (deltaTimeNano * Math.pow(10.0, 9)), globalDeltas.get(2, 0) / (deltaTimeNano * Math.pow(10.0, 9))); + + totalHeading += globalDeltas.get(2, 0); + } + + /** + * This updates the Encoders. + */ + public void updateEncoders() { + leftFront.update(); + rightFront.update(); + leftRear.update(); + rightRear.update(); + } + + /** + * This resets the Encoders. + */ + public void resetEncoders() { + leftFront.reset(); + rightFront.reset(); + leftRear.reset(); + rightRear.reset(); + } + + /** + * This calculates the change in position from the perspective of the robot using information + * from the Encoders. + * + * @return returns a Matrix containing the robot relative movement. + */ + public Matrix getRobotDeltas() { + Matrix returnMatrix = new Matrix(3,1); + // x/forward movement + returnMatrix.set(0,0, FORWARD_TICKS_TO_INCHES * (leftFront.getDeltaPosition() + rightFront.getDeltaPosition() + leftRear.getDeltaPosition() + rightRear.getDeltaPosition())); + //y/strafe movement + returnMatrix.set(1,0, STRAFE_TICKS_TO_INCHES * (-leftFront.getDeltaPosition() + rightFront.getDeltaPosition() + leftRear.getDeltaPosition() - rightRear.getDeltaPosition())); + // theta/turning + returnMatrix.set(2,0, TURN_TICKS_TO_RADIANS * ((-leftFront.getDeltaPosition() + rightFront.getDeltaPosition() - leftRear.getDeltaPosition() + rightRear.getDeltaPosition()) / (ROBOT_WIDTH + ROBOT_LENGTH))); + return returnMatrix; + } + + /** + * This returns how far the robot has turned in radians, in a number not clamped between 0 and + * 2 * pi radians. This is used for some tuning things and nothing actually within the following. + * + * @return returns how far the robot has turned in total, in radians. + */ + public double getTotalHeading() { + return totalHeading; + } + + /** + * This returns the multiplier applied to forward movement measurement to convert from encoder + * ticks to inches. This is found empirically through a tuner. + * + * @return returns the forward ticks to inches multiplier + */ + public double getForwardMultiplier() { + return FORWARD_TICKS_TO_INCHES; + } + + /** + * This returns the multiplier applied to lateral/strafe movement measurement to convert from + * encoder ticks to inches. This is found empirically through a tuner. + * + * @return returns the lateral/strafe ticks to inches multiplier + */ + public double getLateralMultiplier() { + return STRAFE_TICKS_TO_INCHES; + } + + /** + * This returns the multiplier applied to turning movement measurement to convert from encoder + * ticks to radians. This is found empirically through a tuner. + * + * @return returns the turning ticks to radians multiplier + */ + public double getTurningMultiplier() { + return TURN_TICKS_TO_RADIANS; + } + + /** + * This does nothing since this localizer does not use the IMU. + */ + public void resetIMU() { + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/OTOSLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/OTOSLocalizer.java new file mode 100644 index 0000000..cdacd52 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/OTOSLocalizer.java @@ -0,0 +1,218 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization.localizers; + +import com.qualcomm.hardware.sparkfun.SparkFunOTOS; +import com.qualcomm.robotcore.hardware.HardwareMap; + +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Localizer; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; + +/** + * This is the OTOSLocalizer class. This class extends the Localizer superclass and is a + * localizer that uses the SparkFun OTOS. The diagram below, which is modified from + * Road Runner, shows a typical set up. + * + * The view is from the top of the robot looking downwards. + * + * left on robot is the y positive direction + * + * forward on robot is the x positive direction + * + * /--------------\ + * | ____ | + * | ---- | + * | || || | + * | || || | ----> left (y positive) + * | | + * | | + * \--------------/ + * | + * | + * V + * forward (x positive) + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 7/20/2024 + */ +public class OTOSLocalizer extends Localizer { + private HardwareMap hardwareMap; + private Pose startPose; + private SparkFunOTOS otos; + private double previousHeading; + private double totalHeading; + + /** + * This creates a new OTOSLocalizer from a HardwareMap, with a starting Pose at (0,0) + * facing 0 heading. + * + * @param map the HardwareMap + */ + public OTOSLocalizer(HardwareMap map) { + this(map, new Pose()); + } + + /** + * This creates a new OTOSLocalizer from a HardwareMap and a Pose, with the Pose + * specifying the starting pose of the localizer. + * + * @param map the HardwareMap + * @param setStartPose the Pose to start from + */ + public OTOSLocalizer(HardwareMap map, Pose setStartPose) { + hardwareMap = map; + + // TODO: replace this with your OTOS port + /* + TODO: If you want to use the "SparkFunOTOSCorrected" version of OTOS, then replace the + 'SparkFunOTOS.class' below with 'SparkFunOTOSCorrected.class' and set the OTOS as a + "SparkFunOTOS Corrected" in your robot confg + */ + SparkFunOTOS + otos = hardwareMap.get(SparkFunOTOS.class, "sensor_otos"); + + otos.setLinearUnit(DistanceUnit.INCH); + otos.setAngularUnit(AngleUnit.RADIANS); + + // TODO: replace this with your OTOS offset from the center of the robot + // For the OTOS, left/right is the y axis and forward/backward is the x axis, with left being + // positive y and forward being positive x. PI/2 radians is facing forward, and clockwise + // rotation is negative rotation. + otos.setOffset(new SparkFunOTOS.Pose2D(0,0,Math.PI / 2)); + + // TODO: replace these with your tuned multipliers + otos.setLinearScalar(1.0); + otos.setAngularScalar(1.0); + + otos.calibrateImu(); + otos.resetTracking(); + + setStartPose(setStartPose); + totalHeading = 0; + previousHeading = startPose.getHeading(); + + resetOTOS(); + } + + /** + * This returns the current pose estimate. + * + * @return returns the current pose estimate as a Pose + */ + @Override + public Pose getPose() { + SparkFunOTOS.Pose2D pose = otos.getPosition(); + return MathFunctions.addPoses(startPose, new Pose(pose.x, pose.y, pose.h)); + } + + /** + * This returns the current velocity estimate. + * + * @return returns the current velocity estimate as a Pose + */ + @Override + public Pose getVelocity() { + SparkFunOTOS.Pose2D OTOSVelocity = otos.getVelocity(); + return new Pose(OTOSVelocity.x, OTOSVelocity.y, OTOSVelocity.h); + } + + /** + * This returns the current velocity estimate. + * + * @return returns the current velocity estimate as a Vector + */ + @Override + public Vector getVelocityVector() { + return getVelocity().getVector(); + } + + /** + * This sets the start pose. Changing the start pose should move the robot as if all its + * previous movements were displacing it from its new start pose. + * + * @param setStart the new start pose + */ + @Override + public void setStartPose(Pose setStart) { + startPose = setStart; + } + + /** + * This sets the current pose estimate. Changing this should just change the robot's current + * pose estimate, not anything to do with the start pose. + * + * @param setPose the new current pose estimate + */ + @Override + public void setPose(Pose setPose) { + resetOTOS(); + Pose setOTOSPose = MathFunctions.subtractPoses(setPose, startPose); + otos.setPosition(new SparkFunOTOS.Pose2D(setOTOSPose.getX(), setOTOSPose.getY(), setOTOSPose.getHeading())); + } + + /** + * This updates the total heading of the robot. The OTOS handles all other updates itself. + */ + @Override + public void update() { + totalHeading += MathFunctions.getSmallestAngleDifference(otos.getPosition().h, previousHeading); + previousHeading = otos.getPosition().h; + } + + /** + * This resets the OTOS. + */ + public void resetOTOS() { + otos.resetTracking(); + } + + /** + * This returns how far the robot has turned in radians, in a number not clamped between 0 and + * 2 * pi radians. This is used for some tuning things and nothing actually within the following. + * + * @return returns how far the robot has turned in total, in radians. + */ + public double getTotalHeading() { + return totalHeading; + } + + /** + * This returns the multiplier applied to forward movement measurement to convert from OTOS + * ticks to inches. For the OTOS, this value is the same as the lateral multiplier. + * This is found empirically through a tuner. + * + * @return returns the forward ticks to inches multiplier + */ + public double getForwardMultiplier() { + return otos.getLinearScalar(); + } + + /** + * This returns the multiplier applied to lateral/strafe movement measurement to convert from + * OTOS ticks to inches. For the OTOS, this value is the same as the forward multiplier. + * This is found empirically through a tuner. + * + * @return returns the lateral/strafe ticks to inches multiplier + */ + public double getLateralMultiplier() { + return otos.getLinearScalar(); + } + + /** + * This returns the multiplier applied to turning movement measurement to convert from OTOS ticks + * to radians. This is found empirically through a tuner. + * + * @return returns the turning ticks to radians multiplier + */ + public double getTurningMultiplier() { + return otos.getAngularScalar(); + } + + /** + * This does nothing since this localizer does not use the IMU. + */ + public void resetIMU() { + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/RRToPedroThreeWheelLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/RRToPedroThreeWheelLocalizer.java new file mode 100644 index 0000000..15275f0 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/RRToPedroThreeWheelLocalizer.java @@ -0,0 +1,159 @@ +//package org.firstinspires.ftc.teamcode.pedroPathing.localization; +// +//import com.acmerobotics.roadrunner.geometry.Pose2d; +//import com.qualcomm.robotcore.hardware.HardwareMap; +// +//import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +//import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; +// +//import java.util.ArrayList; +//import java.util.List; +// +///** +// * This is the RRToPedroThreeWheelLocalizer class. This class extends the Localizer superclass and +// * is intended to adapt the old Road Runner three wheel odometry localizer to the new Pedro Pathing +// * localizer system. +// * +// * @author Anyi Lin - 10158 Scott's Bots +// * @version 1.0, 5/9/2024 +// */ +//public class RRToPedroThreeWheelLocalizer extends Localizer { +// private RoadRunnerThreeWheelLocalizer localizer; +// private double totalHeading; +// private Pose startPose; +// private Pose previousPose; +// +// /** +// * This creates a new RRToPedroThreeWheelLocalizer from a HardwareMap. This adapts the previously +// * used Road Runner localization system to the new Pedro Pathing localization system. +// * +// * @param hardwareMap the HardwareMap +// */ +// public RRToPedroThreeWheelLocalizer(HardwareMap hardwareMap) { +// List lastTrackingEncPositions = new ArrayList<>(); +// List lastTrackingEncVels = new ArrayList<>(); +// +// localizer = new RoadRunnerThreeWheelLocalizer(hardwareMap, lastTrackingEncPositions, lastTrackingEncVels); +// +// startPose = new Pose(); +// previousPose = new Pose(); +// } +// +// /** +// * This returns the current pose estimate as a Pose. +// * +// * @return returns the current pose estimate +// */ +// @Override +// public Pose getPose() { +// Pose2d pose = localizer.getPoseEstimate(); +// return new Pose(pose.getX(), pose.getY(), pose.getHeading()); +// } +// +// /** +// * This returns the current velocity estimate as a Pose. +// * +// * @return returns the current velocity estimate +// */ +// @Override +// public Pose getVelocity() { +// Pose2d pose = localizer.getPoseVelocity(); +// return new Pose(pose.getX(), pose.getY(), pose.getHeading()); +// } +// +// /** +// * This returns the current velocity estimate as a Vector. +// * +// * @return returns the current velocity estimate +// */ +// @Override +// public Vector getVelocityVector() { +// Pose2d pose = localizer.getPoseVelocity(); +// Vector returnVector = new Vector(); +// returnVector.setOrthogonalComponents(pose.getX(), pose.getY()); +// return returnVector; +// } +// +// /** +// * This sets the start pose. Any movement of the robot is treated as a displacement from the +// * start pose, so moving the start pose will move the current pose estimate the same amount. +// * +// * @param setStart the new start pose +// */ +// @Override +// public void setStartPose(Pose setStart) { +// Pose oldStart = startPose; +// startPose = setStart; +// Pose startDiff = MathFunctions.subtractPoses(startPose, oldStart); +// localizer.setPoseEstimate(new Pose2d(getPose().getX() + startDiff.getX(), getPose().getY() + startDiff.getY(), getPose().getHeading() + startDiff.getHeading())); +// } +// +// /** +// * This sets the current pose estimate. This has no effect on the start pose. +// * +// * @param setPose the new current pose estimate +// */ +// @Override +// public void setPose(Pose setPose) { +// localizer.setPoseEstimate(new Pose2d(setPose.getX(), setPose.getY(), setPose.getHeading())); +// } +// +// /** +// * This updates the total heading and previous pose estimate. Everything else is handled by the +// * Road Runner localizer on its own, but updating this tells you how far the robot has really +// * turned. +// */ +// @Override +// public void update() { +// totalHeading += MathFunctions.getTurnDirection(previousPose.getHeading(), getPose().getHeading()) * MathFunctions.getSmallestAngleDifference(previousPose.getHeading(), getPose().getHeading()); +// previousPose = getPose(); +// } +// +// /** +// * This returns how far the robot has actually turned. +// * +// * @return returns the total angle turned, in degrees. +// */ +// @Override +// public double getTotalHeading() { +// return totalHeading; +// } +// +// /** +// * This returns the forward multiplier of the Road Runner localizer, which converts from ticks +// * to inches. You can actually use the tuners in Pedro Pathing to find the value that everything +// * multiplied together should be. If you do use that, then do be aware that the value returned is +// * the product of the Road Runner ticks to inches and the x multiplier. +// * +// * @return returns the forward multiplier +// */ +// @Override +// public double getForwardMultiplier() { +// return RoadRunnerThreeWheelLocalizer.encoderTicksToInches(1) * RoadRunnerThreeWheelLocalizer.X_MULTIPLIER; +// } +// +// /** +// * This returns the lateral multiplier of the Road Runner localizer, which converts from ticks +// * to inches. You can actually use the tuners in Pedro Pathing to find the value that everything +// * multiplied together should be. If you do use that, then do be aware that the value returned is +// * the product of the Road Runner ticks to inches and the y multiplier. +// * +// * @return returns the lateral multiplier +// */ +// @Override +// public double getLateralMultiplier() { +// return RoadRunnerThreeWheelLocalizer.encoderTicksToInches(1) * RoadRunnerThreeWheelLocalizer.Y_MULTIPLIER; +// } +// +// /** +// * This returns the turning multiplier of the Road Runner localizer, which doesn't actually exist. +// * There really isn't a point in tuning the turning for the Road Runner localizer. This will +// * actually just return the average of the two other multipliers. +// * +// * @return returns the turning multiplier +// */ +// @Override +// public double getTurningMultiplier() { +// return (getForwardMultiplier() + getLateralMultiplier()) / 2; +// } +//} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/RoadRunnerEncoder.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/RoadRunnerEncoder.java new file mode 100644 index 0000000..d743b49 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/RoadRunnerEncoder.java @@ -0,0 +1,132 @@ +//package org.firstinspires.ftc.teamcode.pedroPathing.localization; +// +//import com.acmerobotics.roadrunner.util.NanoClock; +//import com.qualcomm.robotcore.hardware.DcMotorEx; +//import com.qualcomm.robotcore.hardware.DcMotorSimple; +// +///** +// * This class is adapted from the Road Runner Encoder class. Later, this will be replaced with a +// * custom encoder class. According to Road Runner, this wraps a motor instance to provide corrected +// * velocity counts and allow reversing independently of the corresponding slot's motor direction. +// * +// * I'm fairly sure I didn't make any changes to this class, just copied it so I wouldn't have to have +// * import statements, so I'm not crediting myself as an author for this. +// * +// * @author Road Runner dev team +// * @version 1.0, 5/9/2024 +// */ +//public class RoadRunnerEncoder { +// private final static int CPS_STEP = 0x10000; +// +// private static double inverseOverflow(double input, double estimate) { +// // convert to uint16 +// int real = (int) input & 0xffff; +// // initial, modulo-based correction: it can recover the remainder of 5 of the upper 16 bits +// // because the velocity is always a multiple of 20 cps due to Expansion Hub's 50ms measurement window +// real += ((real % 20) / 4) * CPS_STEP; +// // estimate-based correction: it finds the nearest multiple of 5 to correct the upper bits by +// real += Math.round((estimate - real) / (5 * CPS_STEP)) * 5 * CPS_STEP; +// return real; +// } +// +// public enum Direction { +// FORWARD(1), +// REVERSE(-1); +// +// private int multiplier; +// +// Direction(int multiplier) { +// this.multiplier = multiplier; +// } +// +// public int getMultiplier() { +// return multiplier; +// } +// } +// +// private DcMotorEx motor; +// private NanoClock clock; +// +// private Direction direction; +// +// private int lastPosition; +// private int velocityEstimateIdx; +// private double[] velocityEstimates; +// private double lastUpdateTime; +// +// public RoadRunnerEncoder(DcMotorEx motor, NanoClock clock) { +// this.motor = motor; +// this.clock = clock; +// +// this.direction = Direction.FORWARD; +// +// this.lastPosition = 0; +// this.velocityEstimates = new double[3]; +// this.lastUpdateTime = clock.seconds(); +// } +// +// public RoadRunnerEncoder(DcMotorEx motor) { +// this(motor, NanoClock.system()); +// } +// +// public Direction getDirection() { +// return direction; +// } +// +// private int getMultiplier() { +// return getDirection().getMultiplier() * (motor.getDirection() == DcMotorSimple.Direction.FORWARD ? 1 : -1); +// } +// +// /** +// * Allows you to set the direction of the counts and velocity without modifying the motor's direction state +// * @param direction either reverse or forward depending on if encoder counts should be negated +// */ +// public void setDirection(Direction direction) { +// this.direction = direction; +// } +// +// /** +// * Gets the position from the underlying motor and adjusts for the set direction. +// * Additionally, this method updates the velocity estimates used for compensated velocity +// * +// * @return encoder position +// */ +// public int getCurrentPosition() { +// int multiplier = getMultiplier(); +// int currentPosition = motor.getCurrentPosition() * multiplier; +// if (currentPosition != lastPosition) { +// double currentTime = clock.seconds(); +// double dt = currentTime - lastUpdateTime; +// velocityEstimates[velocityEstimateIdx] = (currentPosition - lastPosition) / dt; +// velocityEstimateIdx = (velocityEstimateIdx + 1) % 3; +// lastPosition = currentPosition; +// lastUpdateTime = currentTime; +// } +// return currentPosition; +// } +// +// /** +// * Gets the velocity directly from the underlying motor and compensates for the direction +// * See {@link #getCorrectedVelocity} for high (>2^15) counts per second velocities (such as on REV Through Bore) +// * +// * @return raw velocity +// */ +// public double getRawVelocity() { +// int multiplier = getMultiplier(); +// return motor.getVelocity() * multiplier; +// } +// +// /** +// * Uses velocity estimates gathered in {@link #getCurrentPosition} to estimate the upper bits of velocity +// * that are lost in overflow due to velocity being transmitted as 16 bits. +// * CAVEAT: must regularly call {@link #getCurrentPosition} for the compensation to work correctly. +// * +// * @return corrected velocity +// */ +// public double getCorrectedVelocity() { +// double median = velocityEstimates[0] > velocityEstimates[1] +// ? Math.max(velocityEstimates[1], Math.min(velocityEstimates[0], velocityEstimates[2])) +// : Math.max(velocityEstimates[0], Math.min(velocityEstimates[1], velocityEstimates[2])); +// return inverseOverflow(getRawVelocity(), median); +// } +//} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/RoadRunnerThreeWheelLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/RoadRunnerThreeWheelLocalizer.java new file mode 100644 index 0000000..2ee75a9 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/RoadRunnerThreeWheelLocalizer.java @@ -0,0 +1,123 @@ +//package org.firstinspires.ftc.teamcode.pedroPathing.localization; +// +//import androidx.annotation.NonNull; +// +//import com.acmerobotics.dashboard.config.Config; +//import com.acmerobotics.roadrunner.geometry.Pose2d; +//import com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer; +//import com.qualcomm.robotcore.hardware.DcMotorEx; +//import com.qualcomm.robotcore.hardware.HardwareMap; +// +//import java.util.Arrays; +//import java.util.List; +// +///* +// * Sample tracking wheel localizer implementation assuming the standard configuration: +// * +// * left on robot is y pos +// * +// * front of robot is x pos +// * +// * /--------------\ +// * | ____ | +// * | ---- | +// * | || || | +// * | || || | +// * | | +// * | | +// * \--------------/ +// * +// */ +// +///** +// * This class is adapted from the Road Runner StandardTrackingWheelLocalizer class. Later, this will +// * be replaced with a custom localizer. I made some minor changes, so I'm crediting myself as an +// * 'author' of sorts, but really this is pretty much Road Runner's code, just moved to be local to +// * Pedro Pathing to avoid having imports. +// * +// * @author Road Runner dev team +// * @author Anyi Lin - 10158 Scott's Bots +// * @version 1.0, 5/9/2024 +// */ +//@Config +//public class RoadRunnerThreeWheelLocalizer extends ThreeTrackingWheelLocalizer { +// public static double TICKS_PER_REV = 8192; +// public static double WHEEL_RADIUS = 1.37795; // in +// public static double GEAR_RATIO = 1; // output (wheel) speed / input (encoder) speed +// +// public static double X_MULTIPLIER = 0.5008239963; +// public static double Y_MULTIPLIER = 0.5018874659; +// +// public static double leftX = -18.5/25.4 - 0.1, leftY = 164.4/25.4, rightX = -18.4/25.4 - 0.1, rightY = -159.6/25.4, strafeX = -107.9/25.4+0.25, strafeY = -1.1/25.4-0.23; +// +// private RoadRunnerEncoder leftEncoder, rightEncoder, strafeEncoder; +// +// private List lastEncPositions, lastEncVels; +// +// public RoadRunnerThreeWheelLocalizer(HardwareMap hardwareMap, List lastTrackingEncPositions, List lastTrackingEncVels) { +// super(Arrays.asList( +// new Pose2d(leftX, leftY, 0), // left +// new Pose2d(rightX, rightY, 0), // right +// new Pose2d(strafeX, strafeY, Math.toRadians(90)) // strafe +// )); +// +// lastEncPositions = lastTrackingEncPositions; +// lastEncVels = lastTrackingEncVels; +// +// // TODO: redo the configs here +// leftEncoder = new RoadRunnerEncoder(hardwareMap.get(DcMotorEx.class, "leftRear")); +// rightEncoder = new RoadRunnerEncoder(hardwareMap.get(DcMotorEx.class, "rightFront")); +// strafeEncoder = new RoadRunnerEncoder(hardwareMap.get(DcMotorEx.class, "strafeEncoder")); +// +// // TODO: reverse any encoders using Encoder.setDirection(Encoder.Direction.REVERSE) +// leftEncoder.setDirection(RoadRunnerEncoder.Direction.REVERSE); +// rightEncoder.setDirection(RoadRunnerEncoder.Direction.REVERSE); +// strafeEncoder.setDirection(RoadRunnerEncoder.Direction.FORWARD); +// } +// +// public void resetHeading(double heading) { +// setPoseEstimate(new Pose2d(getPoseEstimate().getX(), getPoseEstimate().getY(), heading)); +// } +// +// public static double encoderTicksToInches(double ticks) { +// return WHEEL_RADIUS * 2 * Math.PI * GEAR_RATIO * ticks / TICKS_PER_REV; +// } +// +// @NonNull +// @Override +// public List getWheelPositions() { +// int leftPos = leftEncoder.getCurrentPosition(); +// int rightPos = rightEncoder.getCurrentPosition(); +// int frontPos = strafeEncoder.getCurrentPosition(); +// +// lastEncPositions.clear(); +// lastEncPositions.add(leftPos); +// lastEncPositions.add(rightPos); +// lastEncPositions.add(frontPos); +// +// return Arrays.asList( +// encoderTicksToInches(leftPos) * X_MULTIPLIER, +// encoderTicksToInches(rightPos) * X_MULTIPLIER, +// encoderTicksToInches(frontPos) * Y_MULTIPLIER +// ); +// } +// +// @NonNull +// @Override +// public List getWheelVelocities() { +// int leftVel = (int) leftEncoder.getCorrectedVelocity(); +// int rightVel = (int) rightEncoder.getCorrectedVelocity(); +// int frontVel = (int) strafeEncoder.getCorrectedVelocity(); +// +// lastEncVels.clear(); +// lastEncVels.add(leftVel); +// lastEncVels.add(rightVel); +// lastEncVels.add(frontVel); +// +// return Arrays.asList( +// encoderTicksToInches(leftVel) * X_MULTIPLIER, +// encoderTicksToInches(rightVel) * X_MULTIPLIER, +// encoderTicksToInches(frontVel) * Y_MULTIPLIER +// ); +// } +//} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelIMULocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelIMULocalizer.java new file mode 100644 index 0000000..1e9fd7b --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelIMULocalizer.java @@ -0,0 +1,316 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization.localizers; + +import com.acmerobotics.dashboard.config.Config; +import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.HardwareMap; +import com.qualcomm.robotcore.hardware.IMU; + +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Encoder; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Localizer; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Matrix; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; +import org.firstinspires.ftc.teamcode.pedroPathing.util.NanoTimer; + +/** + * This is the ThreeWheelIMULocalizer class. This class extends the Localizer superclass and is a + * localizer that uses the three wheel odometry set up with the IMU to have more accurate heading + * readings. The diagram below, which is modified from Road Runner, shows a typical set up. + * + * The view is from the top of the robot looking downwards. + * + * left on robot is the y positive direction + * + * forward on robot is the x positive direction + * + * /--------------\ + * | ____ | + * | ---- | + * | || || | + * | || || | ----> left (y positive) + * | | + * | | + * \--------------/ + * | + * | + * V + * forward (x positive) + * + * @author Logan Nash + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 7/9/2024 + */ +@Config +public class ThreeWheelIMULocalizer extends Localizer { + private HardwareMap hardwareMap; + private Pose startPose; + private Pose displacementPose; + private Pose currentVelocity; + private Matrix prevRotationMatrix; + private NanoTimer timer; + private long deltaTimeNano; + private Encoder leftEncoder; + private Encoder rightEncoder; + private Encoder strafeEncoder; + private Pose leftEncoderPose; + private Pose rightEncoderPose; + private Pose strafeEncoderPose; + + public final IMU imu; + private double previousIMUOrientation; + private double deltaRadians; + private double totalHeading; + public static double FORWARD_TICKS_TO_INCHES = 0.002957;//8192 * 1.37795 * 2 * Math.PI * 0.5008239963; + public static double STRAFE_TICKS_TO_INCHES = -0.003127403096038503;//8192 * 1.37795 * 2 * Math.PI * 0.5018874659; + public static double TURN_TICKS_TO_RADIANS = 0.002995;//8192 * 1.37795 * 2 * Math.PI * 0.5; + + public static boolean useIMU = true; + + /** + * This creates a new ThreeWheelIMULocalizer from a HardwareMap, with a starting Pose at (0,0) + * facing 0 heading. + * + * @param map the HardwareMap + */ + public ThreeWheelIMULocalizer(HardwareMap map) { + this(map, new Pose()); + } + + /** + * This creates a new ThreeWheelIMULocalizer from a HardwareMap and a Pose, with the Pose + * specifying the starting pose of the localizer. + * + * @param map the HardwareMap + * @param setStartPose the Pose to start from + */ + public ThreeWheelIMULocalizer(HardwareMap map, Pose setStartPose) { + hardwareMap = map; + imu = hardwareMap.get(IMU.class, "imu"); + + // TODO: replace this with your IMU's orientation + imu.initialize(new IMU.Parameters(new RevHubOrientationOnRobot(RevHubOrientationOnRobot.LogoFacingDirection.LEFT, RevHubOrientationOnRobot.UsbFacingDirection.UP))); + + // TODO: replace these with your encoder positions + leftEncoderPose = new Pose(-3, 5.7, 0); + rightEncoderPose = new Pose(-3, -5.7, 0); + strafeEncoderPose = new Pose(6.9, 1, Math.toRadians(90)); + + + // TODO: replace these with your encoder ports + leftEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, "lb")); + rightEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, "lf")); + strafeEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, "rf")); + + // TODO: reverse any encoders necessary + leftEncoder.setDirection(Encoder.REVERSE); + rightEncoder.setDirection(Encoder.FORWARD); + strafeEncoder.setDirection(Encoder.FORWARD); + + setStartPose(setStartPose); + timer = new NanoTimer(); + deltaTimeNano = 1; + displacementPose = new Pose(); + currentVelocity = new Pose(); + totalHeading = 0; + + resetEncoders(); + } + + /** + * This returns the current pose estimate. + * + * @return returns the current pose estimate as a Pose + */ + @Override + public Pose getPose() { + return MathFunctions.addPoses(startPose, displacementPose); + } + + /** + * This returns the current velocity estimate. + * + * @return returns the current velocity estimate as a Pose + */ + @Override + public Pose getVelocity() { + return currentVelocity.copy(); + } + + /** + * This returns the current velocity estimate. + * + * @return returns the current velocity estimate as a Vector + */ + @Override + public Vector getVelocityVector() { + return currentVelocity.getVector(); + } + + /** + * This sets the start pose. Changing the start pose should move the robot as if all its + * previous movements were displacing it from its new start pose. + * + * @param setStart the new start pose + */ + @Override + public void setStartPose(Pose setStart) { + startPose = setStart; + } + + /** + * This sets the Matrix that contains the previous pose's heading rotation. + * + * @param heading the rotation of the Matrix + */ + public void setPrevRotationMatrix(double heading) { + prevRotationMatrix = new Matrix(3,3); + prevRotationMatrix.set(0, 0, Math.cos(heading)); + prevRotationMatrix.set(0, 1, -Math.sin(heading)); + prevRotationMatrix.set(1, 0, Math.sin(heading)); + prevRotationMatrix.set(1, 1, Math.cos(heading)); + prevRotationMatrix.set(2, 2, 1.0); + } + + /** + * This sets the current pose estimate. Changing this should just change the robot's current + * pose estimate, not anything to do with the start pose. + * + * @param setPose the new current pose estimate + */ + @Override + public void setPose(Pose setPose) { + displacementPose = MathFunctions.subtractPoses(setPose, startPose); + resetEncoders(); + } + + /** + * This updates the elapsed time timer that keeps track of time between updates, as well as the + * change position of the Encoders. Then, the robot's global change in position is calculated + * using the pose exponential method. + */ + @Override + public void update() { + deltaTimeNano = timer.getElapsedTime(); + timer.resetTimer(); + + updateEncoders(); + Matrix robotDeltas = getRobotDeltas(); + Matrix globalDeltas; + setPrevRotationMatrix(getPose().getHeading()); + + Matrix transformation = new Matrix(3,3); + if (Math.abs(robotDeltas.get(2, 0)) < 0.001) { + transformation.set(0, 0, 1.0 - (Math.pow(robotDeltas.get(2, 0), 2) / 6.0)); + transformation.set(0, 1, -robotDeltas.get(2, 0) / 2.0); + transformation.set(1, 0, robotDeltas.get(2, 0) / 2.0); + transformation.set(1, 1, 1.0 - (Math.pow(robotDeltas.get(2, 0), 2) / 6.0)); + transformation.set(2, 2, 1.0); + } else { + transformation.set(0, 0, Math.sin(robotDeltas.get(2, 0)) / robotDeltas.get(2, 0)); + transformation.set(0, 1, (Math.cos(robotDeltas.get(2, 0)) - 1.0) / robotDeltas.get(2, 0)); + transformation.set(1, 0, (1.0 - Math.cos(robotDeltas.get(2, 0))) / robotDeltas.get(2, 0)); + transformation.set(1, 1, Math.sin(robotDeltas.get(2, 0)) / robotDeltas.get(2, 0)); + transformation.set(2, 2, 1.0); + } + + globalDeltas = Matrix.multiply(Matrix.multiply(prevRotationMatrix, transformation), robotDeltas); + + displacementPose.add(new Pose(globalDeltas.get(0, 0), globalDeltas.get(1, 0), globalDeltas.get(2, 0))); + currentVelocity = new Pose(globalDeltas.get(0, 0) / (deltaTimeNano * Math.pow(10.0, 9)), globalDeltas.get(1, 0) / (deltaTimeNano * Math.pow(10.0, 9)), globalDeltas.get(2, 0) / (deltaTimeNano * Math.pow(10.0, 9))); + + totalHeading += globalDeltas.get(2, 0); + } + + /** + * This updates the Encoders. + */ + public void updateEncoders() { + leftEncoder.update(); + rightEncoder.update(); + strafeEncoder.update(); + + double currentIMUOrientation = MathFunctions.normalizeAngle(imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS)); + deltaRadians = MathFunctions.getTurnDirection(previousIMUOrientation, currentIMUOrientation) * MathFunctions.getSmallestAngleDifference(currentIMUOrientation, previousIMUOrientation); + previousIMUOrientation = currentIMUOrientation; + } + + /** + * This resets the Encoders. + */ + public void resetEncoders() { + leftEncoder.reset(); + rightEncoder.reset(); + strafeEncoder.reset(); + } + + /** + * This calculates the change in position from the perspective of the robot using information + * from the Encoders. + * + * @return returns a Matrix containing the robot relative movement. + */ + public Matrix getRobotDeltas() { + Matrix returnMatrix = new Matrix(3,1); + // x/forward movement + returnMatrix.set(0,0, FORWARD_TICKS_TO_INCHES * ((rightEncoder.getDeltaPosition() * leftEncoderPose.getY() - leftEncoder.getDeltaPosition() * rightEncoderPose.getY()) / (leftEncoderPose.getY() - rightEncoderPose.getY()))); + //y/strafe movement + returnMatrix.set(1,0, STRAFE_TICKS_TO_INCHES * (strafeEncoder.getDeltaPosition() - strafeEncoderPose.getX() * ((rightEncoder.getDeltaPosition() - leftEncoder.getDeltaPosition()) / (leftEncoderPose.getY() - rightEncoderPose.getY())))); + // theta/turning + if (MathFunctions.getSmallestAngleDifference(0, deltaRadians) > 0.00005 && useIMU) { + returnMatrix.set(2, 0, deltaRadians); + } else { + returnMatrix.set(2,0, TURN_TICKS_TO_RADIANS * ((rightEncoder.getDeltaPosition() - leftEncoder.getDeltaPosition()) / (leftEncoderPose.getY() - rightEncoderPose.getY()))); + } + return returnMatrix; + } + + /** + * This returns how far the robot has turned in radians, in a number not clamped between 0 and + * 2 * pi radians. This is used for some tuning things and nothing actually within the following. + * + * @return returns how far the robot has turned in total, in radians. + */ + public double getTotalHeading() { + return totalHeading; + } + + /** + * This returns the multiplier applied to forward movement measurement to convert from encoder + * ticks to inches. This is found empirically through a tuner. + * + * @return returns the forward ticks to inches multiplier + */ + public double getForwardMultiplier() { + return FORWARD_TICKS_TO_INCHES; + } + + /** + * This returns the multiplier applied to lateral/strafe movement measurement to convert from + * encoder ticks to inches. This is found empirically through a tuner. + * + * @return returns the lateral/strafe ticks to inches multiplier + */ + public double getLateralMultiplier() { + return STRAFE_TICKS_TO_INCHES; + } + + /** + * This returns the multiplier applied to turning movement measurement to convert from encoder + * ticks to radians. This is found empirically through a tuner. + * + * @return returns the turning ticks to radians multiplier + */ + public double getTurningMultiplier() { + return TURN_TICKS_TO_RADIANS; + } + + /** + * This resets the IMU. + */ + public void resetIMU() { + imu.resetYaw(); + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelLocalizer.java new file mode 100644 index 0000000..6814b86 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/ThreeWheelLocalizer.java @@ -0,0 +1,292 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization.localizers; + +import com.acmerobotics.dashboard.config.Config; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.HardwareMap; + +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Encoder; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Localizer; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Matrix; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; +import org.firstinspires.ftc.teamcode.pedroPathing.util.NanoTimer; + +/** + * This is the ThreeWheelLocalizer class. This class extends the Localizer superclass and is a + * localizer that uses the three wheel odometry set up. The diagram below, which is modified from + * Road Runner, shows a typical set up. + * + * The view is from the top of the robot looking downwards. + * + * left on robot is the y positive direction + * + * forward on robot is the x positive direction + * + * /--------------\ + * | ____ | + * | ---- | + * | || || | + * | || || | ----> left (y positive) + * | | + * | | + * \--------------/ + * | + * | + * V + * forward (x positive) + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 4/2/2024 + */ +@Config +public class ThreeWheelLocalizer extends Localizer { + private HardwareMap hardwareMap; + private Pose startPose; + private Pose displacementPose; + private Pose currentVelocity; + private Matrix prevRotationMatrix; + private NanoTimer timer; + private long deltaTimeNano; + private Encoder leftEncoder; + private Encoder rightEncoder; + private Encoder strafeEncoder; + private Pose leftEncoderPose; + private Pose rightEncoderPose; + private Pose strafeEncoderPose; + private double totalHeading; + public static double FORWARD_TICKS_TO_INCHES = 0.00052189;//8192 * 1.37795 * 2 * Math.PI * 0.5008239963; + public static double STRAFE_TICKS_TO_INCHES = 0.00052189;//8192 * 1.37795 * 2 * Math.PI * 0.5018874659; + public static double TURN_TICKS_TO_RADIANS = 0.00053717;//8192 * 1.37795 * 2 * Math.PI * 0.5; + + /** + * This creates a new ThreeWheelLocalizer from a HardwareMap, with a starting Pose at (0,0) + * facing 0 heading. + * + * @param map the HardwareMap + */ + public ThreeWheelLocalizer(HardwareMap map) { + this(map, new Pose()); + } + + /** + * This creates a new ThreeWheelLocalizer from a HardwareMap and a Pose, with the Pose + * specifying the starting pose of the localizer. + * + * @param map the HardwareMap + * @param setStartPose the Pose to start from + */ + public ThreeWheelLocalizer(HardwareMap map, Pose setStartPose) { + // TODO: replace these with your encoder positions + leftEncoderPose = new Pose(-18.5/25.4 - 0.1, 164.4/25.4, 0); + rightEncoderPose = new Pose(-18.4/25.4 - 0.1, -159.6/25.4, 0); + strafeEncoderPose = new Pose(0*(-107.9/25.4+8)+-107.9/25.4+0.25, -1.1/25.4-0.23, Math.toRadians(90)); + + hardwareMap = map; + + // TODO: replace these with your encoder ports + leftEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, "leftRear")); + rightEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, "rightFront")); + strafeEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, "strafeEncoder")); + + // TODO: reverse any encoders necessary + leftEncoder.setDirection(Encoder.REVERSE); + rightEncoder.setDirection(Encoder.REVERSE); + strafeEncoder.setDirection(Encoder.FORWARD); + + setStartPose(setStartPose); + timer = new NanoTimer(); + deltaTimeNano = 1; + displacementPose = new Pose(); + currentVelocity = new Pose(); + totalHeading = 0; + + resetEncoders(); + } + + /** + * This returns the current pose estimate. + * + * @return returns the current pose estimate as a Pose + */ + @Override + public Pose getPose() { + return MathFunctions.addPoses(startPose, displacementPose); + } + + /** + * This returns the current velocity estimate. + * + * @return returns the current velocity estimate as a Pose + */ + @Override + public Pose getVelocity() { + return currentVelocity.copy(); + } + + /** + * This returns the current velocity estimate. + * + * @return returns the current velocity estimate as a Vector + */ + @Override + public Vector getVelocityVector() { + return currentVelocity.getVector(); + } + + /** + * This sets the start pose. Changing the start pose should move the robot as if all its + * previous movements were displacing it from its new start pose. + * + * @param setStart the new start pose + */ + @Override + public void setStartPose(Pose setStart) { + startPose = setStart; + } + + /** + * This sets the Matrix that contains the previous pose's heading rotation. + * + * @param heading the rotation of the Matrix + */ + public void setPrevRotationMatrix(double heading) { + prevRotationMatrix = new Matrix(3,3); + prevRotationMatrix.set(0, 0, Math.cos(heading)); + prevRotationMatrix.set(0, 1, -Math.sin(heading)); + prevRotationMatrix.set(1, 0, Math.sin(heading)); + prevRotationMatrix.set(1, 1, Math.cos(heading)); + prevRotationMatrix.set(2, 2, 1.0); + } + + /** + * This sets the current pose estimate. Changing this should just change the robot's current + * pose estimate, not anything to do with the start pose. + * + * @param setPose the new current pose estimate + */ + @Override + public void setPose(Pose setPose) { + displacementPose = MathFunctions.subtractPoses(setPose, startPose); + resetEncoders(); + } + + /** + * This updates the elapsed time timer that keeps track of time between updates, as well as the + * change position of the Encoders. Then, the robot's global change in position is calculated + * using the pose exponential method. + */ + @Override + public void update() { + deltaTimeNano = timer.getElapsedTime(); + timer.resetTimer(); + + updateEncoders(); + Matrix robotDeltas = getRobotDeltas(); + Matrix globalDeltas; + setPrevRotationMatrix(getPose().getHeading()); + + Matrix transformation = new Matrix(3,3); + if (Math.abs(robotDeltas.get(2, 0)) < 0.001) { + transformation.set(0, 0, 1.0 - (Math.pow(robotDeltas.get(2, 0), 2) / 6.0)); + transformation.set(0, 1, -robotDeltas.get(2, 0) / 2.0); + transformation.set(1, 0, robotDeltas.get(2, 0) / 2.0); + transformation.set(1, 1, 1.0 - (Math.pow(robotDeltas.get(2, 0), 2) / 6.0)); + transformation.set(2, 2, 1.0); + } else { + transformation.set(0, 0, Math.sin(robotDeltas.get(2, 0)) / robotDeltas.get(2, 0)); + transformation.set(0, 1, (Math.cos(robotDeltas.get(2, 0)) - 1.0) / robotDeltas.get(2, 0)); + transformation.set(1, 0, (1.0 - Math.cos(robotDeltas.get(2, 0))) / robotDeltas.get(2, 0)); + transformation.set(1, 1, Math.sin(robotDeltas.get(2, 0)) / robotDeltas.get(2, 0)); + transformation.set(2, 2, 1.0); + } + + globalDeltas = Matrix.multiply(Matrix.multiply(prevRotationMatrix, transformation), robotDeltas); + + displacementPose.add(new Pose(globalDeltas.get(0, 0), globalDeltas.get(1, 0), globalDeltas.get(2, 0))); + currentVelocity = new Pose(globalDeltas.get(0, 0) / (deltaTimeNano * Math.pow(10.0, 9)), globalDeltas.get(1, 0) / (deltaTimeNano * Math.pow(10.0, 9)), globalDeltas.get(2, 0) / (deltaTimeNano * Math.pow(10.0, 9))); + + totalHeading += globalDeltas.get(2, 0); + } + + /** + * This updates the Encoders. + */ + public void updateEncoders() { + leftEncoder.update(); + rightEncoder.update(); + strafeEncoder.update(); + } + + /** + * This resets the Encoders. + */ + public void resetEncoders() { + leftEncoder.reset(); + rightEncoder.reset(); + strafeEncoder.reset(); + } + + /** + * This calculates the change in position from the perspective of the robot using information + * from the Encoders. + * + * @return returns a Matrix containing the robot relative movement. + */ + public Matrix getRobotDeltas() { + Matrix returnMatrix = new Matrix(3,1); + // x/forward movement + returnMatrix.set(0,0, FORWARD_TICKS_TO_INCHES * ((rightEncoder.getDeltaPosition() * leftEncoderPose.getY() - leftEncoder.getDeltaPosition() * rightEncoderPose.getY()) / (leftEncoderPose.getY() - rightEncoderPose.getY()))); + //y/strafe movement + returnMatrix.set(1,0, STRAFE_TICKS_TO_INCHES * (strafeEncoder.getDeltaPosition() - strafeEncoderPose.getX() * ((rightEncoder.getDeltaPosition() - leftEncoder.getDeltaPosition()) / (leftEncoderPose.getY() - rightEncoderPose.getY())))); + // theta/turning + returnMatrix.set(2,0, TURN_TICKS_TO_RADIANS * ((rightEncoder.getDeltaPosition() - leftEncoder.getDeltaPosition()) / (leftEncoderPose.getY() - rightEncoderPose.getY()))); + return returnMatrix; + } + + /** + * This returns how far the robot has turned in radians, in a number not clamped between 0 and + * 2 * pi radians. This is used for some tuning things and nothing actually within the following. + * + * @return returns how far the robot has turned in total, in radians. + */ + public double getTotalHeading() { + return totalHeading; + } + + /** + * This returns the multiplier applied to forward movement measurement to convert from encoder + * ticks to inches. This is found empirically through a tuner. + * + * @return returns the forward ticks to inches multiplier + */ + public double getForwardMultiplier() { + return FORWARD_TICKS_TO_INCHES; + } + + /** + * This returns the multiplier applied to lateral/strafe movement measurement to convert from + * encoder ticks to inches. This is found empirically through a tuner. + * + * @return returns the lateral/strafe ticks to inches multiplier + */ + public double getLateralMultiplier() { + return STRAFE_TICKS_TO_INCHES; + } + + /** + * This returns the multiplier applied to turning movement measurement to convert from encoder + * ticks to radians. This is found empirically through a tuner. + * + * @return returns the turning ticks to radians multiplier + */ + public double getTurningMultiplier() { + return TURN_TICKS_TO_RADIANS; + } + + /** + * This does nothing since this localizer does not use the IMU. + */ + public void resetIMU() { + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/TwoWheelLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/TwoWheelLocalizer.java new file mode 100644 index 0000000..62415d6 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/localizers/TwoWheelLocalizer.java @@ -0,0 +1,299 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization.localizers; + +import com.acmerobotics.dashboard.config.Config; +import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.HardwareMap; +import com.qualcomm.robotcore.hardware.IMU; + +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Encoder; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Localizer; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Matrix; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; +import org.firstinspires.ftc.teamcode.pedroPathing.util.NanoTimer; + +/** + * This is the TwoWheelLocalizer class. This class extends the Localizer superclass and is a + * localizer that uses the two wheel odometry with IMU set up. The diagram below, which is modified from + * Road Runner, shows a typical set up. + * + * The view is from the top of the robot looking downwards. + * + * left on robot is the y positive direction + * + * forward on robot is the x positive direction + * + * /--------------\ + * | ____ | + * | ---- | + * | || || | + * | || || | ----> left (y positive) + * | | + * | | + * \--------------/ + * | + * | + * V + * forward (x positive) + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 4/2/2024 + */ +@Config +public class TwoWheelLocalizer extends Localizer { // todo: make two wheel odo work + private HardwareMap hardwareMap; + private IMU imu; + private Pose startPose; + private Pose displacementPose; + private Pose currentVelocity; + private Matrix prevRotationMatrix; + private NanoTimer timer; + private long deltaTimeNano; + private Encoder forwardEncoder; + private Encoder strafeEncoder; + private Pose forwardEncoderPose; + private Pose strafeEncoderPose; + private double previousIMUOrientation; + private double deltaRadians; + private double totalHeading; + public static double FORWARD_TICKS_TO_INCHES = 8192 * 1.37795 * 2 * Math.PI * 0.5008239963; + public static double STRAFE_TICKS_TO_INCHES = 8192 * 1.37795 * 2 * Math.PI * 0.5018874659; + + /** + * This creates a new TwoWheelLocalizer from a HardwareMap, with a starting Pose at (0,0) + * facing 0 heading. + * + * @param map the HardwareMap + */ + public TwoWheelLocalizer(HardwareMap map) { + this(map, new Pose()); + } + + /** + * This creates a new TwoWheelLocalizer from a HardwareMap and a Pose, with the Pose + * specifying the starting pose of the localizer. + * + * @param map the HardwareMap + * @param setStartPose the Pose to start from + */ + public TwoWheelLocalizer(HardwareMap map, Pose setStartPose) { + // TODO: replace these with your encoder positions + forwardEncoderPose = new Pose(-18.5/25.4 - 0.1, 164.4/25.4, 0); + strafeEncoderPose = new Pose(-107.9/25.4+0.25, -1.1/25.4-0.23, Math.toRadians(90)); + + hardwareMap = map; + + imu = hardwareMap.get(IMU.class, "imu"); + // TODO: replace this with your IMU's orientation + imu.initialize(new IMU.Parameters(new RevHubOrientationOnRobot(RevHubOrientationOnRobot.LogoFacingDirection.UP, RevHubOrientationOnRobot.UsbFacingDirection.LEFT))); + + // TODO: replace these with your encoder ports + forwardEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, "leftRear")); + strafeEncoder = new Encoder(hardwareMap.get(DcMotorEx.class, "strafeEncoder")); + + // TODO: reverse any encoders necessary + forwardEncoder.setDirection(Encoder.REVERSE); + strafeEncoder.setDirection(Encoder.FORWARD); + + setStartPose(setStartPose); + timer = new NanoTimer(); + deltaTimeNano = 1; + displacementPose = new Pose(); + currentVelocity = new Pose(); + + previousIMUOrientation = MathFunctions.normalizeAngle(imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS)); + deltaRadians = 0; + } + + /** + * This returns the current pose estimate. + * + * @return returns the current pose estimate as a Pose + */ + @Override + public Pose getPose() { + return MathFunctions.addPoses(startPose, displacementPose); + } + + /** + * This returns the current velocity estimate. + * + * @return returns the current velocity estimate as a Pose + */ + @Override + public Pose getVelocity() { + return currentVelocity.copy(); + } + + /** + * This returns the current velocity estimate. + * + * @return returns the current velocity estimate as a Vector + */ + @Override + public Vector getVelocityVector() { + return currentVelocity.getVector(); + } + + /** + * This sets the start pose. Changing the start pose should move the robot as if all its + * previous movements were displacing it from its new start pose. + * + * @param setStart the new start pose + */ + @Override + public void setStartPose(Pose setStart) { + startPose = setStart; + } + + /** + * This sets the Matrix that contains the previous pose's heading rotation. + * + * @param heading the rotation of the Matrix + */ + public void setPrevRotationMatrix(double heading) { + prevRotationMatrix = new Matrix(3,3); + prevRotationMatrix.set(0, 0, Math.cos(heading)); + prevRotationMatrix.set(0, 1, -Math.sin(heading)); + prevRotationMatrix.set(1, 0, Math.sin(heading)); + prevRotationMatrix.set(1, 1, Math.cos(heading)); + prevRotationMatrix.set(2, 2, 1.0); + } + + /** + * This sets the current pose estimate. Changing this should just change the robot's current + * pose estimate, not anything to do with the start pose. + * + * @param setPose the new current pose estimate + */ + @Override + public void setPose(Pose setPose) { + displacementPose = MathFunctions.subtractPoses(setPose, startPose); + resetEncoders(); + } + + /** + * This updates the elapsed time timer that keeps track of time between updates, as well as the + * change position of the Encoders and the IMU readings. Then, the robot's global change in + * position is calculated using the pose exponential method. + */ + @Override + public void update() { + deltaTimeNano = timer.getElapsedTime(); + timer.resetTimer(); + + updateEncoders(); + Matrix robotDeltas = getRobotDeltas(); + Matrix globalDeltas; + setPrevRotationMatrix(getPose().getHeading()); + + Matrix transformation = new Matrix(3,3); + if (Math.abs(robotDeltas.get(2, 0)) < 0.001) { + transformation.set(0, 0, 1.0 - (Math.pow(robotDeltas.get(2, 0), 2) / 6.0)); + transformation.set(0, 1, -robotDeltas.get(2, 0) / 2.0); + transformation.set(1, 0, robotDeltas.get(2, 0) / 2.0); + transformation.set(1, 1, 1.0 - (Math.pow(robotDeltas.get(2, 0), 2) / 6.0)); + transformation.set(2, 2, 1.0); + } else { + transformation.set(0, 0, Math.sin(robotDeltas.get(2, 0)) / robotDeltas.get(2, 0)); + transformation.set(0, 1, (Math.cos(robotDeltas.get(2, 0)) - 1.0) / robotDeltas.get(2, 0)); + transformation.set(1, 0, (1.0 - Math.cos(robotDeltas.get(2, 0))) / robotDeltas.get(2, 0)); + transformation.set(1, 1, Math.sin(robotDeltas.get(2, 0)) / robotDeltas.get(2, 0)); + transformation.set(2, 2, 1.0); + } + + globalDeltas = Matrix.multiply(Matrix.multiply(prevRotationMatrix, transformation), robotDeltas); + + displacementPose.add(new Pose(globalDeltas.get(0, 0), globalDeltas.get(1, 0), globalDeltas.get(2, 0))); + currentVelocity = new Pose(globalDeltas.get(0, 0) / (deltaTimeNano * Math.pow(10.0, 9)), globalDeltas.get(1, 0) / (deltaTimeNano * Math.pow(10.0, 9)), globalDeltas.get(2, 0) / (deltaTimeNano * Math.pow(10.0, 9))); + + totalHeading += globalDeltas.get(2, 0); + } + + /** + * This updates the Encoders as well as the IMU. + */ + public void updateEncoders() { + forwardEncoder.update(); + strafeEncoder.update(); + + double currentIMUOrientation = MathFunctions.normalizeAngle(imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS)); + deltaRadians = MathFunctions.getTurnDirection(previousIMUOrientation, currentIMUOrientation) * MathFunctions.getSmallestAngleDifference(currentIMUOrientation, previousIMUOrientation); + previousIMUOrientation = currentIMUOrientation; + } + + /** + * This resets the Encoders. + */ + public void resetEncoders() { + forwardEncoder.reset(); + strafeEncoder.reset(); + } + + /** + * This calculates the change in position from the perspective of the robot using information + * from the Encoders and IMU. + * + * @return returns a Matrix containing the robot relative movement. + */ + public Matrix getRobotDeltas() { + Matrix returnMatrix = new Matrix(3,1); + // x/forward movement + returnMatrix.set(0,0, FORWARD_TICKS_TO_INCHES * (forwardEncoder.getDeltaPosition() - forwardEncoderPose.getY() * deltaRadians)); + //y/strafe movement + returnMatrix.set(1,0, STRAFE_TICKS_TO_INCHES * (strafeEncoder.getDeltaPosition() - strafeEncoderPose.getX() * deltaRadians)); + // theta/turning + returnMatrix.set(2,0, deltaRadians); + return returnMatrix; + } + + /** + * This returns how far the robot has turned in radians, in a number not clamped between 0 and + * 2 * pi radians. This is used for some tuning things and nothing actually within the following. + * + * @return returns how far the robot has turned in total, in radians. + */ + public double getTotalHeading() { + return totalHeading; + } + + /** + * This returns the multiplier applied to forward movement measurement to convert from encoder + * ticks to inches. This is found empirically through a tuner. + * + * @return returns the forward ticks to inches multiplier + */ + public double getForwardMultiplier() { + return FORWARD_TICKS_TO_INCHES; + } + + /** + * This returns the multiplier applied to lateral/strafe movement measurement to convert from + * encoder ticks to inches. This is found empirically through a tuner. + * + * @return returns the lateral/strafe ticks to inches multiplier + */ + public double getLateralMultiplier() { + return STRAFE_TICKS_TO_INCHES; + } + + /** + * This returns the multiplier applied to turning movement measurement to convert from encoder + * ticks to radians. This is found empirically through a tuner. + * + * @return returns the turning ticks to radians multiplier + */ + public double getTurningMultiplier() { + return 1; + } + + /** + * This resets the IMU. + */ + public void resetIMU() { + imu.resetYaw(); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/FowardTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/FowardTuner.java new file mode 100644 index 0000000..ff59830 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/FowardTuner.java @@ -0,0 +1,72 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization.tuning; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.acmerobotics.dashboard.telemetry.TelemetryPacket; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.PoseUpdater; +import org.firstinspires.ftc.teamcode.pedroPathing.util.DashboardPoseTracker; +import org.firstinspires.ftc.teamcode.pedroPathing.util.Drawing; + +/** + * This is the ForwardTuner OpMode. This tracks the forward movement of the robot and displays the + * necessary ticks to inches multiplier. This displayed multiplier is what's necessary to scale the + * robot's current distance in ticks to the specified distance in inches. So, to use this, run the + * tuner, then pull/push the robot to the specified distance using a ruler on the ground. When you're + * at the end of the distance, record the ticks to inches multiplier. Feel free to run multiple trials + * and average the results. Then, input the multiplier into the forward ticks to inches in your + * localizer of choice. + * You can adjust the target distance on FTC Dashboard: 192/168/43/1:8080/dash + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 5/6/2024 + */ +@Config +@Autonomous(name = "Forward Localizer Tuner", group = "Autonomous Pathing Tuning") +public class FowardTuner extends OpMode { + private PoseUpdater poseUpdater; + private DashboardPoseTracker dashboardPoseTracker; + + private Telemetry telemetryA; + + public static double DISTANCE = 30; + + /** + * This initializes the PoseUpdater as well as the FTC Dashboard telemetry. + */ + @Override + public void init() { + poseUpdater = new PoseUpdater(hardwareMap); + + dashboardPoseTracker = new DashboardPoseTracker(poseUpdater); + + telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); + telemetryA.addLine("Pull your robot forward " + DISTANCE + " inches. Your forward ticks to inches will be shown on the telemetry."); + telemetryA.update(); + + Drawing.drawRobot(poseUpdater.getPose(), "#4CAF50"); + Drawing.sendPacket(); + } + + /** + * This updates the robot's pose estimate, and updates the FTC Dashboard telemetry with the + * calculated multiplier and draws the robot. + */ + @Override + public void loop() { + poseUpdater.update(); + + telemetryA.addData("distance moved", poseUpdater.getPose().getX()); + telemetryA.addLine("The multiplier will display what your forward ticks to inches should be to scale your current distance to " + DISTANCE + " inches."); + telemetryA.addData("multiplier", DISTANCE / (poseUpdater.getPose().getX() / poseUpdater.getLocalizer().getForwardMultiplier())); + telemetryA.update(); + + Drawing.drawPoseHistory(dashboardPoseTracker, "#4CAF50"); + Drawing.drawRobot(poseUpdater.getPose(), "#4CAF50"); + Drawing.sendPacket(); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/LateralTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/LateralTuner.java new file mode 100644 index 0000000..f3d42f3 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/LateralTuner.java @@ -0,0 +1,72 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization.tuning; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.acmerobotics.dashboard.telemetry.TelemetryPacket; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.PoseUpdater; +import org.firstinspires.ftc.teamcode.pedroPathing.util.DashboardPoseTracker; +import org.firstinspires.ftc.teamcode.pedroPathing.util.Drawing; + +/** + * This is the LateralTuner OpMode. This tracks the strafe movement of the robot and displays the + * necessary ticks to inches multiplier. This displayed multiplier is what's necessary to scale the + * robot's current distance in ticks to the specified distance in inches. So, to use this, run the + * tuner, then pull/push the robot to the specified distance using a ruler on the ground. When you're + * at the end of the distance, record the ticks to inches multiplier. Feel free to run multiple trials + * and average the results. Then, input the multiplier into the strafe ticks to inches in your + * localizer of choice. + * You can adjust the target distance on FTC Dashboard: 192/168/43/1:8080/dash + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 5/6/2024 + */ +@Config +@Autonomous(name = "Lateral Localizer Tuner", group = "Autonomous Pathing Tuning") +public class LateralTuner extends OpMode { + private PoseUpdater poseUpdater; + private DashboardPoseTracker dashboardPoseTracker; + + private Telemetry telemetryA; + + public static double DISTANCE = 30; + + /** + * This initializes the PoseUpdater as well as the FTC Dashboard telemetry. + */ + @Override + public void init() { + poseUpdater = new PoseUpdater(hardwareMap); + + dashboardPoseTracker = new DashboardPoseTracker(poseUpdater); + + telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); + telemetryA.addLine("Pull your robot to the right " + DISTANCE + " inches. Your strafe ticks to inches will be shown on the telemetry."); + telemetryA.update(); + + Drawing.drawRobot(poseUpdater.getPose(), "#4CAF50"); + Drawing.sendPacket(); + } + + /** + * This updates the robot's pose estimate, and updates the FTC Dashboard telemetry with the + * calculated multiplier and draws the robot. + */ + @Override + public void loop() { + poseUpdater.update(); + + telemetryA.addData("distance moved", poseUpdater.getPose().getY()); + telemetryA.addLine("The multiplier will display what your strafe ticks to inches should be to scale your current distance to " + DISTANCE + " inches."); + telemetryA.addData("multiplier", DISTANCE / (poseUpdater.getPose().getY() / poseUpdater.getLocalizer().getLateralMultiplier())); + telemetryA.update(); + + Drawing.drawPoseHistory(dashboardPoseTracker, "#4CAF50"); + Drawing.drawRobot(poseUpdater.getPose(), "#4CAF50"); + Drawing.sendPacket(); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/LocalizationTest.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/LocalizationTest.java new file mode 100644 index 0000000..32e0452 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/LocalizationTest.java @@ -0,0 +1,122 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization.tuning; + +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.PoseUpdater; +import org.firstinspires.ftc.teamcode.pedroPathing.util.DashboardPoseTracker; +import org.firstinspires.ftc.teamcode.pedroPathing.util.Drawing; + +import java.util.Arrays; +import java.util.List; + +/** + * This is the LocalizationTest OpMode. This is basically just a simple mecanum drive attached to a + * PoseUpdater. The OpMode will print out the robot's pose to telemetry as well as draw the robot + * on FTC Dashboard (192/168/43/1:8080/dash). You should use this to check the robot's localization. + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 5/6/2024 + */ +@Config +@TeleOp(group = "Pedro Pathing Tuning", name = "Localization Test") +public class LocalizationTest extends OpMode { + private PoseUpdater poseUpdater; + private DashboardPoseTracker dashboardPoseTracker; + private Telemetry telemetryA; + + private DcMotorEx leftFront; + private DcMotorEx leftRear; + private DcMotorEx rightFront; + private DcMotorEx rightRear; + private List motors; + + /** + * This initializes the PoseUpdater, the mecanum drive motors, and the FTC Dashboard telemetry. + */ + @Override + public void init() { + poseUpdater = new PoseUpdater(hardwareMap); + + dashboardPoseTracker = new DashboardPoseTracker(poseUpdater); + + leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName); + leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName); + rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName); + rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName); + + leftFront.setDirection(DcMotorSimple.Direction.REVERSE); + leftRear.setDirection(DcMotorSimple.Direction.REVERSE); + + motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear); + + for (DcMotorEx motor : motors) { + MotorConfigurationType motorConfigurationType = motor.getMotorType().clone(); + motorConfigurationType.setAchieveableMaxRPMFraction(1.0); + motor.setMotorType(motorConfigurationType); + } + + for (DcMotorEx motor : motors) { + motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); + } + + telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); + telemetryA.addLine("This will print your robot's position to telemetry while " + + "allowing robot control through a basic mecanum drive on gamepad 1."); + telemetryA.update(); + + Drawing.drawRobot(poseUpdater.getPose(), "#4CAF50"); + Drawing.sendPacket(); + } + + /** + * This updates the robot's pose estimate, the simple mecanum drive, and updates the FTC + * Dashboard telemetry with the robot's position as well as draws the robot's position. + */ + @Override + public void loop() { + poseUpdater.update(); + dashboardPoseTracker.update(); + + double y = -gamepad1.left_stick_y; // Remember, this is reversed! + double x = gamepad1.left_stick_x; // this is strafing + double rx = gamepad1.right_stick_x; + + // Denominator is the largest motor power (absolute value) or 1 + // This ensures all the powers maintain the same ratio, but only when + // at least one is out of the range [-1, 1] + double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1); + double leftFrontPower = (y + x + rx) / denominator; + double leftRearPower = (y - x + rx) / denominator; + double rightFrontPower = (y - x - rx) / denominator; + double rightRearPower = (y + x - rx) / denominator; + + leftFront.setPower(leftFrontPower); + leftRear.setPower(leftRearPower); + rightFront.setPower(rightFrontPower); + rightRear.setPower(rightRearPower); + + telemetryA.addData("x", poseUpdater.getPose().getX()); + telemetryA.addData("y", poseUpdater.getPose().getY()); + telemetryA.addData("heading", poseUpdater.getPose().getHeading()); + telemetryA.addData("total heading", poseUpdater.getTotalHeading()); + telemetryA.update(); + + Drawing.drawPoseHistory(dashboardPoseTracker, "#4CAF50"); + Drawing.drawRobot(poseUpdater.getPose(), "#4CAF50"); + Drawing.sendPacket(); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/TurnTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/TurnTuner.java new file mode 100644 index 0000000..1693990 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/localization/tuning/TurnTuner.java @@ -0,0 +1,71 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.localization.tuning; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.acmerobotics.dashboard.telemetry.TelemetryPacket; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.PoseUpdater; +import org.firstinspires.ftc.teamcode.pedroPathing.util.DashboardPoseTracker; +import org.firstinspires.ftc.teamcode.pedroPathing.util.Drawing; + +/** + * This is the TurnTuner OpMode. This tracks the turning movement of the robot and displays the + * necessary ticks to inches multiplier. This displayed multiplier is what's necessary to scale the + * robot's current angle in ticks to the specified angle in radians. So, to use this, run the + * tuner, then pull/push the robot to the specified angle using a protractor or lines on the ground. + * When you're at the end of the angle, record the ticks to inches multiplier. Feel free to run + * multiple trials and average the results. Then, input the multiplier into the turning ticks to + * radians in your localizer of choice. + * You can adjust the target angle on FTC Dashboard: 192/168/43/1:8080/dash + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 5/6/2024 + */ +@Config +@Autonomous(name = "Turn Localizer Tuner", group = "Autonomous Pathing Tuning") +public class TurnTuner extends OpMode { + private PoseUpdater poseUpdater; + private DashboardPoseTracker dashboardPoseTracker; + + private Telemetry telemetryA; + + public static double ANGLE = 2 * Math.PI; + + /** + * This initializes the PoseUpdater as well as the FTC Dashboard telemetry. + */ + @Override + public void init() { + poseUpdater = new PoseUpdater(hardwareMap); + + dashboardPoseTracker = new DashboardPoseTracker(poseUpdater); + + telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); + telemetryA.addLine("Turn your robot " + ANGLE + " radians. Your turn ticks to inches will be shown on the telemetry."); + telemetryA.update(); + + Drawing.drawRobot(poseUpdater.getPose(), "#4CAF50"); + Drawing.sendPacket(); + } + + /** + * This updates the robot's pose estimate, and updates the FTC Dashboard telemetry with the + * calculated multiplier and draws the robot. + */ + @Override + public void loop() { + poseUpdater.update(); + + telemetryA.addData("total angle", poseUpdater.getTotalHeading()); + telemetryA.addLine("The multiplier will display what your turn ticks to inches should be to scale your current angle to " + ANGLE + " radians."); + telemetryA.addData("multiplier", ANGLE / (poseUpdater.getTotalHeading() / poseUpdater.getLocalizer().getTurningMultiplier())); + + Drawing.drawPoseHistory(dashboardPoseTracker, "#4CAF50"); + Drawing.drawRobot(poseUpdater.getPose(), "#4CAF50"); + Drawing.sendPacket(); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierCurve.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierCurve.java new file mode 100644 index 0000000..f5bb12a --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierCurve.java @@ -0,0 +1,348 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration; + + +import org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants; + +import java.util.ArrayList; +import java.util.Arrays; + +/** + * This is the BezierCurve class. This class handles the creation of Bezier curves, which are used + * as the basis of the path for the Path class. Bezier curves are parametric curves defined by a set + * of control points. So, they take in one input, t, that ranges from [0, 1] and that returns a point + * on the curve. Essentially, Bezier curves are a way of defining a parametric line easily. You can + * read more on Bezier curves here: https://en.wikipedia.org/wiki/Bézier_curve + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/5/2024 + */ +public class BezierCurve { + // This contains the coefficients for the curve points + private ArrayList pointCoefficients = new ArrayList<>(); + + // This contains the control points for the Bezier curve + private ArrayList controlPoints = new ArrayList<>(); + + private Vector endTangent = new Vector(); + + private final int APPROXIMATION_STEPS = FollowerConstants.APPROXIMATION_STEPS; + + private final int DASHBOARD_DRAWING_APPROXIMATION_STEPS = 100; + + private double[][] dashboardDrawingPoints; + + private double UNIT_TO_TIME; + private double length; + + /** + * This creates an empty BezierCurve. + * IMPORTANT NOTE: Only use this for the constructors of classes extending this. If you try to + * run the robot on a Path containing an empty BezierCurve, then it will explode. + */ + public BezierCurve() { + } + + /** + * This creates a new BezierCurve with an ArrayList of control points and generates the curve. + * IMPORTANT NOTE: The order of the control points is important. That's the order the code will + * process them in, with the 0 index being the start point and the final index being the end point + * + * @param controlPoints This is the ArrayList of control points that define the BezierCurve. + */ + public BezierCurve(ArrayList controlPoints) { + if (controlPoints.size()<3) { + try { + throw new Exception("Too few control points"); + } catch (Exception e) { + e.printStackTrace(); + } + } + this.controlPoints = controlPoints; + initialize(); + } + + /** + * This creates a new Bezier curve with some specified control points and generates the curve. + * IMPORTANT NOTE: The order of the control points is important. That's the order the code will + * process them in, with the 0 index being the start point and the final index being the end point. + * + * @param controlPoints This is the specified control points that define the BezierCurve. + */ + public BezierCurve(Point... controlPoints) { + for (Point controlPoint : controlPoints) { + this.controlPoints.add(controlPoint); + } + if (this.controlPoints.size()<3) { + try { + throw new Exception("Too few control points"); + } catch (Exception e) { + e.printStackTrace(); + } + } + initialize(); + } + + /** + * This handles most of the initialization of the BezierCurve that is called from the constructor. + */ + public void initialize() { + generateBezierCurve(); + length = approximateLength(); + UNIT_TO_TIME = 1/length; + endTangent.setOrthogonalComponents(controlPoints.get(controlPoints.size()-1).getX()-controlPoints.get(controlPoints.size()-2).getX(), controlPoints.get(controlPoints.size()-1).getY()-controlPoints.get(controlPoints.size()-2).getY()); + endTangent = MathFunctions.normalizeVector(endTangent); + initializeDashboardDrawingPoints(); + } + + /** + * This creates the Array that holds the Points to draw on the Dashboard. + */ + public void initializeDashboardDrawingPoints() { + dashboardDrawingPoints = new double[2][DASHBOARD_DRAWING_APPROXIMATION_STEPS + 1]; + for (int i = 0; i <= DASHBOARD_DRAWING_APPROXIMATION_STEPS; i++) { + Point currentPoint = getPoint(i/(double) (DASHBOARD_DRAWING_APPROXIMATION_STEPS)); + dashboardDrawingPoints[0][i] = currentPoint.getX(); + dashboardDrawingPoints[1][i] = currentPoint.getY(); + } + } + + /** + * This returns a 2D Array of doubles containing the x and y positions of points to draw on FTC + * Dashboard. + * + * @return returns the 2D Array to draw on FTC Dashboard + */ + public double[][] getDashboardDrawingPoints() { + return dashboardDrawingPoints; + } + + /** + * This generates the Bezier curve. It assumes that the ArrayList of control points has been set. + * Well, this actually generates the coefficients for each control point on the Bezier curve. + * These coefficients can then be used to calculate a position, velocity, or accleration on the + * Bezier curve on the fly without much computational expense. + * + * See https://en.wikipedia.org/wiki/Bézier_curve for the explicit formula for Bezier curves + */ + public void generateBezierCurve() { + int n = controlPoints.size()-1; + for (int i = 0; i <= n; i++) { + pointCoefficients.add(new BezierCurveCoefficients(n, i)); + } + } + + /** + * This returns the unit tangent Vector at the end of the BezierCurve. + * + * @return returns the end tangent Vector. + */ + public Vector getEndTangent() { + return MathFunctions.copyVector(endTangent); + } + + /** + * This approximates the length of the BezierCurve in APPROXIMATION_STEPS number of steps. It's + * like a Riemann's sum, but for a parametric function's arc length. + * + * @return returns the approximated length of the BezierCurve. + */ + public double approximateLength() { + Point previousPoint = getPoint(0); + Point currentPoint; + double approxLength = 0; + for (int i = 1; i <= APPROXIMATION_STEPS; i++) { + currentPoint = getPoint(i/(double)APPROXIMATION_STEPS); + approxLength += previousPoint.distanceFrom(currentPoint); + previousPoint = currentPoint; + } + return approxLength; + } + + /** + * This returns the point on the Bezier curve that is specified by the parametric t value. A + * Bezier curve is a parametric function that returns points along it with t ranging from [0, 1], + * with 0 being the beginning of the curve and 1 being at the end. The Follower will follow + * BezierCurves from 0 to 1, in terms of t. + * + * @param t this is the t value of the parametric curve. t is clamped to be between 0 and 1 inclusive. + * @return this returns the point requested. + */ + public Point getPoint(double t) { + t = MathFunctions.clamp(t, 0, 1); + double xCoordinate = 0; + double yCoordinate = 0; + + // calculates the x coordinate of the point requested + for (int i = 0; i < controlPoints.size(); i++) { + xCoordinate += pointCoefficients.get(i).getValue(t) * controlPoints.get(i).getX(); + } + + // calculates the y coordinate of the point requested + for (int i = 0; i < controlPoints.size(); i++) { + yCoordinate += pointCoefficients.get(i).getValue(t) * controlPoints.get(i).getY(); + } + return new Point(xCoordinate, yCoordinate, Point.CARTESIAN); + } + + /** + * This returns the curvature of the Bezier curve at a specified t-value. + * + * @param t the parametric t input. + * @return returns the curvature. + */ + public double getCurvature(double t) { + t = MathFunctions.clamp(t, 0, 1); + Vector derivative = getDerivative(t); + Vector secondDerivative = getSecondDerivative(t); + + if (derivative.getMagnitude() == 0) return 0; + return (MathFunctions.crossProduct(derivative, secondDerivative))/Math.pow(derivative.getMagnitude(),3); + } + + /** + * This returns the derivative on the BezierCurve that is specified by the parametric t value. + * This is returned as a Vector, and this Vector is the tangent to the BezierCurve. + * + * @param t this is the t value of the parametric curve. t is clamped to be between 0 and 1 inclusive. + * @return this returns the derivative requested. + */ + public Vector getDerivative(double t) { + t = MathFunctions.clamp(t, 0, 1); + double xCoordinate = 0; + double yCoordinate = 0; + Vector returnVector = new Vector(); + + // calculates the x coordinate of the point requested + for (int i = 0; i < controlPoints.size()-1; i++) { + xCoordinate += pointCoefficients.get(i).getDerivativeValue(t) * (MathFunctions.subtractPoints(controlPoints.get(i+1), controlPoints.get(i)).getX()); + } + + // calculates the y coordinate of the point requested + for (int i = 0; i < controlPoints.size()-1; i++) {; + yCoordinate += pointCoefficients.get(i).getDerivativeValue(t) * (MathFunctions.subtractPoints(controlPoints.get(i+1), controlPoints.get(i)).getY()); + } + + returnVector.setOrthogonalComponents(xCoordinate, yCoordinate); + + return returnVector; + } + + /** + * This returns the second derivative on the BezierCurve that is specified by the parametric t value. + * This is returned as a Vector, and this Vector is the acceleration on the BezierCurve. + * + * @param t this is the t value of the parametric curve. t is clamped to be between 0 and 1 inclusive. + * @return this returns the second derivative requested. + */ + public Vector getSecondDerivative(double t) { + t = MathFunctions.clamp(t, 0, 1); + double xCoordinate = 0; + double yCoordinate = 0; + Vector returnVector = new Vector(); + + // calculates the x coordinate of the point requested + for (int i = 0; i < controlPoints.size()-2; i++) { + xCoordinate += pointCoefficients.get(i).getSecondDerivativeValue(t) * (MathFunctions.addPoints(MathFunctions.subtractPoints(controlPoints.get(i+2), new Point(2*controlPoints.get(i+1).getX(), 2*controlPoints.get(i+1).getY(), Point.CARTESIAN)), controlPoints.get(i)).getX()); + } + + // calculates the y coordinate of the point requested + for (int i = 0; i < controlPoints.size()-2; i++) { + yCoordinate += pointCoefficients.get(i).getSecondDerivativeValue(t) * (MathFunctions.addPoints(MathFunctions.subtractPoints(controlPoints.get(i+2), new Point(2*controlPoints.get(i+1).getX(), 2*controlPoints.get(i+1).getY(), Point.CARTESIAN)), controlPoints.get(i)).getY()); + } + + returnVector.setOrthogonalComponents(xCoordinate, yCoordinate); + + return returnVector; + } + + /** + * Because, for whatever reason, the second derivative returned by the getSecondDerivative(double t) + * method doesn't return the correct heading of the second derivative, this gets an approximate + * second derivative essentially using the limit method. I use this for its heading only. + * + * @param t this is the t value of the parametric curve. t is clamped to be between 0 and 1 inclusive. + * @return this returns the approximated second derivative. + */ + public Vector getApproxSecondDerivative(double t) { + double current = getDerivative(t).getTheta(); + double deltaCurrent = getDerivative(t + 0.0001).getTheta(); + + return new Vector(1, deltaCurrent - current); + } + + /** + * Returns the ArrayList of control points for this BezierCurve. + * + * @return This returns the control points. + */ + public ArrayList getControlPoints() { + return controlPoints; + } + + /** + * Returns the first control point for this BezierCurve. + * + * @return This returns the Point. + */ + public Point getFirstControlPoint() { + return controlPoints.get(0); + } + + /** + * Returns the second control point, or the one after the start, for this BezierCurve. + * + * @return This returns the Point. + */ + public Point getSecondControlPoint() { + return controlPoints.get(1); + } + + /** + * Returns the second to last control point for this BezierCurve. + * + * @return This returns the Point. + */ + public Point getSecondToLastControlPoint() { + return controlPoints.get(controlPoints.size()-2); + } + + /** + * Returns the last control point for this BezierCurve. + * + * @return This returns the Point. + */ + public Point getLastControlPoint() { + return controlPoints.get(controlPoints.size()-1); + } + + /** + * Returns the approximate length of this BezierCurve. + * + * @return This returns the length. + */ + public double length() { + return length; + } + + /** + * Returns the conversion factor of one unit of distance into t-value. Since parametric functions + * are defined by t, which can mean time, I use "time" in some method names for conciseness. + * + * @return returns the conversion factor. + */ + public double UNIT_TO_TIME() { + return UNIT_TO_TIME; + } + + /** + * Returns the type of path. This is used in case we need to identify the type of BezierCurve + * this is. + * + * @return returns the type of path. + */ + public String pathType() { + return "curve"; + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierCurveCoefficients.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierCurveCoefficients.java new file mode 100644 index 0000000..f8fc51d --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierCurveCoefficients.java @@ -0,0 +1,66 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration; + +/** + * This is the BezierCurveCoefficients class. This class handles holding the coefficients for each + * control point for the BezierCurve class to allow for faster on the fly calculations of points, + * derivatives, and second derivatives on Bezier curves. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/8/2024 + */ +public class BezierCurveCoefficients { + private double coefficient; + private double derivativeCoefficient; + private double secondDerivativeCoefficient; + + private int n; + private int i; + + /** + * This creates the coefficients within the summation equations for calculating positions, + * derivatives, and second derivatives on Bezier curves. + * + * @param n this is the degree of the Bezier curve function. + * @param i this is the i within the summation equation, so basically which place it is in the + * summation. + */ + public BezierCurveCoefficients(int n, int i) { + this.n = n; + this.i = i; + coefficient = MathFunctions.nCr(n, i); + derivativeCoefficient = MathFunctions.nCr(n - 1, i); + secondDerivativeCoefficient = MathFunctions.nCr(n - 2, i); + } + + /** + * This returns the coefficient for the summation to calculate a position on BezierCurves. + * + * @param t this is the t value within the parametric equation for the Bezier curve. + * @return this returns the coefficient. + */ + public double getValue(double t) { + return coefficient * Math.pow(1 - t, n - i) * Math.pow(t, i); + } + + /** + * This returns the coefficient for the summation to calculate a derivative on BezierCurves. + * + * @param t this is the t value within the parametric equation for the Bezier curve. + * @return this returns the coefficient. + */ + public double getDerivativeValue(double t) { + return n * derivativeCoefficient * Math.pow(t, i) * Math.pow(1 - t, n - i - 1); + } + + /** + * This returns the coefficient for the summation to calculate a second derivative on BezierCurves. + * + * @param t this is the t value within the parametric equation for the Bezier curve. + * @return this returns the coefficient. + */ + public double getSecondDerivativeValue(double t) { + return n * (n - 1) * secondDerivativeCoefficient * Math.pow(t, i) * Math.pow(1 - t, n - i - 2); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierLine.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierLine.java new file mode 100644 index 0000000..04c7979 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierLine.java @@ -0,0 +1,209 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration; + +import java.util.ArrayList; + +/** + * This is the BezierLine class. This class handles the creation of BezierLines, which is what I + * call Bezier curves with only two control points. The parent BezierCurve class cannot handle Bezier + * curves with less than three control points, so this class handles lines. Additionally, it makes + * the calculations done on the fly a little less computationally expensive and more streamlined. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/9/2024 + */ +public class BezierLine extends BezierCurve { + + private Point startPoint; + private Point endPoint; + + private Vector endTangent; + + private double UNIT_TO_TIME; + private double length; + + /** + * This creates a new BezierLine with specified start and end Points. + * This is just a line but it extends the BezierCurve class so things work. + * + * @param startPoint start point of the line. + * @param endPoint end point of the line. + */ + public BezierLine(Point startPoint, Point endPoint) { + super(); + this.startPoint = startPoint; + this.endPoint = endPoint; + length = approximateLength(); + UNIT_TO_TIME = 1 / length; + endTangent = MathFunctions.normalizeVector(getDerivative(1)); + super.initializeDashboardDrawingPoints(); + } + + /** + * This returns the unit tangent Vector at the end of the BezierLine. + * + * @return returns the tangent Vector. + */ + @Override + public Vector getEndTangent() { + return MathFunctions.copyVector(endTangent); + } + + /** + * This gets the length of the BezierLine. + * + * @return returns the length of the BezierLine. + */ + @Override + public double approximateLength() { + return Math.sqrt(Math.pow(startPoint.getX() - endPoint.getX(), 2) + Math.pow(startPoint.getY() - endPoint.getY(), 2)); + } + + /** + * This returns the Point on the Bezier line that is specified by the parametric t value. + * + * @param t this is the t value of the parametric line. t is clamped to be between 0 and 1 inclusive. + * @return this returns the Point requested. + */ + @Override + public Point getPoint(double t) { + t = MathFunctions.clamp(t, 0, 1); + return new Point((endPoint.getX() - startPoint.getX()) * t + startPoint.getX(), (endPoint.getY() - startPoint.getY()) * t + startPoint.getY(), Point.CARTESIAN); + } + + /** + * This returns the curvature of the BezierLine, which is zero. + * + * @param t the parametric t value. + * @return returns the curvature. + */ + @Override + public double getCurvature(double t) { + return 0.0; + } + + /** + * This returns the derivative on the BezierLine as a Vector, which is a constant slope. + * The t value doesn't really do anything, but it's there so I can override methods. + * + * @param t this is the t value of the parametric curve. t is clamped to be between 0 and 1 inclusive. + * @return this returns the derivative requested. + */ + @Override + public Vector getDerivative(double t) { + Vector returnVector = new Vector(); + + returnVector.setOrthogonalComponents(endPoint.getX() - startPoint.getX(), endPoint.getY() - startPoint.getY()); + + return returnVector; + } + + /** + * This returns the second derivative on the Bezier line, which is a zero Vector. + * Once again, the t is only there for the override. + * + * @param t this is the t value of the parametric curve. t is clamped to be between 0 and 1 inclusive. + * @return this returns the second derivative requested. + */ + @Override + public Vector getSecondDerivative(double t) { + return new Vector(); + } + + /** + * This returns the zero Vector, but it's here so I can override the method in the BezierCurve + * class. + * + * @param t this is the t value of the parametric curve. t is clamped to be between 0 and 1 inclusive. + * @return this returns the approximated second derivative, which is the zero Vector. + */ + @Override + public Vector getApproxSecondDerivative(double t) { + return new Vector(); + } + + /** + * Returns the ArrayList of control points for this BezierLine. + * + * @return This returns the control points. + */ + @Override + public ArrayList getControlPoints() { + ArrayList returnList = new ArrayList<>(); + returnList.add(startPoint); + returnList.add(endPoint); + return returnList; + } + + /** + * Returns the first control point for this BezierLine. + * + * @return This returns the Point. + */ + @Override + public Point getFirstControlPoint() { + return startPoint; + } + + /** + * Returns the second control point, or the one after the start, for this BezierLine. + * + * @return This returns the Point. + */ + @Override + public Point getSecondControlPoint() { + return endPoint; + } + + /** + * Returns the second to last control point for this BezierLine. + * + * @return This returns the Point. + */ + @Override + public Point getSecondToLastControlPoint() { + return startPoint; + } + + /** + * Returns the last control point for this BezierLine. + * + * @return This returns the Point. + */ + @Override + public Point getLastControlPoint() { + return endPoint; + } + + /** + * Returns the length of this BezierLine. + * + * @return This returns the length. + */ + @Override + public double length() { + return length; + } + + /** + * Returns the conversion factor of one unit of distance into t value. + * + * @return returns the conversion factor. + */ + @Override + public double UNIT_TO_TIME() { + return UNIT_TO_TIME; + } + + /** + * Returns the type of path. This is used in case we need to identify the type of BezierCurve + * this is. + * + * @return returns the type of path. + */ + @Override + public String pathType() { + return "line"; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierPoint.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierPoint.java new file mode 100644 index 0000000..cd2382e --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/BezierPoint.java @@ -0,0 +1,209 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration; + +import java.util.ArrayList; + +/** + * This is the BezierPoint class. This class handles the creation of BezierPoints, which is what I + * call Bezier curves with only one control point. The parent BezierCurve class cannot handle Bezier + * curves with less than three control points, so this class handles points. Additionally, it makes + * the calculations done on the fly a little less computationally expensive and more streamlined. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/9/2024 + */ +public class BezierPoint extends BezierCurve { + + private Point point; + + private Vector endTangent = new Vector(); + + private double UNIT_TO_TIME; + private double length; + + /** + * This creates a new BezierPoint with a specified Point. + * This is just a point but it extends the BezierCurve class so things work. + * + * @param point the specified point. + */ + public BezierPoint(Point point) { + super(); + this.point = point; + length = approximateLength(); + super.initializeDashboardDrawingPoints(); + } + + /** + * This supposedly returns the unit tangent Vector at the end of the path, but since there is + * no end tangent of a point, this returns a zero Vector instead. Holding BezierPoints in the + * Follower doesn't use the drive Vector, so the end tangent Vector is not needed or truly used. + * + * @return returns the zero Vector. + */ + @Override + public Vector getEndTangent() { + return MathFunctions.copyVector(endTangent); + } + + /** + * This gets the length of the BezierPoint. Since points don't have length, this returns zero. + * + * @return returns the length of the BezierPoint. + */ + @Override + public double approximateLength() { + return 0.0; + } + + /** + * This returns the point on the BezierPoint that is specified by the parametric t value. Since + * this is a Point, this just returns the one control point's position. + * + * @param t this is the t value of the parametric line. t is clamped to be between 0 and 1 inclusive. + * @return this returns the Point requested. + */ + @Override + public Point getPoint(double t) { + return new Point(point.getX(), point.getY(), Point.CARTESIAN); + } + + /** + * This returns the curvature of the BezierPoint, which is zero since this is a Point. + * + * @param t the parametric t value. + * @return returns the curvature, which is zero. + */ + @Override + public double getCurvature(double t) { + return 0.0; + } + + /** + * This returns the derivative on the BezierPoint, which is the zero Vector since this is a Point. + * The t value doesn't really do anything, but it's there so I can override methods. + * + * @param t this is the t value of the parametric curve. t is clamped to be between 0 and 1 inclusive. + * @return this returns the derivative requested, which is the zero Vector. + */ + @Override + public Vector getDerivative(double t) { + return MathFunctions.copyVector(endTangent); + } + + /** + * This returns the second derivative on the Bezier line, which is the zero Vector since this + * is a Point. + * Once again, the t is only there for the override. + * + * @param t this is the t value of the parametric curve. t is clamped to be between 0 and 1 inclusive. + * @return this returns the second derivative requested, which is the zero Vector. + */ + @Override + public Vector getSecondDerivative(double t) { + return new Vector(); + } + + /** + * This returns the zero Vector, but it's here so I can override the method in the BezierCurve + * class. + * + * @param t this is the t value of the parametric curve. t is clamped to be between 0 and 1 inclusive. + * @return this returns the approximated second derivative, which is the zero Vector. + */ + @Override + public Vector getApproxSecondDerivative(double t) { + return new Vector(); + } + + /** + * Returns the ArrayList of control points for this BezierPoint + * + * @return This returns the control point. + */ + @Override + public ArrayList getControlPoints() { + ArrayList returnList = new ArrayList<>(); + returnList.add(point); + return returnList; + } + + /** + * Returns the first, and only, control point for this BezierPoint + * + * @return This returns the Point. + */ + @Override + public Point getFirstControlPoint() { + return point; + } + + /** + * Returns the second control point, or the one after the start, for this BezierPoint. This + * returns the one control point of the BezierPoint, and there are several redundant methods + * that return the same control point, but it's here so I can override methods. + * + * @return This returns the Point. + */ + @Override + public Point getSecondControlPoint() { + return point; + } + + /** + * Returns the second to last control point for this BezierPoint. This + * returns the one control point of the BezierPoint, and there are several redundant methods + * that return the same control point, but it's here so I can override methods. + * + * @return This returns the Point. + */ + @Override + public Point getSecondToLastControlPoint() { + return point; + } + + /** + * Returns the last control point for this BezierPoint. This + * returns the one control point of the BezierPoint, and there are several redundant methods + * that return the same control point, but it's here so I can override methods. + * + * @return This returns the Point. + */ + @Override + public Point getLastControlPoint() { + return point; + } + + /** + * Returns the length of this BezierPoint, which is zero since Points don't have length. + * + * @return This returns the length. + */ + @Override + public double length() { + return length; + } + + /** + * Returns the conversion factor of one unit of distance into t value. There is no length or + * conversion factor to speak of for Points. + * + * @return returns the conversion factor. + */ + @Override + public double UNIT_TO_TIME() { + return 0; + } + + /** + * Returns the type of path. This is used in case we need to identify the type of BezierCurve + * this is. + * + * @return returns the type of path. + */ + @Override + public String pathType() { + return "point"; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/MathFunctions.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/MathFunctions.java new file mode 100644 index 0000000..0edfbfd --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/MathFunctions.java @@ -0,0 +1,307 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration; + +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose; + +/** + * This is the MathFunctions class. This contains many useful math related methods that I use in + * other classes to simplify code elsewhere. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/9/2024 + */ +public class MathFunctions { + + /** + * This is a simple implementation of the choose function in math. It's equivalent to the number + * of ways you can choose r items from n total items, if only which items got picked and not the + * order of picking the items mattered. + * + * @param n this is how many you want to choose from. + * @param r this is how many you want to choose. + * @return returns the result of the "n choose r" function. + */ + public static double nCr(int n, int r) { + double num = 1; + double denom = 1; + + // this multiplies up the numerator of the nCr function + for (int i = n; i > n-r; i--) { + num *= i; + } + + // this multiplies up the denominator of the nCr function + for (int i = 1; i <=r; i++) { + denom *= i; + } + + return num/denom; + } + + /** + * This returns the sign (positive/negative) of a number. + * + * @param get the number. + * @return returns the sign of the number. + */ + public static double getSign(double get) { + if (get == 0) return 0; + if (get > 0) return 1; + return -1; + } + + /** + * This clamps down a value to between the lower and upper bounds inclusive. + * + * @param num the number to be clamped. + * @param lower the lower bound. + * @param upper the upper bound. + * @return returns the clamped number. + */ + public static double clamp(double num, double lower, double upper) { + if (num < lower) return lower; + if (num > upper) return upper; + return num; + } + + /** + * This normalizes an angle to be between 0 and 2 pi radians, inclusive. + * + * IMPORTANT NOTE: This method operates in radians. + * + * @param angleRadians the angle to be normalized. + * @return returns the normalized angle. + */ + public static double normalizeAngle(double angleRadians) { + double angle = angleRadians; + while (angle<0) angle += 2*Math.PI; + while (angle>2*Math.PI) angle -= 2*Math.PI; + return angle; + } + + /** + * This returns the smallest angle between two angles. This operates in radians. + * + * @param one one of the angles. + * @param two the other one. + * @return returns the smallest angle. + */ + public static double getSmallestAngleDifference(double one, double two) { + return Math.min(MathFunctions.normalizeAngle(one-two), MathFunctions.normalizeAngle(two-one)); + } + + /** + * This gets the direction to turn between a start heading and an end heading. Positive is left + * and negative is right. This operates in radians. + * + * @return returns the turn direction. + */ + public static double getTurnDirection(double startHeading, double endHeading) { + if (MathFunctions.normalizeAngle(endHeading-startHeading) >= 0 && MathFunctions.normalizeAngle(endHeading-startHeading) <= Math.PI) { + return 1; // counter clock wise + } + return -1; // clock wise + } + + /** + * This returns the distance between a Pose and a Point, + * + * @param pose this is the Pose. + * @param point this is the Point. + * @return returns the distance between the two. + */ + public static double distance(Pose pose, Point point) { + return Math.sqrt(Math.pow(pose.getX()-point.getX(), 2) + Math.pow(pose.getY()-point.getY(), 2)); + } + + /** + * This returns the distance between a Pose and another Pose. + * + * @param one this is the first Pose. + * @param two this is the second Pose. + * @return returns the distance between the two. + */ + public static double distance(Pose one, Pose two) { + return Math.sqrt(Math.pow(one.getX()-two.getX(), 2) + Math.pow(one.getY()-two.getY(), 2)); + } + + /** + * This returns a Point that is the sum of the two input Point. + * + * @param one the first Point + * @param two the second Point + * @return returns the sum of the two Points. + */ + public static Point addPoints(Point one, Point two) { + return new Point(one.getX() + two.getX(), one.getY() + two.getY(), Point.CARTESIAN); + } + + /** + * This returns a Pose that is the sum of the two input Pose. + * + * @param one the first Pose + * @param two the second Pose + * @return returns the sum of the two Pose. + */ + public static Pose addPoses(Pose one, Pose two) { + return new Pose(one.getX() + two.getX(), one.getY() + two.getY(), one.getHeading() + two.getHeading()); + } + + /** + * This subtracts the second Point from the first Point and returns the result as a Point. + * Do note that order matters here. + * + * @param one the first Point. + * @param two the second Point. + * @return returns the difference of the two Points. + */ + public static Point subtractPoints(Point one, Point two) { + return new Point(one.getX() - two.getX(), one.getY() - two.getY(), Point.CARTESIAN); + } + + /** + * This subtracts the second Pose from the first Pose and returns the result as a Pose. + * Do note that order matters here. + * + * @param one the first Pose. + * @param two the second Pose. + * @return returns the difference of the two Pose. + */ + public static Pose subtractPoses(Pose one, Pose two) { + return new Pose(one.getX() - two.getX(), one.getY() - two.getY(), one.getHeading() - two.getHeading()); + } + + /** + * This multiplies a Point by a scalar and returns the result as a Point + * + * @param point the Point being multiplied. + * @param scalar the scalar multiplying into the Point. + * @return returns the scaled Point. + */ + public static Point scalarMultiplyPoint(Point point, double scalar) { + return new Point(point.getX()*scalar, point.getY()*scalar, Point.CARTESIAN); + } + + /** + * Copies a Point, but with a different reference location in the memory. So basically a deep + * copy. + * + * @param point the Point to be deep copied. + * @return returns the copied Point. + */ + public static Point copyPoint(Point point) { + return new Point(point.getX(), point.getY(), Point.CARTESIAN); + } + + /** + * Copies a Vector, but with a different reference location in the memory. So basically a deep + * copy. + * + * @param vector Vector to be deep copied. + * @return returns the copied Vector. + */ + public static Vector copyVector(Vector vector) { + return new Vector(vector.getMagnitude(), vector.getTheta()); + } + + /** + * This multiplies a Vector by a scalar and returns the result as a Vector. + * + * @param vector the Vector being multiplied. + * @param scalar the scalar multiplying into the Vector. + * @return returns the scaled Vector. + */ + public static Vector scalarMultiplyVector(Vector vector, double scalar) { + return new Vector(vector.getMagnitude()*scalar, vector.getTheta()); + } + + /** + * This normalizes a Vector to be of magnitude 1, unless the Vector is the zero Vector. + * In that case, it just returns back the zero Vector but with a different memory location. + * + * @param vector the Vector being normalized. + * @return returns the normalized (or zero) Vector. + */ + public static Vector normalizeVector(Vector vector) { + if (vector.getMagnitude() == 0) { + return new Vector(0.0, vector.getTheta()); + } else { + return new Vector(vector.getMagnitude()/Math.abs(vector.getMagnitude()), vector.getTheta()); + } + } + + /** + * This returns a Vector that is the sum of the two input Vectors. + * + * @param one the first Vector. + * @param two the second Vector. + * @return returns the sum of the Vectors. + */ + public static Vector addVectors(Vector one, Vector two) { + Vector returnVector = new Vector(); + returnVector.setOrthogonalComponents(one.getXComponent()+two.getXComponent(), one.getYComponent()+two.getYComponent()); + return returnVector; + } + + /** + * This subtracts the second Vector from the first Vector and returns the result as a Vector. + * Do note that order matters here. + * + * @param one the first Vector. + * @param two the second Vector. + * @return returns the second Vector subtracted from the first Vector. + */ + public static Vector subtractVectors(Vector one, Vector two) { + Vector returnVector = new Vector(); + returnVector.setOrthogonalComponents(one.getXComponent()-two.getXComponent(), one.getYComponent()-two.getYComponent()); + return returnVector; + } + + /** + * This computes the dot product of the two Vectors. + * + * @param one the first Vector. + * @param two the second Vector. + * @return returns the dot product of the two Vectors. + */ + public static double dotProduct(Vector one, Vector two) { + return one.getXComponent()*two.getXComponent() + one.getYComponent()*two.getYComponent(); + } + + /** + * This computes the first Vector crossed with the second Vector, so a cross product. + * Do note that order matters here. + * + * @param one the first Vector. + * @param two the second Vector. + * @return returns the cross product of the two Vectors. + */ + public static double crossProduct(Vector one, Vector two) { + return one.getXComponent()*two.getYComponent() - one.getYComponent()*two.getXComponent(); + } + + /** + * This returns whether a specified value is within a second specified value by plus/minus a + * specified accuracy amount. + * + * @param one first number specified. + * @param two second number specified. + * @param accuracy the level of accuracy specified. + * @return returns if the two numbers are within the specified accuracy of each other. + */ + public static boolean roughlyEquals(double one, double two, double accuracy) { + return (one < two + accuracy && one > two - accuracy); + } + + /** + * This returns whether a specified number is within a second specified number by plus/minus 0.0001. + * + * @param one first number specified. + * @param two second number specified. + * @return returns if a specified number is within plus/minus 0.0001 of the second specified number. + */ + public static boolean roughlyEquals(double one, double two) { + return roughlyEquals(one, two, 0.0001); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/Path.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/Path.java new file mode 100644 index 0000000..1539a49 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/Path.java @@ -0,0 +1,486 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration; + +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose; +import org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants; + +import java.util.ArrayList; + +/** + * This is the Path class. This class handles containing information on the actual path the Follower + * will follow, not just the shape of the path that the BezierCurve class handles. This contains + * information on the stop criteria for a Path, the heading interpolation, and deceleration. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/10/2024 + */ +public class Path { + private BezierCurve curve; + + private double startHeading; + private double endHeading; + private double closestPointCurvature; + private double closestPointTValue; + private double linearInterpolationEndTime; + + private Vector closestPointTangentVector; + private Vector closestPointNormalVector; + + private boolean isTangentHeadingInterpolation = true; + private boolean followTangentReversed; + + // A multiplier for the zero power acceleration to change the speed the robot decelerates at + // the end of paths. + // Increasing this will cause the robot to try to decelerate faster, at the risk of overshoots + // or localization slippage. + // Decreasing this will cause the deceleration at the end of the Path to be slower, making the + // robot slower but reducing risk of end-of-path overshoots or localization slippage. + // This can be set individually for each Path, but this is the default. + private double zeroPowerAccelerationMultiplier = FollowerConstants.zeroPowerAccelerationMultiplier; + + // When the robot is at the end of its current Path or PathChain and the velocity goes + // this value, then end the Path. This is in inches/second. + // This can be custom set for each Path. + private double pathEndVelocityConstraint = FollowerConstants.pathEndVelocityConstraint; + + // When the robot is at the end of its current Path or PathChain and the translational error + // goes below this value, then end the Path. This is in inches. + // This can be custom set for each Path. + private double pathEndTranslationalConstraint = FollowerConstants.pathEndTranslationalConstraint; + + // When the robot is at the end of its current Path or PathChain and the heading error goes + // below this value, then end the Path. This is in radians. + // This can be custom set for each Path. + private double pathEndHeadingConstraint = FollowerConstants.pathEndHeadingConstraint; + + // When the t-value of the closest point to the robot on the Path is greater than this value, + // then the Path is considered at its end. + // This can be custom set for each Path. + private double pathEndTValueConstraint = FollowerConstants.pathEndTValueConstraint; + + // When the Path is considered at its end parametrically, then the Follower has this many + // milliseconds to further correct by default. + // This can be custom set for each Path. + private double pathEndTimeoutConstraint = FollowerConstants.pathEndTimeoutConstraint; + + /** + * Creates a new Path from a BezierCurve. The default heading interpolation is tangential. + * + * @param curve the BezierCurve. + */ + public Path(BezierCurve curve) { + this.curve = curve; + } + + /** + * This sets the heading interpolation to linear with a specified start heading and end heading + * for the Path. This will interpolate across the entire length of the Path, so there may be + * some issues with end heading accuracy and precision if this is used. If a precise end heading + * is necessary, then use the setLinearHeadingInterpolation(double startHeading, + * double endHeading, double endTime) method. + * + * @param startHeading The start of the linear heading interpolation. + * @param endHeading The end of the linear heading interpolation. + * This will be reached at the end of the Path if no end time is specified. + */ + public void setLinearHeadingInterpolation(double startHeading, double endHeading) { + linearInterpolationEndTime = 1; + isTangentHeadingInterpolation = false; + this.startHeading = startHeading; + this.endHeading = endHeading; + } + + /** + * This sets the heading interpolation to linear with a specified start heading and end heading + * for the Path. This will interpolate from the start of the Path to the specified end time. + * This ensures high accuracy and precision than interpolating across the entire Path. However, + * interpolating too quickly can cause undesired oscillations and inaccuracies of its own, so + * generally interpolating to something like 0.8 of your Path should work best. + * + * @param startHeading The start of the linear heading interpolation. + * @param endHeading The end of the linear heading interpolation. + * This will be reached at the end of the Path if no end time is specified. + * @param endTime The end time on the Path that the linear heading interpolation will finish. + * This value ranges from [0, 1] since Bezier curves are parametric functions. + */ + public void setLinearHeadingInterpolation(double startHeading, double endHeading, double endTime) { + linearInterpolationEndTime = MathFunctions.clamp(endTime, 0.000000001, 1); + isTangentHeadingInterpolation = false; + this.startHeading = startHeading; + this.endHeading = endHeading; + } + + /** + * This sets the heading interpolation to maintain a constant heading. + * + * @param setHeading the constant heading for the Path. + */ + public void setConstantHeadingInterpolation(double setHeading) { + linearInterpolationEndTime = 1; + isTangentHeadingInterpolation = false; + startHeading = setHeading; + endHeading = setHeading; + } + + /** + * This gets the closest Point from a specified pose to the BezierCurve with a binary search + * that is limited to some specified step limit. + * + * @param pose the pose. + * @param searchStepLimit the binary search step limit. + * @return returns the closest Point. + */ + public Pose getClosestPoint(Pose pose, int searchStepLimit) { + double lower = 0; + double upper = 1; + Point returnPoint; + + // we don't need to calculate the midpoint, so we start off at the 1/4 and 3/4 point + for (int i = 0; i < searchStepLimit; i++) { + if (MathFunctions.distance(pose, getPoint(lower + 0.25 * (upper-lower))) > MathFunctions.distance(pose, getPoint(lower + 0.75 * (upper-lower)))) { + lower += (upper-lower)/2.0; + } else { + upper -= (upper-lower)/2.0; + } + } + + closestPointTValue = lower + 0.5 * (upper-lower); + + returnPoint = getPoint(closestPointTValue); + + closestPointTangentVector = curve.getDerivative(closestPointTValue); + + closestPointNormalVector = curve.getApproxSecondDerivative(closestPointTValue); + + closestPointCurvature = curve.getCurvature(closestPointTValue); + + return new Pose(returnPoint.getX(), returnPoint.getY(), getClosestPointHeadingGoal()); + } + + /** + * This sets whether to follow the tangent heading facing away from (reverse) or towards the + * tangent. This will also set your heading interpolation to tangential. + * + * @param set sets tangential heading reversed or not. + */ + public void setReversed(boolean set) { + isTangentHeadingInterpolation = true; + followTangentReversed = set; + } + + /** + * This sets the heading interpolation to tangential. + */ + public void setTangentHeadingInterpolation() { + isTangentHeadingInterpolation = true; + followTangentReversed = false; + } + + /** + * This returns the unit tangent Vector at the end of the BezierCurve. + * + * @return returns the end tangent Vector. + */ + public Vector getEndTangent() { + return curve.getEndTangent(); + } + + /** + * This returns the point on the Bezier curve that is specified by the parametric t value. A + * Bezier curve is a parametric function that returns points along it with t ranging from [0, 1], + * with 0 being the beginning of the curve and 1 being at the end. The Follower will follow + * BezierCurves from 0 to 1, in terms of t. + * + * @param t this is the t value of the parametric curve. t is clamped to be between 0 and 1 inclusive. + * @return this returns the point requested. + */ + public Point getPoint(double t) { + return curve.getPoint(t); + } + + /** + * This returns the t-value of the closest Point on the BezierCurve. + * + * @return returns the closest Point t-value. + */ + public double getClosestPointTValue() { + return closestPointTValue; + } + + /** + * This returns the approximated length of the BezierCurve. + * + * @return returns the length of the BezierCurve. + */ + public double length() { + return curve.length(); + } + + /** + * This returns the curvature of the BezierCurve at a specified t-value. + * + * @param t the specified t-value. + * @return returns the curvature of the BezierCurve at the specified t-value. + */ + public double getCurvature(double t) { + return curve.getCurvature(t); + } + + /** + * This returns the curvature of the BezierCurve at the closest Point. + * + * @return returns the curvature of the BezierCurve at the closest Point. + */ + public double getClosestPointCurvature() { + return closestPointCurvature; + } + + /** + * This returns the normal Vector at the closest Point. + * + * @return returns the normal Vector at the closest Point. + */ + public Vector getClosestPointNormalVector() { + return MathFunctions.copyVector(closestPointNormalVector); + } + + /** + * This returns the tangent Vector at the closest Point. + * + * @return returns the tangent Vector at the closest Point. + */ + public Vector getClosestPointTangentVector() { + return MathFunctions.copyVector(closestPointTangentVector); + } + + /** + * This returns the heading goal at the closest Point. + * + * @return returns the heading goal at the closest Point. + */ + public double getClosestPointHeadingGoal() { + if (isTangentHeadingInterpolation) { + if (followTangentReversed) return MathFunctions.normalizeAngle(closestPointTangentVector.getTheta() + Math.PI); + return closestPointTangentVector.getTheta(); + } else { + return getHeadingGoal(closestPointTValue); + } + } + + /** + * This gets the heading goal at a specified t-value. + * + * @param t the specified t-value. + * @return returns the heading goal at the specified t-value. + */ + public double getHeadingGoal(double t) { + if (isTangentHeadingInterpolation) { + if (followTangentReversed) return MathFunctions.normalizeAngle(curve.getDerivative(t).getTheta() + Math.PI); + return curve.getDerivative(t).getTheta(); + } else { + if (t > linearInterpolationEndTime) { + return MathFunctions.normalizeAngle(endHeading); + } + return MathFunctions.normalizeAngle(startHeading + MathFunctions.getTurnDirection(startHeading, endHeading) * MathFunctions.getSmallestAngleDifference(endHeading, startHeading) * (t / linearInterpolationEndTime)); + } + } + + /** + * This returns if the robot is at the end of the Path, according to the parametric t-value. + * + * @return returns if at end. + */ + public boolean isAtParametricEnd() { + if (closestPointTValue >= pathEndTValueConstraint) return true; + return false; + } + + /** + * This returns if the robot is at the beginning of the Path, according to the parametric t-value. + * + * @return returns if at start. + */ + public boolean isAtParametricStart() { + if (closestPointTValue <= 1- pathEndTValueConstraint) return true; + return false; + } + + /** + * Returns the ArrayList of control points for this BezierCurve. + * + * @return This returns the control points. + */ + public ArrayList getControlPoints() { + return curve.getControlPoints(); + } + + /** + * Returns the first control point for this BezierCurve. + * + * @return This returns the Point. + */ + public Point getFirstControlPoint() { + return curve.getFirstControlPoint(); + } + + /** + * Returns the second control point, or the one after the start, for this BezierCurve. + * + * @return This returns the Point. + */ + public Point getSecondControlPoint() { + return curve.getSecondControlPoint(); + } + + /** + * Returns the second to last control point for this BezierCurve. + * + * @return This returns the Point. + */ + public Point getSecondToLastControlPoint() { + return curve.getSecondToLastControlPoint(); + } + + /** + * Returns the last control point for this BezierCurve. + * + * @return This returns the Point. + */ + public Point getLastControlPoint() { + return curve.getLastControlPoint(); + } + + /** + * This sets the path's deceleration factor in terms of the natural deceleration of the robot + * when power is cut from the drivetrain. + * + * @param set This sets the multiplier. + */ + public void setZeroPowerAccelerationMultiplier(double set) { + zeroPowerAccelerationMultiplier = set; + } + + /** + * This sets the velocity stop criteria. When velocity is below this amount, then this is met. + * + * @param set This sets the velocity end constraint. + */ + public void setPathEndVelocityConstraint(double set) { + pathEndVelocityConstraint = set; + } + + /** + * This sets the translational stop criteria. When the translational error, or how far off the + * end point the robot is, goes below this, then the translational end criteria is met. + * + * @param set This sets the translational end constraint. + */ + public void setPathEndTranslationalConstraint(double set) { + pathEndTranslationalConstraint = set; + } + + /** + * This sets the heading stop criteria. When the heading error is less than this amount, then + * the heading end criteria is met. + * + * @param set This sets the heading end constraint. + */ + public void setPathEndHeadingConstraint(double set) { + pathEndHeadingConstraint = set; + } + + /** + * This sets the parametric end criteria. When the t-value of the closest Point on the Path is + * greater than this amount, then the parametric end criteria is met. + * + * @param set This sets the t-value end constraint. + */ + public void setPathEndTValueConstraint(double set) { + pathEndTValueConstraint = set; + } + + /** + * This sets the Path end timeout. If the Path is at its end parametrically, then the Follower + * has this many milliseconds to correct before the Path gets ended anyways. + * + * @param set This sets the Path end timeout. + */ + public void setPathEndTimeoutConstraint(double set) { + pathEndTimeoutConstraint = set; + } + + /** + * This gets the deceleration multiplier. + * + * @return This returns the deceleration multiplier. + */ + public double getZeroPowerAccelerationMultiplier() { + return zeroPowerAccelerationMultiplier; + } + + /** + * This gets the velocity stop criteria. + * + * @return This returns the velocity stop criteria. + */ + public double getPathEndVelocityConstraint() { + return pathEndVelocityConstraint; + } + + /** + * This gets the translational stop criteria. + * + * @return This returns the translational stop criteria. + */ + public double getPathEndTranslationalConstraint() { + return pathEndTranslationalConstraint; + } + + /** + * This gets the heading stop criteria. + * + * @return This returns the heading stop criteria. + */ + public double getPathEndHeadingConstraint() { + return pathEndHeadingConstraint; + } + + /** + * This gets the parametric end criteria. + * + * @return This returns the parametric end criteria. + */ + public double getPathEndTValueConstraint() { + return pathEndTValueConstraint; + } + + /** + * This gets the Path end correction time. + * + * @return This returns the Path end correction time. + */ + public double getPathEndTimeoutConstraint() { + return pathEndTimeoutConstraint; + } + + /** + * Returns the type of path. This is used in case we need to identify the type of BezierCurve + * this is. + * + * @return returns the type of path. + */ + public String pathType() { + return curve.pathType(); + } + + /** + * This returns a 2D Array of doubles containing the x and y positions of points to draw on FTC + * Dashboard. + * + * @return returns the 2D Array to draw on FTC Dashboard + */ + public double[][] getDashboardDrawingPoints() { + return curve.getDashboardDrawingPoints(); + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/PathBuilder.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/PathBuilder.java new file mode 100644 index 0000000..5bfff7d --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/PathBuilder.java @@ -0,0 +1,217 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration; + +import java.util.ArrayList; + +/** + * This is the PathBuilder class. This class makes it easier to create PathChains, so you don't have + * to individually create Path instances to create a PathChain. A PathBuilder can be accessed + * through running the pathBuilder() method on an instance of the Follower class, or just creating + * an instance of PathBuilder regularly. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/11/2024 + */ +public class PathBuilder { + private ArrayList paths = new ArrayList<>(); + + private ArrayList callbacks = new ArrayList<>(); + + /** + * This is an empty constructor for the PathBuilder class so it can get started. + * The PathBuilder allows for easier construction of PathChains. + * The proper usage is using an instance of the Follower class: + * Follower follower = new Follower(hardwareMap); + * Then calling "follower.pathBuilder.[INSERT PATH BUILDING METHODS].build(); + * Of course, you can split up the method calls onto separate lines for readability. + */ + public PathBuilder() { + } + + /** + * This adds a Path to the PathBuilder. + * + * @param path The Path being added. + * @return This returns itself with the updated data. + */ + public PathBuilder addPath(Path path) { + this.paths.add(path); + return this; + } + + /** + * This adds a default Path defined by a specified BezierCurve to the PathBuilder. + * + * @param curve The curve is turned into a Path and added. + * @return This returns itself with the updated data. + */ + public PathBuilder addPath(BezierCurve curve) { + this.paths.add(new Path(curve)); + return this; + } + + /** + * This sets a linear heading interpolation on the last Path added to the PathBuilder. + * + * @param startHeading The start of the linear heading interpolation. + * @param endHeading The end of the linear heading interpolation. + * This will be reached at the end of the Path if no end time is specified. + * @return This returns itself with the updated data. + */ + public PathBuilder setLinearHeadingInterpolation(double startHeading, double endHeading) { + this.paths.get(paths.size()-1).setLinearHeadingInterpolation(startHeading, endHeading); + return this; + } + + /** + * This sets a linear heading interpolation on the last Path added to the PathBuilder. + * + * @param startHeading The start of the linear heading interpolation. + * @param endHeading The end of the linear heading interpolation. + * This will be reached at the end of the Path if no end time is specified. + * @param endTime The end time on the Path that the linear heading interpolation will end. + * This value goes from [0, 1] since Bezier curves are parametric functions. + * @return This returns itself with the updated data. + */ + public PathBuilder setLinearHeadingInterpolation(double startHeading, double endHeading, double endTime) { + this.paths.get(paths.size()-1).setLinearHeadingInterpolation(startHeading, endHeading, endTime); + return this; + } + + /** + * This sets a constant heading interpolation on the last Path added to the PathBuilder. + * + * @param setHeading The constant heading specified. + * @return This returns itself with the updated data. + */ + public PathBuilder setConstantHeadingInterpolation(double setHeading) { + this.paths.get(paths.size()-1).setConstantHeadingInterpolation(setHeading); + return this; + } + + /** + * This sets a reversed or tangent heading interpolation on the last Path added to the PathBuilder. + * + * @param set This sets the heading to reversed tangent following if this parameter is true. + * Conversely, this sets a tangent following if this parameter is false. + * @return This returns itself with the updated data. + */ + public PathBuilder setReversed(boolean set) { + this.paths.get(paths.size()-1).setReversed(set); + return this; + } + /** + * This sets the heading interpolation to tangential on the last Path added to the PathBuilder. + * There really shouldn't be a reason to use this since the default heading interpolation is + * tangential but it's here. + */ + public PathBuilder setTangentHeadingInterpolation() { + this.paths.get(paths.size()-1).setTangentHeadingInterpolation(); + return this; + } + + /** + * This sets the deceleration multiplier on the last Path added to the PathBuilder. + * + * @param set This sets the multiplier for the goal for the deceleration of the robot. + * @return This returns itself with the updated data. + */ + public PathBuilder setZeroPowerAccelerationMultiplier(double set) { + this.paths.get(paths.size()-1).setZeroPowerAccelerationMultiplier(set); + return this; + } + + /** + * This sets the path end velocity constraint on the last Path added to the PathBuilder. + * + * @param set This sets the path end velocity constraint. + * @return This returns itself with the updated data. + */ + public PathBuilder setPathEndVelocityConstraint(double set) { + this.paths.get(paths.size()-1).setPathEndVelocityConstraint(set); + return this; + } + + /** + * This sets the path end translational constraint on the last Path added to the PathBuilder. + * + * @param set This sets the path end translational constraint. + * @return This returns itself with the updated data. + */ + public PathBuilder setPathEndTranslationalConstraint(double set) { + this.paths.get(paths.size()-1).setPathEndTranslationalConstraint(set); + return this; + } + + /** + * This sets the path end heading constraint on the last Path added to the PathBuilder. + * + * @param set This sets the path end heading constraint. + * @return This returns itself with the updated data. + */ + public PathBuilder setPathEndHeadingConstraint(double set) { + this.paths.get(paths.size()-1).setPathEndHeadingConstraint(set); + return this; + } + + /** + * This sets the path end t-value (parametric time) constraint on the last Path added to the PathBuilder. + * + * @param set This sets the path end t-value (parametric time) constraint. + * @return This returns itself with the updated data. + */ + public PathBuilder setPathEndTValueConstraint(double set) { + this.paths.get(paths.size()-1).setPathEndTValueConstraint(set); + return this; + } + + /** + * This sets the path end timeout constraint on the last Path added to the PathBuilder. + * + * @param set This sets the path end timeout constraint. + * @return This returns itself with the updated data. + */ + public PathBuilder setPathEndTimeoutConstraint(double set) { + this.paths.get(paths.size()-1).setPathEndTimeoutConstraint(set); + return this; + } + + /** + * This adds a temporal callback on the last Path added to the PathBuilder. + * This callback is set to run at a specified number of milliseconds after the start of the path. + * + * @param time This sets the number of milliseconds of wait between the start of the Path and + * the calling of the callback. + * @param runnable This sets the code for the callback to run. Use lambda statements for this. + * @return This returns itself with the updated data. + */ + public PathBuilder addTemporalCallback(double time, Runnable runnable) { + this.callbacks.add(new PathCallback(time, runnable, PathCallback.TIME, paths.size()-1)); + return this; + } + + /** + * This adds a parametric callback on the last Path added to the PathBuilder. + * This callback is set to run at a certain point on the Path. + * + * @param t This sets the t-value (parametric time) on the Path for when to run the callback. + * @param runnable This sets the code for the callback to run. Use lambda statements for this. + * @return This returns itself with the updated data. + */ + public PathBuilder addParametricCallback(double t, Runnable runnable) { + this.callbacks.add(new PathCallback(t, runnable, PathCallback.PARAMETRIC, paths.size()-1)); + return this; + } + + /** + * This builds all the Path and callback information together into a PathChain. + * + * @return This returns a PathChain made of all the specified paths and callbacks. + */ + public PathChain build() { + PathChain returnChain = new PathChain(paths); + returnChain.setCallbacks(callbacks); + return returnChain; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/PathCallback.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/PathCallback.java new file mode 100644 index 0000000..c02e1d5 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/PathCallback.java @@ -0,0 +1,78 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration; + +import org.firstinspires.ftc.teamcode.pedroPathing.util.SingleRunAction; + +/** + * This is the PathCallback class. This class handles callbacks of Runnables in PathChains. + * Basically, this allows you to run non-blocking code in the middle of PathChains. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/11/2024 + */ +public class PathCallback extends SingleRunAction { + + private double startCondition; + + private int type; + private int index; + + public static final int TIME = 0; + public static final int PARAMETRIC = 1; + + /** + * This creates a new PathCallback with a specified start condition (either time or parametric), + * a Runnable of code to run (preferably a lambda statement), a type (using the class constants), + * and an index for which Path within a PathChain the callback is to run on. + * + * @param startCondition This defines when the callback is to be run, either as a wait time in + * milliseconds or a t-value (parametric time) point. + * @param runnable This contains the code to run when the callback is called. + * @param type This defines the type of callback using the class constants. + * @param index This defines which Path within the PathChain the callback is to run on. + */ + public PathCallback(double startCondition, Runnable runnable, int type, int index) { + super(runnable); + this.startCondition = startCondition; + this.type = type; + if (this.type != TIME || this.type != PARAMETRIC) { + this.type = PARAMETRIC; + } + if (this.type == TIME && this.startCondition < 0) { + this.startCondition = 0.0; + } + if (this.type == PARAMETRIC) { + this.startCondition = MathFunctions.clamp(this.startCondition, 0, 1); + } + this.index = index; + } + + /** + * This returns the type of callback this is (time or parametric). + * + * @return This returns the type of callback. + */ + public int getType() { + return type; + } + + /** + * This returns the start condition for this callback. This will be the wait time in milliseconds + * if this is a time callback or a t-value if this is a parametric callback. + * + * @return This returns the start condition. + */ + public double getStartCondition() { + return startCondition; + } + + /** + * This returns the index of which Path the callback is to run on within the PathChain. + * + * @return This returns the Path index of this callback. + */ + public int getIndex() { + return index; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/PathChain.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/PathChain.java new file mode 100644 index 0000000..f350f5e --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/PathChain.java @@ -0,0 +1,94 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration; + +import java.util.ArrayList; + +/** + * This is the PathChain class. This class handles chaining together multiple Paths into a larger + * collection of Paths that can be run continuously. Additionally, this allows for the addition of + * PathCallbacks to specific Paths in the PathChain, allowing for non-blocking code to be run in + * the middle of a PathChain. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/11/2024 + */ +public class PathChain { + private ArrayList pathChain = new ArrayList<>(); + + private ArrayList callbacks = new ArrayList<>(); + + /** + * This creates a new PathChain from some specified Paths. + * + * IMPORTANT NOTE: Order matters here. The order in which the Paths are input is the order in + * which they will be run. + * + * @param paths the specified Paths. + */ + public PathChain(Path... paths) { + for (Path path : paths) { + pathChain.add(path); + } + } + + /** + * This creates a new PathChain from an ArrayList of Paths. + * + * IMPORTANT NOTE: Order matters here. The order in which the Paths are input is the order in + * which they will be run. + * + * @param paths the ArrayList of Paths. + */ + public PathChain(ArrayList paths) { + pathChain = paths; + } + + /** + * This returns the Path on the PathChain at a specified index. + * + * @param index the index. + * @return returns the Path at the index. + */ + public Path getPath(int index) { + return pathChain.get(index); + } + + /** + * This returns the size of the PathChain. + * + * @return returns the size of the PathChain. + */ + public int size() { + return pathChain.size(); + } + + /** + * This sets the PathCallbacks of the PathChain with some specified PathCallbacks. + * + * @param callbacks the specified PathCallbacks. + */ + public void setCallbacks(PathCallback... callbacks) { + for (PathCallback callback : callbacks) { + this.callbacks.add(callback); + } + } + + /** + * This sets the PathCallbacks of the PathChain with an ArrayList of PathCallbacks. + * + * @param callbacks the ArrayList of PathCallbacks. + */ + public void setCallbacks(ArrayList callbacks) { + this.callbacks = callbacks; + } + + /** + * This returns the PathCallbacks of this PathChain in an ArrayList. + * + * @return returns the PathCallbacks. + */ + public ArrayList getCallbacks() { + return callbacks; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/Point.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/Point.java new file mode 100644 index 0000000..0da8df8 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/Point.java @@ -0,0 +1,185 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration; + +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose; + +/** + * This is the Point class. This class handles storing information about the location of points in + * 2D space in both Cartesian, or rectangular, and polar coordinates. Additionally, this contains + * the method to find the distance between two Points. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/11/2024 + */ +public class Point { + + // IMPORTANT NOTE: theta is defined in radians. + // These are the values of the coordinate defined by this Point, in both polar and + // Cartesian systems. + private double r; + private double theta; + private double x; + private double y; + + // these are used for ease of changing/setting identification + public static final int POLAR = 0; + public static final int CARTESIAN = 1; + + + /** + * This creates a new Point with coordinate inputs and a specified coordinate system. + * + * @param rOrX Depending on the coordinate system specified, this is either the r or x value. + * In polar coordinates, the r value is the distance from the origin. + * In Cartesian coordinates, the x value is the distance left/right from the origin. + * @param thetaOrY Depending on the coordinate system specified, this is either the theta or + * y value. + * In polar coordinates, the theta value is the angle from the positive x-axis. + * Increasing theta moves in the counter-clockwise direction. + * In Cartesian coordinates, the y value is the distance up/down from the origin. + * @param identifier this specifies what coordinate system the coordinate inputs are in. + */ + public Point(double rOrX, double thetaOrY, int identifier) { + setCoordinates(rOrX, thetaOrY, identifier); + } + + /** + * This creates a new Point from a Pose. + * + * @param pose the Pose. + */ + public Point(Pose pose) { + setCoordinates(pose.getX(), pose.getY(), CARTESIAN); + } + + /** + * This sets the coordinates of the Point using the specified coordinate system. + * + * @param rOrX Depending on the coordinate system specified, this is either the r or x value. + * In polar coordinates, the r value is the distance from the origin. + * In Cartesian coordinates, the x value is the distance left/right from the origin. + * @param thetaOrY Depending on the coordinate system specified, this is either the theta or + * y value. + * In polar coordinates, the theta value is the angle from the positive x-axis. + * Increasing theta moves in the counter-clockwise direction. + * In Cartesian coordinates, the y value is the distance up/down from the origin. + * @param identifier this specifies what coordinate system to use when setting values. + */ + public void setCoordinates(double rOrX, double thetaOrY, int identifier) { + double[] setOtherCoordinates; + switch (identifier) { // this detects which coordinate system to use + // there is no POLAR case since that's covered by the default + case CARTESIAN: + x = rOrX; + y = thetaOrY; + setOtherCoordinates = cartesianToPolar(x, y); + r = setOtherCoordinates[0]; + theta = setOtherCoordinates[1]; + break; + default: + if (rOrX<0) { + r = -rOrX; + theta = MathFunctions.normalizeAngle(thetaOrY+Math.PI); + } else { + r = rOrX; + theta = MathFunctions.normalizeAngle(thetaOrY); + } + setOtherCoordinates = polarToCartesian(r, theta); + x = setOtherCoordinates[0]; + y = setOtherCoordinates[1]; + break; + } + } + + /** + * Calculates the distance between this Point and some other specified Point. + * + * @param otherPoint the other specified Point. + * @return returns the distance between the two Points. + */ + public double distanceFrom(Point otherPoint) { + return Math.sqrt(Math.pow(otherPoint.getX()-x, 2) + Math.pow(otherPoint.getY()-y, 2)); + } + + /** + * This takes in an r and theta value and converts them to Cartesian coordinates. + * + * @param r this is the r value of the Point being converted. + * @param theta this is the theta value of the Point being converted. + * @return this returns the x and y values, in that order, in an Array of doubles. + */ + public static double[] polarToCartesian(double r, double theta) { + return new double[] {r * Math.cos(theta), r * Math.sin(theta)}; + } + + /** + * This takes in an x and y value and converts them to polar coordinates. + * + * @param x this is the x value of the Point being converted. + * @param y this is the y value of the Point being converted. + * @return this returns the r and theta values, in that order, in an Array of doubles. + */ + public static double[] cartesianToPolar(double x, double y) { + if (x == 0) { + if (y > 0) { + return new double[] {Math.abs(y), Math.PI/2}; + } else { + return new double[] {Math.abs(y), (3 * Math.PI) / 2}; + } + } + double r = Math.sqrt(x*x+y*y); + if (x < 0) return new double[] {r, Math.PI+Math.atan(y/x)}; + if (y > 0) { + return new double[]{r, Math.atan(y / x)}; + } else { + return new double[]{r, (2*Math.PI) + Math.atan(y / x)}; + } + } + + /** + * Returns the r value of this Point. This is a polar coordinate value. + * + * @return returns the r value. + */ + public double getR() { + return r; + } + + /** + * Returns the theta value of this Point. This is a polar coordinate value. + * + * @return returns the theta value. + */ + public double getTheta() { + return theta; + } + + /** + * Returns the x value of this Point. This is a Cartesian coordinate value. + * + * @return returns the x value. + */ + public double getX() { + return x; + } + + /** + * Returns the y value of this Point. This is a Cartesian coordinate value. + * + * @return returns the y value. + */ + public double getY() { + return y; + } + + /** + * This creates a new Point with the same information as this Point, just pointing to a different + * memory location. In other words, a deep copy. + * + * @return returns a copy of this Point. + */ + public Point copy() { + return new Point(getX(), getY(), CARTESIAN); + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/Vector.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/Vector.java new file mode 100644 index 0000000..f1a093b --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/pathGeneration/Vector.java @@ -0,0 +1,141 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration; + +/** + * This is the Point class. This class handles storing information about vectors, which are + * basically Points but using polar coordinates as the default. The main reason this class exists + * is because some vector math needs to be done in the Follower, and dot products and cross + * products of Points just don't seem right. Also, there are a few more methods in here that make + * using Vectors a little easier than using a Point in polar coordinates. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/11/2024 + */ +public class Vector { + + // IMPORTANT NOTE: theta is defined in radians. + // These are the values of the coordinate defined by this Point, in both polar and + // Cartesian systems. + private double magnitude; + private double theta; + private double xComponent; + private double yComponent; + + /** + * This creates a new Vector with zero magnitude and direction. + */ + public Vector() { + setComponents(0, 0); + } + + /** + * This creates a new Vector with a specified magnitude and direction. + * + * @param magnitude magnitude of the Vector. + * @param theta the direction of the Vector in radians. + */ + public Vector(double magnitude, double theta) { + setComponents(magnitude, theta); + } + + /** + * This sets the components of the Vector in regular vector coordinates. + * + * @param magnitude sets the magnitude of this Vector. + * @param theta sets the theta value of this Vector. + */ + public void setComponents(double magnitude, double theta) { + double[] orthogonalComponents; + if (magnitude<0) { + this.magnitude = -magnitude; + this.theta = MathFunctions.normalizeAngle(theta+Math.PI); + } else { + this.magnitude = magnitude; + this.theta = MathFunctions.normalizeAngle(theta); + } + orthogonalComponents = Point.polarToCartesian(magnitude, theta); + xComponent = orthogonalComponents[0]; + yComponent = orthogonalComponents[1]; + } + + /** + * This sets only the magnitude of the Vector. + * + * @param magnitude sets the magnitude of this Vector. + */ + public void setMagnitude(double magnitude) { + setComponents(magnitude, theta); + } + + /** + * This sets only the angle, theta, of the Vector. + * + * @param theta sets the angle, or theta value, of this Vector. + */ + public void setTheta(double theta) { + setComponents(magnitude, theta); + } + + /** + * This rotates the Vector by an angle, theta. + * + * @param theta2 the angle to be added. + */ + public void rotateVector(double theta2) { + setTheta(theta+theta2); + } + + /** + * This sets the orthogonal components of the Vector. These orthogonal components are assumed + * to be in the direction of the x-axis and y-axis. In other words, this is setting the + * coordinates of the Vector using x and y coordinates instead of a direction and magnitude. + * + * @param xComponent sets the x component of this Vector. + * @param yComponent sets the y component of this Vector. + */ + public void setOrthogonalComponents(double xComponent, double yComponent) { + double[] polarComponents; + this.xComponent = xComponent; + this.yComponent = yComponent; + polarComponents = Point.cartesianToPolar(xComponent, yComponent); + magnitude = polarComponents[0]; + theta = polarComponents[1]; + } + + /** + * Returns the magnitude of this Vector. + * + * @return returns the magnitude. + */ + public double getMagnitude() { + return magnitude; + } + + /** + * Returns the theta value, or angle, of this Vector. + * + * @return returns the theta value. + */ + public double getTheta() { + return theta; + } + + /** + * Returns the x component of this Vector. + * + * @return returns the x component. + */ + public double getXComponent() { + return xComponent; + } + + /** + * Returns the y component of this Vector. + * + * @return returns the y component. + */ + public double getYComponent() { + return yComponent; + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/Circle.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/Circle.java new file mode 100644 index 0000000..196b378 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/Circle.java @@ -0,0 +1,74 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.tuning; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierCurve; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point; + +/** + * This is the Circle autonomous OpMode. It runs the robot in a PathChain that's actually not quite + * a circle, but some Bezier curves that have control points set essentially in a square. However, + * it turns enough to tune your centripetal force correction and some of your heading. Some lag in + * heading is to be expected. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/12/2024 + */ +@Config +@Autonomous (name = "Circle", group = "Autonomous Pathing Tuning") +public class Circle extends OpMode { + private Telemetry telemetryA; + + public static double RADIUS = 10; + + private Follower follower; + + private PathChain circle; + + /** + * This initializes the Follower and creates the PathChain for the "circle". Additionally, this + * initializes the FTC Dashboard telemetry. + */ + @Override + public void init() { + follower = new Follower(hardwareMap); + + circle = follower.pathBuilder() + .addPath(new BezierCurve(new Point(0,0, Point.CARTESIAN), new Point(RADIUS,0, Point.CARTESIAN), new Point(RADIUS, RADIUS, Point.CARTESIAN))) + .addPath(new BezierCurve(new Point(RADIUS, RADIUS, Point.CARTESIAN), new Point(RADIUS,2*RADIUS, Point.CARTESIAN), new Point(0,2*RADIUS, Point.CARTESIAN))) + .addPath(new BezierCurve(new Point(0,2*RADIUS, Point.CARTESIAN), new Point(-RADIUS,2*RADIUS, Point.CARTESIAN), new Point(-RADIUS, RADIUS, Point.CARTESIAN))) + .addPath(new BezierCurve(new Point(-RADIUS, RADIUS, Point.CARTESIAN), new Point(-RADIUS,0, Point.CARTESIAN), new Point(0,0, Point.CARTESIAN))) + .build(); + + follower.followPath(circle); + + telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); + telemetryA.addLine("This will run in a roughly circular shape of radius " + RADIUS + + ", starting on the right-most edge. So, make sure you have enough " + + "space to the left, front, and back to run the OpMode."); + telemetryA.update(); + } + + /** + * This runs the OpMode, updating the Follower as well as printing out the debug statements to + * the Telemetry, as well as the FTC Dashboard. + */ + @Override + public void loop() { + follower.update(); + if (follower.atParametricEnd()) { + follower.followPath(circle); + } + + follower.telemetryDebug(telemetryA); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/CurvedBackAndForth.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/CurvedBackAndForth.java new file mode 100644 index 0000000..6ff548f --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/CurvedBackAndForth.java @@ -0,0 +1,85 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.tuning; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierCurve; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Path; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point; + +/** + * This is the CurvedBackAndForth autonomous OpMode. It runs the robot in a specified distance + * forward and to the left. On reaching the end of the forward Path, the robot runs the backward + * Path the same distance back to the start. Rinse and repeat! This is good for testing a variety + * of Vectors, like the drive Vector, the translational Vector, the heading Vector, and the + * centripetal Vector. Remember to test your tunings on StraightBackAndForth as well, since tunings + * that work well for curves might have issues going in straight lines. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/13/2024 + */ +@Config +@Autonomous (name = "Curved Back And Forth", group = "Autonomous Pathing Tuning") +public class CurvedBackAndForth extends OpMode { + private Telemetry telemetryA; + + public static double DISTANCE = 20; + + private boolean forward = true; + + private Follower follower; + + private Path forwards; + private Path backwards; + + /** + * This initializes the Follower and creates the forward and backward Paths. Additionally, this + * initializes the FTC Dashboard telemetry. + */ + @Override + public void init() { + follower = new Follower(hardwareMap); + + forwards = new Path(new BezierCurve(new Point(0,0, Point.CARTESIAN), new Point(Math.abs(DISTANCE),0, Point.CARTESIAN), new Point(Math.abs(DISTANCE),DISTANCE, Point.CARTESIAN))); + backwards = new Path(new BezierCurve(new Point(Math.abs(DISTANCE),DISTANCE, Point.CARTESIAN), new Point(Math.abs(DISTANCE),0, Point.CARTESIAN), new Point(0,0, Point.CARTESIAN))); + + backwards.setReversed(true); + + follower.followPath(forwards); + + telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); + telemetryA.addLine("This will run the robot in a curve going " + DISTANCE + " inches" + + " to the left and the same number of inches forward. The robot will go" + + "forward and backward continuously along the path. Make sure you have" + + "enough room."); + telemetryA.update(); + } + + /** + * This runs the OpMode, updating the Follower as well as printing out the debug statements to + * the Telemetry, as well as the FTC Dashboard. + */ + @Override + public void loop() { + follower.update(); + if (!follower.isBusy()) { + if (forward) { + forward = false; + follower.followPath(backwards); + } else { + forward = true; + follower.followPath(forwards); + } + } + + telemetryA.addData("going forward", forward); + follower.telemetryDebug(telemetryA); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java new file mode 100644 index 0000000..af72609 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/FollowerConstants.java @@ -0,0 +1,211 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.tuning; + +import com.acmerobotics.dashboard.config.Config; + +import org.firstinspires.ftc.teamcode.pedroPathing.util.CustomFilteredPIDFCoefficients; +import org.firstinspires.ftc.teamcode.pedroPathing.util.CustomPIDFCoefficients; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; +import org.firstinspires.ftc.teamcode.pedroPathing.util.KalmanFilterParameters; + +/** + * This is the FollowerConstants class. It holds many constants and parameters for various parts of + * the Follower. This is here to allow for easier tuning of Pedro Pathing, as well as concentrate + * everything tunable for the Paths themselves in one place. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/4/2024 + */ +@Config +public class FollowerConstants { + + // This section is for configuring your motors + public static String leftFrontMotorName = "leftFront"; + public static String leftRearMotorName = "leftRear"; + public static String rightFrontMotorName = "rightFront"; + public static String rightRearMotorName = "rightRear"; + + // This section is for setting the actual drive vector for the front left wheel, if the robot + // is facing a heading of 0 radians with the wheel centered at (0,0) + private static double xMovement = 81.34056; + private static double yMovement = 65.43028; + private static double[] convertToPolar = Point.cartesianToPolar(xMovement, -yMovement); + public static Vector frontLeftVector = MathFunctions.normalizeVector(new Vector(convertToPolar[0],convertToPolar[1])); + + + // Translational PIDF coefficients (don't use integral) + public static CustomPIDFCoefficients translationalPIDFCoefficients = new CustomPIDFCoefficients( + 0.1, + 0, + 0, + 0); + + // Translational Integral + public static CustomPIDFCoefficients translationalIntegral = new CustomPIDFCoefficients( + 0, + 0, + 0, + 0); + + // Feed forward constant added on to the translational PIDF + public static double translationalPIDFFeedForward = 0.015; + + + // Heading error PIDF coefficients + public static CustomPIDFCoefficients headingPIDFCoefficients = new CustomPIDFCoefficients( + 1, + 0, + 0, + 0); + + // Feed forward constant added on to the heading PIDF + public static double headingPIDFFeedForward = 0.01; + + + // Drive PIDF coefficients + public static CustomFilteredPIDFCoefficients drivePIDFCoefficients = new CustomFilteredPIDFCoefficients( + 0.025, + 0, + 0.00001, + 0.6, + 0); + + // Feed forward constant added on to the drive PIDF + public static double drivePIDFFeedForward = 0.01; + + // Kalman filter parameters for the drive error Kalman filter + public static KalmanFilterParameters driveKalmanFilterParameters = new KalmanFilterParameters( + 6, + 1); + + + // Mass of robot in kilograms + public static double mass = 10.65942; + + // Centripetal force to power scaling + public static double centripetalScaling = 0.0005; + + + // Acceleration of the drivetrain when power is cut in inches/second^2 (should be negative) + // if not negative, then the robot thinks that its going to go faster under 0 power + public static double forwardZeroPowerAcceleration = -34.62719; + + // Acceleration of the drivetrain when power is cut in inches/second^2 (should be negative) + // if not negative, then the robot thinks that its going to go faster under 0 power + public static double lateralZeroPowerAcceleration = -78.15554; + + // A multiplier for the zero power acceleration to change the speed the robot decelerates at + // the end of paths. + // Increasing this will cause the robot to try to decelerate faster, at the risk of overshoots + // or localization slippage. + // Decreasing this will cause the deceleration at the end of the Path to be slower, making the + // robot slower but reducing risk of end-of-path overshoots or localization slippage. + // This can be set individually for each Path, but this is the default. + public static double zeroPowerAccelerationMultiplier = 4; + + + // When the robot is at the end of its current Path or PathChain and the velocity goes below + // this value, then end the Path. This is in inches/second. + // This can be custom set for each Path. + public static double pathEndVelocityConstraint = 0.1; + + // When the robot is at the end of its current Path or PathChain and the translational error + // goes below this value, then end the Path. This is in inches. + // This can be custom set for each Path. + public static double pathEndTranslationalConstraint = 0.1; + + // When the robot is at the end of its current Path or PathChain and the heading error goes + // below this value, then end the Path. This is in radians. + // This can be custom set for each Path. + public static double pathEndHeadingConstraint = 0.007; + + // When the t-value of the closest point to the robot on the Path is greater than this value, + // then the Path is considered at its end. + // This can be custom set for each Path. + public static double pathEndTValueConstraint = 0.995; + + // When the Path is considered at its end parametrically, then the Follower has this many + // milliseconds to further correct by default. + // This can be custom set for each Path. + public static double pathEndTimeoutConstraint = 500; + + // This is how many steps the BezierCurve class uses to approximate the length of a BezierCurve. + public static int APPROXIMATION_STEPS = 1000; + + // This is scales the translational error correction power when the Follower is holding a Point. + public static double holdPointTranslationalScaling = 0.45; + + // This is scales the heading error correction power when the Follower is holding a Point. + public static double holdPointHeadingScaling = 0.35; + + // This is the number of times the velocity is recorded for averaging when approximating a first + // and second derivative for on the fly centripetal correction. The velocity is calculated using + // half of this number of samples, and the acceleration uses all of this number of samples. + public static int AVERAGED_VELOCITY_SAMPLE_NUMBER = 8; + + // This is the number of steps the binary search for closest point uses. More steps is more + // accuracy, and this increases at an exponential rate. However, more steps also does take more + // time. + public static int BEZIER_CURVE_BINARY_STEP_LIMIT = 10; + + + // These activate / deactivate the secondary PIDs. These take over at errors under a set limit for + // the translational, heading, and drive PIDs. + public static boolean useSecondaryTranslationalPID = false; + public static boolean useSecondaryHeadingPID = false; + public static boolean useSecondaryDrivePID = false; + + + // the limit at which the translational PIDF switches between the main and secondary translational PIDFs, + // if the secondary PID is active + public static double translationalPIDFSwitch = 3; + + // Secondary translational PIDF coefficients (don't use integral) + public static CustomPIDFCoefficients secondaryTranslationalPIDFCoefficients = new CustomPIDFCoefficients( + 0.3, + 0, + 0.01, + 0); + + // Secondary translational Integral value + public static CustomPIDFCoefficients secondaryTranslationalIntegral = new CustomPIDFCoefficients( + 0, + 0, + 0, + 0); + + // Feed forward constant added on to the small translational PIDF + public static double secondaryTranslationalPIDFFeedForward = 0.015; + + + // the limit at which the heading PIDF switches between the main and secondary heading PIDFs + public static double headingPIDFSwitch = Math.PI/20; + + // Secondary heading error PIDF coefficients + public static CustomPIDFCoefficients secondaryHeadingPIDFCoefficients = new CustomPIDFCoefficients( + 5, + 0, + 0.08, + 0); + + // Feed forward constant added on to the secondary heading PIDF + public static double secondaryHeadingPIDFFeedForward = 0.01; + + + // the limit at which the heading PIDF switches between the main and secondary drive PIDFs + public static double drivePIDFSwitch = 20; + + // Secondary drive PIDF coefficients + public static CustomFilteredPIDFCoefficients secondaryDrivePIDFCoefficients = new CustomFilteredPIDFCoefficients( + 0.02, + 0, + 0.000005, + 0.6, + 0); + + // Feed forward constant added on to the secondary drive PIDF + public static double secondaryDrivePIDFFeedForward = 0.01; +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardVelocityTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardVelocityTuner.java new file mode 100644 index 0000000..e97f78a --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardVelocityTuner.java @@ -0,0 +1,152 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.tuning; + +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.PoseUpdater; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; + +import java.util.ArrayList; +import java.util.Arrays; +import java.util.List; + +/** + * This is the ForwardVelocityTuner autonomous tuning OpMode. This runs the robot forwards at max + * power until it reaches some specified distance. It records the most recent velocities, and on + * reaching the end of the distance, it averages them and prints out the velocity obtained. It is + * recommended to run this multiple times on a full battery to get the best results. What this does + * is, when paired with StrafeVelocityTuner, allows FollowerConstants to create a Vector that + * empirically represents the direction your mecanum wheels actually prefer to go in, allowing for + * more accurate following. + * You can adjust the distance the robot will travel on FTC Dashboard: 192/168/43/1:8080/dash + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/13/2024 + */ +@Config +@Autonomous (name = "Forward Velocity Tuner", group = "Autonomous Pathing Tuning") +public class ForwardVelocityTuner extends OpMode { + private ArrayList velocities = new ArrayList<>(); + + private DcMotorEx leftFront; + private DcMotorEx leftRear; + private DcMotorEx rightFront; + private DcMotorEx rightRear; + private List motors; + + private PoseUpdater poseUpdater; + + public static double DISTANCE = 40; + public static double RECORD_NUMBER = 10; + + private Telemetry telemetryA; + + private boolean end; + + /** + * This initializes the drive motors as well as the cache of velocities and the FTC Dashboard + * telemetry. + */ + @Override + public void init() { + poseUpdater = new PoseUpdater(hardwareMap); + + leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName); + leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName); + rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName); + rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName); + + // TODO: Make sure that this is the direction your motors need to be reversed in. + leftFront.setDirection(DcMotorSimple.Direction.REVERSE); + leftRear.setDirection(DcMotorSimple.Direction.REVERSE); + + motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear); + + for (DcMotorEx motor : motors) { + MotorConfigurationType motorConfigurationType = motor.getMotorType().clone(); + motorConfigurationType.setAchieveableMaxRPMFraction(1.0); + motor.setMotorType(motorConfigurationType); + } + + for (DcMotorEx motor : motors) { + motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); + } + + for (int i = 0; i < RECORD_NUMBER; i++) { + velocities.add(0.0); + } + + telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); + telemetryA.addLine("The robot will run at 1 power until it reaches " + DISTANCE + " inches forward."); + telemetryA.addLine("Make sure you have enough room, since the robot has inertia after cutting power."); + telemetryA.addLine("After running the distance, the robot will cut power from the drivetrain and display the forward velocity."); + telemetryA.addLine("Press CROSS or A on game pad 1 to stop."); + telemetryA.update(); + + } + + /** + * This starts the OpMode by setting the drive motors to run forward at full power. + */ + @Override + public void start() { + leftFront.setPower(1); + leftRear.setPower(1); + rightFront.setPower(1); + rightRear.setPower(1); + end = false; + } + + /** + * This runs the OpMode. At any point during the running of the OpMode, pressing CROSS or A on + * game pad 1 will stop the OpMode. This continuously records the RECORD_NUMBER most recent + * velocities, and when the robot has run forward enough, these last velocities recorded are + * averaged and printed. + */ + @Override + public void loop() { + if (gamepad1.cross || gamepad1.a) { + requestOpModeStop(); + } + + poseUpdater.update(); + if (!end) { + if (Math.abs(poseUpdater.getPose().getX()) > DISTANCE) { + end = true; + for (DcMotorEx motor : motors) { + motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); + motor.setPower(0); + } + } else { + double currentVelocity = Math.abs(MathFunctions.dotProduct(poseUpdater.getVelocity(), new Vector(1, 0))); + velocities.add(currentVelocity); + velocities.remove(0); + } + } else { + double average = 0; + for (Double velocity : velocities) { + average += velocity; + } + average /= (double) velocities.size(); + + telemetryA.addData("forward velocity:", average); + telemetryA.update(); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardZeroPowerAccelerationTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardZeroPowerAccelerationTuner.java new file mode 100644 index 0000000..9454e13 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardZeroPowerAccelerationTuner.java @@ -0,0 +1,158 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.tuning; + +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.PoseUpdater; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; + +import java.util.ArrayList; +import java.util.Arrays; +import java.util.List; + +/** + * This is the ForwardZeroPowerAccelerationTuner autonomous tuning OpMode. This runs the robot + * forward until a specified velocity is achieved. Then, the robot cuts power to the motors, setting + * them to zero power. The deceleration, or negative acceleration, is then measured until the robot + * stops. The accelerations across the entire time the robot is slowing down is then averaged and + * that number is then printed. This is used to determine how the robot will decelerate in the + * forward direction when power is cut, making the estimations used in the calculations for the + * drive Vector more accurate and giving better braking at the end of Paths. + * You can adjust the max velocity the robot will hit on FTC Dashboard: 192/168/43/1:8080/dash + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/13/2024 + */ +@Config +@Autonomous (name = "Forward Zero Power Acceleration Tuner", group = "Autonomous Pathing Tuning") +public class ForwardZeroPowerAccelerationTuner extends OpMode { + private ArrayList accelerations = new ArrayList<>(); + + private DcMotorEx leftFront; + private DcMotorEx leftRear; + private DcMotorEx rightFront; + private DcMotorEx rightRear; + private List motors; + + private PoseUpdater poseUpdater; + + public static double VELOCITY = 30; + + private double previousVelocity; + + private long previousTimeNano; + + private Telemetry telemetryA; + + private boolean stopping; + private boolean end; + + /** + * This initializes the drive motors as well as the FTC Dashboard telemetry. + */ + @Override + public void init() { + poseUpdater = new PoseUpdater(hardwareMap); + + leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName); + leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName); + rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName); + rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName); + + // TODO: Make sure that this is the direction your motors need to be reversed in. + leftFront.setDirection(DcMotorSimple.Direction.REVERSE); + leftRear.setDirection(DcMotorSimple.Direction.REVERSE); + + motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear); + + for (DcMotorEx motor : motors) { + MotorConfigurationType motorConfigurationType = motor.getMotorType().clone(); + motorConfigurationType.setAchieveableMaxRPMFraction(1.0); + motor.setMotorType(motorConfigurationType); + } + + for (DcMotorEx motor : motors) { + motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); + } + + telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); + telemetryA.addLine("The robot will run forward until it reaches " + VELOCITY + " inches per second."); + telemetryA.addLine("Then, it will cut power from the drivetrain and roll to a stop."); + telemetryA.addLine("Make sure you have enough room."); + telemetryA.addLine("After stopping, the forward zero power acceleration (natural deceleration) will be displayed."); + telemetryA.addLine("Press CROSS or A on game pad 1 to stop."); + telemetryA.update(); + } + + /** + * This starts the OpMode by setting the drive motors to run forward at full power. + */ + @Override + public void start() { + leftFront.setPower(1); + leftRear.setPower(1); + rightFront.setPower(1); + rightRear.setPower(1); + } + + /** + * This runs the OpMode. At any point during the running of the OpMode, pressing CROSS or A on + * game pad 1 will stop the OpMode. When the robot hits the specified velocity, the robot will + * record its deceleration / negative acceleration until it stops. Then, it will average all the + * recorded deceleration / negative acceleration and print that value. + */ + @Override + public void loop() { + if (gamepad1.cross || gamepad1.a) { + requestOpModeStop(); + } + + poseUpdater.update(); + Vector heading = new Vector(1.0, poseUpdater.getPose().getHeading()); + if (!end) { + if (!stopping) { + if (MathFunctions.dotProduct(poseUpdater.getVelocity(), heading) > VELOCITY) { + previousVelocity = MathFunctions.dotProduct(poseUpdater.getVelocity(), heading); + previousTimeNano = System.nanoTime(); + stopping = true; + for (DcMotorEx motor : motors) { + motor.setPower(0); + } + } + } else { + double currentVelocity = MathFunctions.dotProduct(poseUpdater.getVelocity(), heading); + accelerations.add((currentVelocity - previousVelocity) / ((System.nanoTime() - previousTimeNano) / Math.pow(10.0, 9))); + previousVelocity = currentVelocity; + previousTimeNano = System.nanoTime(); + if (currentVelocity < FollowerConstants.pathEndVelocityConstraint) { + end = true; + } + } + } else { + double average = 0; + for (Double acceleration : accelerations) { + average += acceleration; + } + average /= (double)accelerations.size(); + + telemetryA.addData("forward zero power acceleration (deceleration):", average); + telemetryA.update(); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/LateralZeroPowerAccelerationTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/LateralZeroPowerAccelerationTuner.java new file mode 100644 index 0000000..505245d --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/LateralZeroPowerAccelerationTuner.java @@ -0,0 +1,158 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.tuning; + +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.PoseUpdater; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; + +import java.util.ArrayList; +import java.util.Arrays; +import java.util.List; + +/** + * This is the LateralZeroPowerAccelerationTuner autonomous tuning OpMode. This runs the robot + * to the right until a specified velocity is achieved. Then, the robot cuts power to the motors, setting + * them to zero power. The deceleration, or negative acceleration, is then measured until the robot + * stops. The accelerations across the entire time the robot is slowing down is then averaged and + * that number is then printed. This is used to determine how the robot will decelerate in the + * forward direction when power is cut, making the estimations used in the calculations for the + * drive Vector more accurate and giving better braking at the end of Paths. + * You can adjust the max velocity the robot will hit on FTC Dashboard: 192/168/43/1:8080/dash + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/13/2024 + */ +@Config +@Autonomous (name = "Lateral Zero Power Acceleration Tuner", group = "Autonomous Pathing Tuning") +public class LateralZeroPowerAccelerationTuner extends OpMode { + private ArrayList accelerations = new ArrayList<>(); + + private DcMotorEx leftFront; + private DcMotorEx leftRear; + private DcMotorEx rightFront; + private DcMotorEx rightRear; + private List motors; + + private PoseUpdater poseUpdater; + + public static double VELOCITY = 30; + + private double previousVelocity; + + private long previousTimeNano; + + private Telemetry telemetryA; + + private boolean stopping; + private boolean end; + + /** + * This initializes the drive motors as well as the FTC Dashboard telemetry. + */ + @Override + public void init() { + poseUpdater = new PoseUpdater(hardwareMap); + + leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName); + leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName); + rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName); + rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName); + + // TODO: Make sure that this is the direction your motors need to be reversed in. + leftFront.setDirection(DcMotorSimple.Direction.REVERSE); + leftRear.setDirection(DcMotorSimple.Direction.REVERSE); + + motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear); + + for (DcMotorEx motor : motors) { + MotorConfigurationType motorConfigurationType = motor.getMotorType().clone(); + motorConfigurationType.setAchieveableMaxRPMFraction(1.0); + motor.setMotorType(motorConfigurationType); + } + + for (DcMotorEx motor : motors) { + motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); + } + + telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); + telemetryA.addLine("The robot will run to the right until it reaches " + VELOCITY + " inches per second."); + telemetryA.addLine("Then, it will cut power from the drivetrain and roll to a stop."); + telemetryA.addLine("Make sure you have enough room."); + telemetryA.addLine("After stopping, the lateral zero power acceleration (natural deceleration) will be displayed."); + telemetryA.addLine("Press CROSS or A on game pad 1 to stop."); + telemetryA.update(); + } + + /** + * This starts the OpMode by setting the drive motors to run forward at full power. + */ + @Override + public void start() { + leftFront.setPower(1); + leftRear.setPower(-1); + rightFront.setPower(-1); + rightRear.setPower(1); + } + + /** + * This runs the OpMode. At any point during the running of the OpMode, pressing CROSS or A on + * game pad 1 will stop the OpMode. When the robot hits the specified velocity, the robot will + * record its deceleration / negative acceleration until it stops. Then, it will average all the + * recorded deceleration / negative acceleration and print that value. + */ + @Override + public void loop() { + if (gamepad1.cross || gamepad1.a) { + requestOpModeStop(); + } + + poseUpdater.update(); + Vector heading = new Vector(1.0, poseUpdater.getPose().getHeading() - Math.PI/2); + if (!end) { + if (!stopping) { + if (MathFunctions.dotProduct(poseUpdater.getVelocity(), heading) > VELOCITY) { + previousVelocity = MathFunctions.dotProduct(poseUpdater.getVelocity(), heading); + previousTimeNano = System.nanoTime(); + stopping = true; + for (DcMotorEx motor : motors) { + motor.setPower(0); + } + } + } else { + double currentVelocity = MathFunctions.dotProduct(poseUpdater.getVelocity(), heading); + accelerations.add((currentVelocity - previousVelocity) / ((System.nanoTime() - previousTimeNano) / Math.pow(10.0, 9))); + previousVelocity = currentVelocity; + previousTimeNano = System.nanoTime(); + if (currentVelocity < FollowerConstants.pathEndVelocityConstraint) { + end = true; + } + } + } else { + double average = 0; + for (Double acceleration : accelerations) { + average += acceleration; + } + average /= (double)accelerations.size(); + + telemetryA.addData("lateral zero power acceleration (deceleration):", average); + telemetryA.update(); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/StrafeVelocityTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/StrafeVelocityTuner.java new file mode 100644 index 0000000..acd90c0 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/StrafeVelocityTuner.java @@ -0,0 +1,150 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.tuning; + +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.leftRearMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightFrontMotorName; +import static org.firstinspires.ftc.teamcode.pedroPathing.tuning.FollowerConstants.rightRearMotorName; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.DcMotorSimple; +import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.PoseUpdater; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; + +import java.util.ArrayList; +import java.util.Arrays; +import java.util.List; + +/** + * This is the StrafeVelocityTuner autonomous tuning OpMode. This runs the robot right at max + * power until it reaches some specified distance. It records the most recent velocities, and on + * reaching the end of the distance, it averages them and prints out the velocity obtained. It is + * recommended to run this multiple times on a full battery to get the best results. What this does + * is, when paired with ForwardVelocityTuner, allows FollowerConstants to create a Vector that + * empirically represents the direction your mecanum wheels actually prefer to go in, allowing for + * more accurate following. + * You can adjust the distance the robot will travel on FTC Dashboard: 192/168/43/1:8080/dash + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/13/2024 + */ +@Config +@Autonomous (name = "Strafe Velocity Tuner", group = "Autonomous Pathing Tuning") +public class StrafeVelocityTuner extends OpMode { + private ArrayList velocities = new ArrayList<>(); + + private DcMotorEx leftFront; + private DcMotorEx leftRear; + private DcMotorEx rightFront; + private DcMotorEx rightRear; + private List motors; + + private PoseUpdater poseUpdater; + + public static double DISTANCE = 40; + public static double RECORD_NUMBER = 10; + + private Telemetry telemetryA; + + private boolean end; + + /** + * This initializes the drive motors as well as the cache of velocities and the FTC Dashboard + * telemetry. + */ + @Override + public void init() { + poseUpdater = new PoseUpdater(hardwareMap); + + leftFront = hardwareMap.get(DcMotorEx.class, leftFrontMotorName); + leftRear = hardwareMap.get(DcMotorEx.class, leftRearMotorName); + rightRear = hardwareMap.get(DcMotorEx.class, rightRearMotorName); + rightFront = hardwareMap.get(DcMotorEx.class, rightFrontMotorName); + + // TODO: Make sure that this is the direction your motors need to be reversed in. + leftFront.setDirection(DcMotorSimple.Direction.REVERSE); + leftRear.setDirection(DcMotorSimple.Direction.REVERSE); + + motors = Arrays.asList(leftFront, leftRear, rightFront, rightRear); + + for (DcMotorEx motor : motors) { + MotorConfigurationType motorConfigurationType = motor.getMotorType().clone(); + motorConfigurationType.setAchieveableMaxRPMFraction(1.0); + motor.setMotorType(motorConfigurationType); + } + + for (DcMotorEx motor : motors) { + motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.FLOAT); + } + + for (int i = 0; i < RECORD_NUMBER; i++) { + velocities.add(0.0); + } + + telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); + telemetryA.addLine("The robot will run at 1 power until it reaches " + DISTANCE + " inches to the right."); + telemetryA.addLine("Make sure you have enough room, since the robot has inertia after cutting power."); + telemetryA.addLine("After running the distance, the robot will cut power from the drivetrain and display the strafe velocity."); + telemetryA.addLine("Press CROSS or A on game pad 1 to stop."); + telemetryA.update(); + } + + /** + * This starts the OpMode by setting the drive motors to run right at full power. + */ + @Override + public void start() { + leftFront.setPower(1); + leftRear.setPower(-1); + rightFront.setPower(-1); + rightRear.setPower(1); + } + + /** + * This runs the OpMode. At any point during the running of the OpMode, pressing CROSS or A on + * game pad1 will stop the OpMode. This continuously records the RECORD_NUMBER most recent + * velocities, and when the robot has run sideways enough, these last velocities recorded are + * averaged and printed. + */ + @Override + public void loop() { + if (gamepad1.cross || gamepad1.a) { + requestOpModeStop(); + } + + poseUpdater.update(); + if (!end) { + if (Math.abs(poseUpdater.getPose().getY()) > DISTANCE) { + end = true; + for (DcMotorEx motor : motors) { + motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); + motor.setPower(0); + } + } else { + double currentVelocity = Math.abs(MathFunctions.dotProduct(poseUpdater.getVelocity(), new Vector(1, Math.PI/2))); + velocities.add(currentVelocity); + velocities.remove(0); + } + } else { + double average = 0; + for (Double velocity : velocities) { + average += velocity; + } + average /= (double) velocities.size(); + + telemetryA.addData("strafe velocity:", average); + telemetryA.update(); + } + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/StraightBackAndForth.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/StraightBackAndForth.java new file mode 100644 index 0000000..6224a92 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/StraightBackAndForth.java @@ -0,0 +1,84 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.tuning; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.config.Config; +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.qualcomm.robotcore.eventloop.opmode.Autonomous; +import com.qualcomm.robotcore.eventloop.opmode.OpMode; + +import org.firstinspires.ftc.robotcore.external.Telemetry; +import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierLine; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Path; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point; + +/** + * This is the StraightBackAndForth autonomous OpMode. It runs the robot in a specified distance + * straight forward. On reaching the end of the forward Path, the robot runs the backward Path the + * same distance back to the start. Rinse and repeat! This is good for testing a variety of Vectors, + * like the drive Vector, the translational Vector, and the heading Vector. Remember to test your + * tunings on CurvedBackAndForth as well, since tunings that work well for straight lines might + * have issues going in curves. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/12/2024 + */ +@Config +@Autonomous (name = "Straight Back And Forth", group = "Autonomous Pathing Tuning") +public class StraightBackAndForth extends OpMode { + private Telemetry telemetryA; + + public static double DISTANCE = 40; + + private boolean forward = true; + + private Follower follower; + + private Path forwards; + private Path backwards; + + /** + * This initializes the Follower and creates the forward and backward Paths. Additionally, this + * initializes the FTC Dashboard telemetry. + */ + @Override + public void init() { + follower = new Follower(hardwareMap); + + forwards = new Path(new BezierLine(new Point(0,0, Point.CARTESIAN), new Point(DISTANCE,0, Point.CARTESIAN))); + forwards.setConstantHeadingInterpolation(0); + backwards = new Path(new BezierLine(new Point(DISTANCE,0, Point.CARTESIAN), new Point(0,0, Point.CARTESIAN))); + backwards.setConstantHeadingInterpolation(0); + + follower.followPath(forwards); + + telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry()); + telemetryA.addLine("This will run the robot in a straight line going " + DISTANCE + + " inches forward. The robot will go forward and backward continuously" + + " along the path. Make sure you have enough room."); + telemetryA.update(); + } + + /** + * This runs the OpMode, updating the Follower as well as printing out the debug statements to + * the Telemetry, as well as the FTC Dashboard. + */ + @Override + public void loop() { + follower.update(); + if (!follower.isBusy()) { + if (forward) { + forward = false; + follower.followPath(backwards); + } else { + forward = true; + follower.followPath(forwards); + } + } + + telemetryA.addData("going forward", forward); + follower.telemetryDebug(telemetryA); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/CustomFilteredPIDFCoefficients.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/CustomFilteredPIDFCoefficients.java new file mode 100644 index 0000000..0b02174 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/CustomFilteredPIDFCoefficients.java @@ -0,0 +1,70 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +import kotlin.jvm.JvmField; + +/** + * This is the CustomFilteredPIDFCoefficients class. This class handles holding coefficients for filtered PIDF + * controllers. + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 7/15/2024 + */ +public class CustomFilteredPIDFCoefficients { + @JvmField public double P; + @JvmField public double I; + @JvmField public double D; + @JvmField public double T; + @JvmField public double F; + + public FeedForwardConstant feedForwardConstantEquation; + + private boolean usingEquation; + + /** + * This creates a new CustomFilteredPIDFCoefficients with constant coefficients. + * + * @param p the coefficient for the proportional factor. + * @param i the coefficient for the integral factor. + * @param d the coefficient for the derivative factor. + * @param t the time constant for the filter + * @param f the coefficient for the feedforward factor. + */ + public CustomFilteredPIDFCoefficients(double p, double i, double d, double t, double f) { + P = p; + I = i; + D = d; + T = t; + F = f; + } + + /** + * This creates a new CustomFilteredPIDFCoefficients with constant PID coefficients and a variable + * feedforward equation using a FeedForwardConstant. + * + * @param p the coefficient for the proportional factor. + * @param i the coefficient for the integral factor. + * @param d the coefficient for the derivative factor. + * @param t the time constant for the filter + * @param f the equation for the feedforward factor. + */ + public CustomFilteredPIDFCoefficients(double p, double i, double d, double t, FeedForwardConstant f) { + usingEquation = true; + P = p; + I = i; + D = d; + T = t; + feedForwardConstantEquation = f; + } + + /** + * This returns the coefficient for the feedforward factor. + * + * @param input this is inputted into the feedforward equation, if applicable. If there's no + * equation, then any input can be used. + * @return This returns the coefficient for the feedforward factor. + */ + public double getCoefficient(double input) { + if (!usingEquation) return F; + return feedForwardConstantEquation.getConstant(input); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/CustomPIDFCoefficients.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/CustomPIDFCoefficients.java new file mode 100644 index 0000000..65a783a --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/CustomPIDFCoefficients.java @@ -0,0 +1,67 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +import kotlin.jvm.JvmField; + +/** + * This is the CustomPIDFCoefficients class. This class handles holding coefficients for PIDF + * controllers. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/5/2024 + */ +public class CustomPIDFCoefficients { + @JvmField public double P; + @JvmField public double I; + @JvmField public double D; + @JvmField public double F; + + public FeedForwardConstant feedForwardConstantEquation; + + private boolean usingEquation; + + /** + * This creates a new CustomPIDFCoefficients with constant coefficients. + * + * @param p the coefficient for the proportional factor. + * @param i the coefficient for the integral factor. + * @param d the coefficient for the derivative factor. + * @param f the coefficient for the feedforward factor. + */ + public CustomPIDFCoefficients(double p, double i, double d, double f) { + P = p; + I = i; + D = d; + F = f; + } + + /** + * This creates a new CustomPIDFCoefficients with constant PID coefficients and a variable + * feedforward equation using a FeedForwardConstant. + * + * @param p the coefficient for the proportional factor. + * @param i the coefficient for the integral factor. + * @param d the coefficient for the derivative factor. + * @param f the equation for the feedforward factor. + */ + public CustomPIDFCoefficients(double p, double i, double d, FeedForwardConstant f) { + usingEquation = true; + P = p; + I = i; + D = d; + feedForwardConstantEquation = f; + } + + /** + * This returns the coefficient for the feedforward factor. + * + * @param input this is inputted into the feedforward equation, if applicable. If there's no + * equation, then any input can be used. + * @return This returns the coefficient for the feedforward factor. + */ + public double getCoefficient(double input) { + if (!usingEquation) return F; + return feedForwardConstantEquation.getConstant(input); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/DashboardPoseTracker.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/DashboardPoseTracker.java new file mode 100644 index 0000000..3c54156 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/DashboardPoseTracker.java @@ -0,0 +1,76 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.PoseUpdater; + +import java.util.ArrayList; + +/** + * This is the DashboardPoseTracker class. This tracks the pose history of the robot through a + * PoseUpdater, adding to the pose history at specified increments of time and storing the history + * for a specified length of time. + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 5/13/2024 + */ +public class DashboardPoseTracker { + private double[] xPositions; + private double[] yPositions; + private PoseUpdater poseUpdater; + private long lastUpdateTime; + private final int TRACKING_LENGTH = 1500; + private final long UPDATE_TIME = 50; + private final int TRACKING_SIZE = TRACKING_LENGTH / (int) UPDATE_TIME; + + /** + * This creates a new DashboardPoseTracker from a PoseUpdater. + * + * @param poseUpdater the PoseUpdater + */ + public DashboardPoseTracker(PoseUpdater poseUpdater) { + this.poseUpdater = poseUpdater; + xPositions = new double[TRACKING_SIZE]; + yPositions = new double[TRACKING_SIZE]; + + for (int i = 0; i < TRACKING_SIZE; i++) { + xPositions[i] = poseUpdater.getPose().getX(); + yPositions[i] = poseUpdater.getPose().getY(); + } + + lastUpdateTime = System.currentTimeMillis() - UPDATE_TIME; + } + + /** + * This updates the DashboardPoseTracker. When the specified update time has passed from the last + * pose history log, another pose can be logged. The least recent log is also removed. + */ + public void update() { + if (System.currentTimeMillis() - lastUpdateTime > UPDATE_TIME) { + lastUpdateTime = System.currentTimeMillis(); + for (int i = TRACKING_SIZE - 1; i > 0; i--) { + xPositions[i] = xPositions[i - 1]; + yPositions[i] = yPositions[i - 1]; + } + xPositions[0] = poseUpdater.getPose().getX(); + yPositions[0] = poseUpdater.getPose().getY(); + } + } + + /** + * This returns the x positions of the pose history as an Array of doubles. + * + * @return returns the x positions of the pose history + */ + public double[] getXPositionsArray() { + return xPositions; + } + + /** + * This returns the y positions of the pose history as an Array of doubles. + * + * @return returns the y positions of the pose history + */ + public double[] getYPositionsArray() { + return yPositions; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/Drawing.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/Drawing.java new file mode 100644 index 0000000..9a2d956 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/Drawing.java @@ -0,0 +1,155 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +import com.acmerobotics.dashboard.FtcDashboard; +import com.acmerobotics.dashboard.canvas.Canvas; +import com.acmerobotics.dashboard.telemetry.TelemetryPacket; + +import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower; +import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Path; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point; +import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector; + +/** + * This is the Drawing class. It handles the drawing of stuff on FTC Dashboard, like the robot. + * + * @author Logan Nash + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 4/22/2024 + */ +public class Drawing { + private static TelemetryPacket packet; + + /** + * This draws everything that will be used in the Follower's telemetryDebug() method. This takes + * a Follower as an input, so an instance of the DashbaordDrawingHandler class is not needed. + * @param follower + */ + public static void drawDebug(Follower follower) { + if (follower.getCurrentPath() != null) { + drawPath(follower.getCurrentPath(), "#3F51B5"); + Point closestPoint = follower.getPointFromPath(follower.getCurrentPath().getClosestPointTValue()); + drawRobot(new Pose(closestPoint.getX(), closestPoint.getY(), follower.getCurrentPath().getHeadingGoal(follower.getCurrentPath().getClosestPointTValue())), "#3F51B5"); + } + drawPoseHistory(follower.getDashboardPoseTracker(), "#4CAF50"); + drawRobot(follower.getPose(), "#4CAF50"); + sendPacket(); + } + + /** + * This adds instructions to the current packet to draw a robot at a specified Pose with a specified + * color. If no packet exists, then a new one is created. + * + * @param pose the Pose to draw the robot at + * @param color the color to draw the robot with + */ + public static void drawRobot(Pose pose, String color) { + if (packet == null) packet = new TelemetryPacket(); + + packet.fieldOverlay().setStroke(color); + Drawing.drawRobotOnCanvas(packet.fieldOverlay(), pose.copy()); + } + + /** + * This adds instructions to the current packet to draw a Path with a specified color. If no + * packet exists, then a new one is created. + * + * @param path the Path to draw + * @param color the color to draw the Path with + */ + public static void drawPath(Path path, String color) { + if (packet == null) packet = new TelemetryPacket(); + + packet.fieldOverlay().setStroke(color); + Drawing.drawPath(packet.fieldOverlay(), path.getDashboardDrawingPoints()); + } + + /** + * This adds instructions to the current packet to draw all the Paths in a PathChain with a + * specified color. If no packet exists, then a new one is created. + * + * @param pathChain the PathChain to draw + * @param color the color to draw the PathChain with + */ + public static void drawPath(PathChain pathChain, String color) { + for (int i = 0; i < pathChain.size(); i++) { + drawPath(pathChain.getPath(i), color); + } + } + + /** + * This adds instructions to the current packet to draw the pose history of the robot. If no + * packet exists, then a new one is created. + * + * @param poseTracker the DashboardPoseTracker to get the pose history from + * @param color the color to draw the pose history with + */ + public static void drawPoseHistory(DashboardPoseTracker poseTracker, String color) { + if (packet == null) packet = new TelemetryPacket(); + + packet.fieldOverlay().setStroke(color); + packet.fieldOverlay().strokePolyline(poseTracker.getXPositionsArray(), poseTracker.getYPositionsArray()); + } + + /** + * This tries to send the current packet to FTC Dashboard. + * + * @return returns if the operation was successful. + */ + public static boolean sendPacket() { + if (packet != null) { + FtcDashboard.getInstance().sendTelemetryPacket(packet); + packet = null; + return true; + } + return false; + } + + /** + * This draws a robot on the Dashboard at a specified Point. + * + * @param c the Canvas on the Dashboard on which this will draw + * @param t the Point to draw at + */ + public static void drawRobotOnCanvas(Canvas c, Point t) { + final double ROBOT_RADIUS = 9; + + c.setStrokeWidth(1); + c.strokeCircle(t.getX(), t.getY(), ROBOT_RADIUS); + + Vector halfv = new Vector(0.5*ROBOT_RADIUS, t.getTheta()); + Vector p1 = MathFunctions.addVectors(halfv, new Vector(t.getR(), t.getTheta())); + Vector p2 = MathFunctions.addVectors(p1, halfv); + c.strokeLine(p1.getXComponent(), p1.getYComponent(), p2.getXComponent(), p2.getYComponent()); + } + + /** + * This draws a robot on the Dashboard at a specified Pose. This is more useful for drawing the + * actual robot, since the Pose contains the direction the robot is facing as well as its position. + * + * @param c the Canvas on the Dashboard on which this will draw + * @param t the Pose to draw at + */ + public static void drawRobotOnCanvas(Canvas c, Pose t) { + final double ROBOT_RADIUS = 9; + + c.strokeCircle(t.getX(), t.getY(), ROBOT_RADIUS); + Vector v = t.getHeadingVector(); + v.setMagnitude(v.getMagnitude() * ROBOT_RADIUS); + double x1 = t.getX() + v.getXComponent() / 2, y1 = t.getY() + v.getYComponent() / 2; + double x2 = t.getX() + v.getXComponent(), y2 = t.getY() + v.getYComponent(); + c.strokeLine(x1, y1, x2, y2); + } + + /** + * This draws a Path on the Dashboard from a specified Array of Points. + * + * @param c the Canvas on the Dashboard on which this will draw + * @param points the Points to draw + */ + public static void drawPath(Canvas c, double[][] points) { + c.strokePolyline(points[0], points[1]); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/FeedForwardConstant.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/FeedForwardConstant.java new file mode 100644 index 0000000..0085e7c --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/FeedForwardConstant.java @@ -0,0 +1,21 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +/** + * This is the FeedForwardConstant interface. This interface holds a feedforward equation for PIDFs. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/5/2024 + */ +public interface FeedForwardConstant { + + /** + * This returns the coefficient for the feedforward factor. + * + * @param input this is inputted into the feedforward equation, if applicable. If there's no + * equation, then any input can be used. + * @return This returns the coefficient for the feedforward factor. + */ + double getConstant(double input); +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/FilteredPIDFController.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/FilteredPIDFController.java new file mode 100644 index 0000000..07747fe --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/FilteredPIDFController.java @@ -0,0 +1,245 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +/** + * This is the FilteredPIDFController class. This class handles the running of filtered filtered PIDFs. This + * behaves very similarly to a regular filtered PIDF controller, but the derivative portion is filtered with + * a low pass filter to reduce high frequency noise that could affect results. + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 7/15/2024 + */ +public class FilteredPIDFController { + private CustomFilteredPIDFCoefficients coefficients; + + private double previousError; + private double error; + private double position; + private double targetPosition; + private double errorIntegral; + private double errorDerivative; + private double previousDerivative; + private double filteredDerivative; + private double feedForwardInput; + + private long previousUpdateTimeNano; + private long deltaTimeNano; + + /** + * This creates a new filtered PIDFController from a CustomPIDFCoefficients. + * + * @param set the coefficients to use. + */ + public FilteredPIDFController(CustomFilteredPIDFCoefficients set) { + setCoefficients(set); + reset(); + } + + /** + * This takes the current error and runs the filtered PIDF on it. + * + * @return this returns the value of the filtered PIDF from the current error. + */ + public double runPIDF() { + return error * P() + filteredDerivative * D() + errorIntegral * I() + F(); + } + + /** + * This can be used to update the filtered PIDF's current position when inputting a current position and + * a target position to calculate error. This will update the error from the current position to + * the target position specified. + * + * @param update This is the current position. + */ + public void updatePosition(double update) { + position = update; + previousError = error; + error = targetPosition - position; + + deltaTimeNano = System.nanoTime() - previousUpdateTimeNano; + previousUpdateTimeNano = System.nanoTime(); + + errorIntegral += error * (deltaTimeNano / Math.pow(10.0, 9)); + previousDerivative = filteredDerivative; + errorDerivative = (error - previousError) / (deltaTimeNano / Math.pow(10.0, 9)); + filteredDerivative = T() * previousDerivative + (1 - T()) * errorDerivative; + } + + /** + * As opposed to updating position against a target position, this just sets the error to some + * specified value. + * + * @param error The error specified. + */ + public void updateError(double error) { + previousError = this.error; + this.error = error; + + deltaTimeNano = System.nanoTime() - previousUpdateTimeNano; + previousUpdateTimeNano = System.nanoTime(); + + errorIntegral += error * (deltaTimeNano / Math.pow(10.0, 9)); + previousDerivative = errorDerivative; + errorDerivative = (error - previousError) / (deltaTimeNano / Math.pow(10.0, 9)); + filteredDerivative = T() * previousDerivative + (1 - T()) * errorDerivative; + } + + /** + * This can be used to update the feedforward equation's input, if applicable. + * + * @param input the input into the feedforward equation. + */ + public void updateFeedForwardInput(double input) { + feedForwardInput = input; + } + + /** + * This resets all the filtered PIDF's error and position values, as well as the time stamps. + */ + public void reset() { + previousError = 0; + error = 0; + position = 0; + targetPosition = 0; + errorIntegral = 0; + errorDerivative = 0; + previousDerivative = 0; + filteredDerivative = 0; + previousUpdateTimeNano = System.nanoTime(); + } + + /** + * This is used to set the target position if the filtered PIDF is being run with current position and + * target position inputs rather than error inputs. + * + * @param set this sets the target position. + */ + public void setTargetPosition(double set) { + targetPosition = set; + } + + /** + * This returns the target position of the filtered PIDF. + * + * @return this returns the target position. + */ + public double getTargetPosition() { + return targetPosition; + } + + /** + * This is used to set the coefficients of the filtered PIDF. + * + * @param set the coefficients that the filtered PIDF will use. + */ + public void setCoefficients(CustomFilteredPIDFCoefficients set) { + coefficients = set; + } + + /** + * This returns the filtered PIDF's current coefficients. + * + * @return this returns the current coefficients. + */ + public CustomFilteredPIDFCoefficients getCoefficients() { + return coefficients; + } + + /** + * This sets the proportional (P) coefficient of the filtered PIDF only. + * + * @param set this sets the P coefficient. + */ + public void setP(double set) { + coefficients.P = set; + } + + /** + * This returns the proportional (P) coefficient of the filtered PIDF. + * + * @return this returns the P coefficient. + */ + public double P() { + return coefficients.P; + } + + /** + * This sets the integral (I) coefficient of the filtered PIDF only. + * + * @param set this sets the I coefficient. + */ + public void setI(double set) { + coefficients.I = set; + } + + /** + * This returns the integral (I) coefficient of the filtered PIDF. + * + * @return this returns the I coefficient. + */ + public double I() { + return coefficients.I; + } + + /** + * This sets the derivative (D) coefficient of the filtered PIDF only. + * + * @param set this sets the D coefficient. + */ + public void setD(double set) { + coefficients.D = set; + } + + /** + * This returns the derivative (D) coefficient of the filtered PIDF. + * + * @return this returns the D coefficient. + */ + public double D() { + return coefficients.D; + } + + /** + * This sets the time constant (T) of the filtered PIDF only. + * + * @param set this sets the time constant. + */ + public void setT(double set) { + coefficients.T = set; + } + + /** + * This returns the time constant (T) of the filtered PIDF. + * + * @return this returns the time constant. + */ + public double T() { + return coefficients.T; + } + + /** + * This sets the feedforward (F) constant of the filtered PIDF only. + * + * @param set this sets the F constant. + */ + public void setF(double set) { + coefficients.F = set; + } + + /** + * This returns the feedforward (F) constant of the filtered PIDF. + * + * @return this returns the F constant. + */ + public double F() { + return coefficients.getCoefficient(feedForwardInput); + } + + /** + * This returns the current error of the filtered PIDF. + * + * @return this returns the error. + */ + public double getError() { + return error; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/KalmanFilter.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/KalmanFilter.java new file mode 100644 index 0000000..41aa630 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/KalmanFilter.java @@ -0,0 +1,62 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +import com.acmerobotics.dashboard.config.Config; + +import org.firstinspires.ftc.robotcore.external.Telemetry; + +/** + * This is the KalmanFilter class. This creates a Kalman filter that is used to smooth out data. + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 7/17/2024 + */ +public class KalmanFilter { + private KalmanFilterParameters parameters; + private double state; + private double variance; + private double kalmanGain; + private double previousState; + private double previousVariance; + + public KalmanFilter(KalmanFilterParameters parameters) { + this.parameters = parameters; + reset(); + } + + public KalmanFilter(KalmanFilterParameters parameters, double startState, double startVariance, double startGain) { + this.parameters = parameters; + reset(startState, startVariance, startGain); + } + + public void reset(double startState, double startVariance, double startGain) { + state = startState; + previousState = startState; + variance = startVariance; + previousVariance = startVariance; + kalmanGain = startGain; + } + + public void reset() { + reset(0, 1, 1); + } + + public void update(double updateData, double updateProjection) { + state = previousState + updateData; + variance = previousVariance + parameters.modelCovariance; + kalmanGain = variance / (variance + parameters.dataCovariance); + state += kalmanGain * (updateProjection - state); + variance *= (1.0 - kalmanGain); + previousState = state; + previousVariance = variance; + } + + public double getState() { + return state; + } + + public void debug(Telemetry telemetry) { + telemetry.addData("state", state); + telemetry.addData("variance", variance); + telemetry.addData("Kalman gain", kalmanGain); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/KalmanFilterParameters.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/KalmanFilterParameters.java new file mode 100644 index 0000000..e31260b --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/KalmanFilterParameters.java @@ -0,0 +1,25 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +import kotlin.jvm.JvmField; + +/** + * This is the KalmanFilterParameters class. This class handles holding parameters Kalman filters. + * + * @author Anyi Lin - 10158 Scott's Bots + * @version 1.0, 7/17/2024 + */ +public class KalmanFilterParameters { + @JvmField public double modelCovariance; + @JvmField public double dataCovariance; + + /** + * This creates a new KalmanFilterParameters with a specified model and data covariance. + * + * @param modelCovariance the covariance of the model. + * @param dataCovariance the covariance of the data. + */ + public KalmanFilterParameters(double modelCovariance, double dataCovariance) { + this.modelCovariance = modelCovariance; + this.dataCovariance = dataCovariance; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/NanoTimer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/NanoTimer.java new file mode 100644 index 0000000..6501093 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/NanoTimer.java @@ -0,0 +1,46 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +/** + * This is the NanoTimer class. It is an elapsed time clock with nanosecond precision, or at least + * as precise as the System.nanoTime() is. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/5/2024 + */ +public class NanoTimer { + private long startTime; + + /** + * This creates a new NanoTimer with the start time set to its creation time. + */ + public NanoTimer() { + resetTimer(); + } + + /** + * This resets the NanoTimer's start time to the current time using System.nanoTime(). + */ + public void resetTimer() { + startTime = System.nanoTime(); + } + + /** + * This returns the elapsed time in nanoseconds since the start time of the NanoTimer. + * + * @return this returns the elapsed time in nanoseconds. + */ + public long getElapsedTime() { + return System.nanoTime() - startTime; + } + + /** + * This returns the elapsed time in seconds since the start time of the NanoTimer. + * + * @return this returns the elapsed time in seconds. + */ + public double getElapsedTimeSeconds() { + return (getElapsedTime() / Math.pow(10.0,9)); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/PIDFController.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/PIDFController.java new file mode 100644 index 0000000..0b59050 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/PIDFController.java @@ -0,0 +1,223 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +/** + * This is the PIDFController class. This class handles the running of PIDFs. PIDF stands for + * proportional, integral, derivative, and feedforward. PIDFs take the error of a system as an input. + * Coefficients multiply into the error, the integral of the error, the derivative of the error, and + * a feedforward value. Then, these values are added up and returned. In this way, error in the + * system is corrected. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/5/2024 + */ +public class PIDFController { + private CustomPIDFCoefficients coefficients; + + private double previousError; + private double error; + private double position; + private double targetPosition; + private double errorIntegral; + private double errorDerivative; + private double feedForwardInput; + + private long previousUpdateTimeNano; + private long deltaTimeNano; + + /** + * This creates a new PIDFController from a CustomPIDFCoefficients. + * + * @param set the coefficients to use. + */ + public PIDFController(CustomPIDFCoefficients set) { + setCoefficients(set); + reset(); + } + + /** + * This takes the current error and runs the PIDF on it. + * + * @return this returns the value of the PIDF from the current error. + */ + public double runPIDF() { + return error * P() + errorDerivative * D() + errorIntegral * I() + F(); + } + + /** + * This can be used to update the PIDF's current position when inputting a current position and + * a target position to calculate error. This will update the error from the current position to + * the target position specified. + * + * @param update This is the current position. + */ + public void updatePosition(double update) { + position = update; + previousError = error; + error = targetPosition - position; + + deltaTimeNano = System.nanoTime() - previousUpdateTimeNano; + previousUpdateTimeNano = System.nanoTime(); + + errorIntegral += error * (deltaTimeNano / Math.pow(10.0, 9)); + errorDerivative = (error - previousError) / (deltaTimeNano / Math.pow(10.0, 9)); + } + + /** + * As opposed to updating position against a target position, this just sets the error to some + * specified value. + * + * @param error The error specified. + */ + public void updateError(double error) { + previousError = this.error; + this.error = error; + + deltaTimeNano = System.nanoTime() - previousUpdateTimeNano; + previousUpdateTimeNano = System.nanoTime(); + + errorIntegral += error * (deltaTimeNano / Math.pow(10.0, 9)); + errorDerivative = (error - previousError) / (deltaTimeNano / Math.pow(10.0, 9)); + } + + /** + * This can be used to update the feedforward equation's input, if applicable. + * + * @param input the input into the feedforward equation. + */ + public void updateFeedForwardInput(double input) { + feedForwardInput = input; + } + + /** + * This resets all the PIDF's error and position values, as well as the time stamps. + */ + public void reset() { + previousError = 0; + error = 0; + position = 0; + targetPosition = 0; + errorIntegral = 0; + errorDerivative = 0; + previousUpdateTimeNano = System.nanoTime(); + } + + /** + * This is used to set the target position if the PIDF is being run with current position and + * target position inputs rather than error inputs. + * + * @param set this sets the target position. + */ + public void setTargetPosition(double set) { + targetPosition = set; + } + + /** + * This returns the target position of the PIDF. + * + * @return this returns the target position. + */ + public double getTargetPosition() { + return targetPosition; + } + + /** + * This is used to set the coefficients of the PIDF. + * + * @param set the coefficients that the PIDF will use. + */ + public void setCoefficients(CustomPIDFCoefficients set) { + coefficients = set; + } + + /** + * This returns the PIDF's current coefficients. + * + * @return this returns the current coefficients. + */ + public CustomPIDFCoefficients getCoefficients() { + return coefficients; + } + + /** + * This sets the proportional (P) coefficient of the PIDF only. + * + * @param set this sets the P coefficient. + */ + public void setP(double set) { + coefficients.P = set; + } + + /** + * This returns the proportional (P) coefficient of the PIDF. + * + * @return this returns the P coefficient. + */ + public double P() { + return coefficients.P; + } + + /** + * This sets the integral (I) coefficient of the PIDF only. + * + * @param set this sets the I coefficient. + */ + public void setI(double set) { + coefficients.I = set; + } + + /** + * This returns the integral (I) coefficient of the PIDF. + * + * @return this returns the I coefficient. + */ + public double I() { + return coefficients.I; + } + + /** + * This sets the derivative (D) coefficient of the PIDF only. + * + * @param set this sets the D coefficient. + */ + public void setD(double set) { + coefficients.D = set; + } + + /** + * This returns the derivative (D) coefficient of the PIDF. + * + * @return this returns the D coefficient. + */ + public double D() { + return coefficients.D; + } + + /** + * This sets the feedforward (F) constant of the PIDF only. + * + * @param set this sets the F constant. + */ + public void setF(double set) { + coefficients.F = set; + } + + /** + * This returns the feedforward (F) constant of the PIDF. + * + * @return this returns the F constant. + */ + public double F() { + return coefficients.getCoefficient(feedForwardInput); + } + + /** + * This returns the current error of the PIDF. + * + * @return this returns the error. + */ + public double getError() { + return error; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/SingleRunAction.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/SingleRunAction.java new file mode 100644 index 0000000..48a5702 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/SingleRunAction.java @@ -0,0 +1,60 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +/** + * This is the SingleRunAction class. It handles running Runnables once, until a reset is called. + * It also forms the basis of the PathCallback class. Basically, if you want to run a certain action + * once despite looping through a section of code multiple times, then this is for you. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/6/2024 + */ +public class SingleRunAction { + private boolean hasBeenRun; + + private Runnable runnable; + + /** + * This creates a new SingleRunAction with a Runnable containing the code to be run for this action. + * The name is a slight bit misleading, as this can actually be run multiple times. However, the + * run() method only runs once before the reset() method needs to be called to allow the + * SingleRunAction to run again. + * + * @param runnable This is a Runnable containing the code to be run. Preferably, use lambda statements. + */ + public SingleRunAction(Runnable runnable) { + this.runnable = runnable; + } + + /** + * This returns if the SingleRunAction has been run yet. Running reset() will reset this. + * + * @return This returns if it has been run. + */ + public boolean hasBeenRun() { + return hasBeenRun; + } + + /** + * This runs the Runnable of the SingleRunAction. It will only run once before requiring a reset. + * + * @return This returns if the Runnable was successfully run. If not, then a reset is needed to run again. + */ + public boolean run() { + if (!hasBeenRun) { + hasBeenRun = true; + runnable.run(); + return true; + } + return false; + } + + /** + * This resets the SingleRunAction and makes it able to run again. The SingleRunAction is set + * to "has not been run", allowing for multiple uses of the Runnable. + */ + public void reset() { + hasBeenRun = false; + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/Timer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/Timer.java new file mode 100644 index 0000000..a606043 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/util/Timer.java @@ -0,0 +1,46 @@ +package org.firstinspires.ftc.teamcode.pedroPathing.util; + +/** + * This is the Timer class. It is an elapsed time clock with millisecond precision, or at least as + * precise as the System.currentTimeMillis() is. + * + * @author Anyi Lin - 10158 Scott's Bots + * @author Aaron Yang - 10158 Scott's Bots + * @author Harrison Womack - 10158 Scott's Bots + * @version 1.0, 3/5/2024 + */ +public class Timer { + private long startTime; + + /** + * This creates a new Timer with the start time set to its creation time. + */ + public Timer() { + resetTimer(); + } + + /** + * This resets the Timer's start time to the current time using System.currentTimeMillis(). + */ + public void resetTimer() { + startTime = System.currentTimeMillis(); + } + + /** + * This returns the elapsed time in milliseconds since the start time of the Timer. + * + * @return this returns the elapsed time in milliseconds. + */ + public long getElapsedTime() { + return System.currentTimeMillis() - startTime; + } + + /** + * This returns the elapsed time in seconds since the start time of the Timer. + * + * @return this returns the elapsed time in seconds. + */ + public double getElapsedTimeSeconds() { + return (getElapsedTime() / 1000.0); + } +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/readme.md b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/readme.md new file mode 100644 index 0000000..4d1da42 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/readme.md @@ -0,0 +1,131 @@ +## TeamCode Module + +Welcome! + +This module, TeamCode, is the place where you will write/paste the code for your team's +robot controller App. This module is currently empty (a clean slate) but the +process for adding OpModes is straightforward. + +## Creating your own OpModes + +The easiest way to create your own OpMode is to copy a Sample OpMode and make it your own. + +Sample opmodes exist in the FtcRobotController module. +To locate these samples, find the FtcRobotController module in the "Project/Android" tab. + +Expand the following tree elements: + FtcRobotController/java/org.firstinspires.ftc.robotcontroller/external/samples + +### Naming of Samples + +To gain a better understanding of how the samples are organized, and how to interpret the +naming system, it will help to understand the conventions that were used during their creation. + +These conventions are described (in detail) in the sample_conventions.md file in this folder. + +To summarize: A range of different samples classes will reside in the java/external/samples. +The class names will follow a naming convention which indicates the purpose of each class. +The prefix of the name will be one of the following: + +Basic: This is a minimally functional OpMode used to illustrate the skeleton/structure + of a particular style of OpMode. These are bare bones examples. + +Sensor: This is a Sample OpMode that shows how to use a specific sensor. + It is not intended to drive a functioning robot, it is simply showing the minimal code + required to read and display the sensor values. + +Robot: This is a Sample OpMode that assumes a simple two-motor (differential) drive base. + It may be used to provide a common baseline driving OpMode, or + to demonstrate how a particular sensor or concept can be used to navigate. + +Concept: This is a sample OpMode that illustrates performing a specific function or concept. + These may be complex, but their operation should be explained clearly in the comments, + or the comments should reference an external doc, guide or tutorial. + Each OpMode should try to only demonstrate a single concept so they are easy to + locate based on their name. These OpModes may not produce a drivable robot. + +After the prefix, other conventions will apply: + +* Sensor class names are constructed as: Sensor - Company - Type +* Robot class names are constructed as: Robot - Mode - Action - OpModetype +* Concept class names are constructed as: Concept - Topic - OpModetype + +Once you are familiar with the range of samples available, you can choose one to be the +basis for your own robot. In all cases, the desired sample(s) needs to be copied into +your TeamCode module to be used. + +This is done inside Android Studio directly, using the following steps: + + 1) Locate the desired sample class in the Project/Android tree. + + 2) Right click on the sample class and select "Copy" + + 3) Expand the TeamCode/java folder + + 4) Right click on the org.firstinspires.ftc.teamcode folder and select "Paste" + + 5) You will be prompted for a class name for the copy. + Choose something meaningful based on the purpose of this class. + Start with a capital letter, and remember that there may be more similar classes later. + +Once your copy has been created, you should prepare it for use on your robot. +This is done by adjusting the OpMode's name, and enabling it to be displayed on the +Driver Station's OpMode list. + +Each OpMode sample class begins with several lines of code like the ones shown below: + +``` + @TeleOp(name="Template: Linear OpMode", group="Linear Opmode") + @Disabled +``` + +The name that will appear on the driver station's "opmode list" is defined by the code: + ``name="Template: Linear OpMode"`` +You can change what appears between the quotes to better describe your opmode. +The "group=" portion of the code can be used to help organize your list of OpModes. + +As shown, the current OpMode will NOT appear on the driver station's OpMode list because of the + ``@Disabled`` annotation which has been included. +This line can simply be deleted , or commented out, to make the OpMode visible. + + + +## ADVANCED Multi-Team App management: Cloning the TeamCode Module + +In some situations, you have multiple teams in your club and you want them to all share +a common code organization, with each being able to *see* the others code but each having +their own team module with their own code that they maintain themselves. + +In this situation, you might wish to clone the TeamCode module, once for each of these teams. +Each of the clones would then appear along side each other in the Android Studio module list, +together with the FtcRobotController module (and the original TeamCode module). + +Selective Team phones can then be programmed by selecting the desired Module from the pulldown list +prior to clicking to the green Run arrow. + +Warning: This is not for the inexperienced Software developer. +You will need to be comfortable with File manipulations and managing Android Studio Modules. +These changes are performed OUTSIDE of Android Studios, so close Android Studios before you do this. + +Also.. Make a full project backup before you start this :) + +To clone TeamCode, do the following: + +Note: Some names start with "Team" and others start with "team". This is intentional. + +1) Using your operating system file management tools, copy the whole "TeamCode" + folder to a sibling folder with a corresponding new name, eg: "Team0417". + +2) In the new Team0417 folder, delete the TeamCode.iml file. + +3) the new Team0417 folder, rename the "src/main/java/org/firstinspires/ftc/teamcode" folder + to a matching name with a lowercase 'team' eg: "team0417". + +4) In the new Team0417/src/main folder, edit the "AndroidManifest.xml" file, change the line that contains + package="org.firstinspires.ftc.teamcode" + to be + package="org.firstinspires.ftc.team0417" + +5) Add: include ':Team0417' to the "/settings.gradle" file. + +6) Open up Android Studios and clean out any old files by using the menu to "Build/Clean Project"" \ No newline at end of file diff --git a/build.dependencies.gradle b/build.dependencies.gradle index 09d4b8a..90ef1b5 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -1,21 +1,21 @@ repositories { mavenCentral() google() // Needed for androidx + + maven { url = 'https://maven.brott.dev/' } } dependencies { - implementation 'org.firstinspires.ftc:Inspection:9.2.0' - implementation 'org.firstinspires.ftc:Blocks:9.2.0' - implementation 'org.firstinspires.ftc:Tfod:9.2.0' - implementation 'org.firstinspires.ftc:RobotCore:9.2.0' - implementation 'org.firstinspires.ftc:RobotServer:9.2.0' - implementation 'org.firstinspires.ftc:OnBotJava:9.2.0' - implementation 'org.firstinspires.ftc:Hardware:9.2.0' - implementation 'org.firstinspires.ftc:FtcCommon:9.2.0' - implementation 'org.firstinspires.ftc:Vision:9.2.0' - implementation 'org.firstinspires.ftc:gameAssets-CenterStage:1.0.0' - implementation 'org.tensorflow:tensorflow-lite-task-vision:0.4.3' - runtimeOnly 'org.tensorflow:tensorflow-lite:2.12.0' + implementation 'org.firstinspires.ftc:Inspection:10.0.0' + implementation 'org.firstinspires.ftc:Blocks:10.0.0' + implementation 'org.firstinspires.ftc:RobotCore:10.0.0' + implementation 'org.firstinspires.ftc:RobotServer:10.0.0' + implementation 'org.firstinspires.ftc:OnBotJava:10.0.0' + implementation 'org.firstinspires.ftc:Hardware:10.0.0' + implementation 'org.firstinspires.ftc:FtcCommon:10.0.0' + implementation 'org.firstinspires.ftc:Vision:10.0.0' implementation 'androidx.appcompat:appcompat:1.2.0' + + implementation 'com.acmerobotics.dashboard:dashboard:0.4.5' }