FtcRobotController v11.1

This commit is contained in:
Cal Kestis
2025-12-31 10:54:21 -08:00
parent 40bc118a40
commit dc995e3d6f
9 changed files with 82 additions and 57 deletions

View File

@@ -1,8 +1,8 @@
<?xml version="1.0" encoding="utf-8"?>
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
xmlns:tools="http://schemas.android.com/tools"
android:versionCode="60"
android:versionName="11.0">
android:versionCode="61"
android:versionName="11.1">
<uses-permission android:name="android.permission.RECEIVE_BOOT_COMPLETED" />

View File

@@ -92,24 +92,22 @@ public class ConceptAprilTag extends LinearOpMode {
telemetry.update();
waitForStart();
if (opModeIsActive()) {
while (opModeIsActive()) {
while (opModeIsActive()) {
telemetryAprilTag();
telemetryAprilTag();
// Push telemetry to the Driver Station.
telemetry.update();
// 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 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.

View File

@@ -88,24 +88,22 @@ public class ConceptAprilTagEasy extends LinearOpMode {
telemetry.update();
waitForStart();
if (opModeIsActive()) {
while (opModeIsActive()) {
while (opModeIsActive()) {
telemetryAprilTag();
telemetryAprilTag();
// Push telemetry to the Driver Station.
telemetry.update();
// 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 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.

View File

@@ -81,27 +81,25 @@ public class ConceptAprilTagSwitchableCameras extends LinearOpMode {
telemetry.update();
waitForStart();
if (opModeIsActive()) {
while (opModeIsActive()) {
while (opModeIsActive()) {
telemetryCameraSwitching();
telemetryAprilTag();
telemetryCameraSwitching();
telemetryAprilTag();
// Push telemetry to the Driver Station.
telemetry.update();
// 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();
}
doCameraSwitching();
// Share the CPU.
sleep(20);
// Save CPU resources; can resume streaming when needed.
if (gamepad1.dpad_down) {
visionPortal.stopStreaming();
} else if (gamepad1.dpad_up) {
visionPortal.resumeStreaming();
}
doCameraSwitching();
// Share the CPU.
sleep(20);
}
// Save more CPU resources when camera is no longer needed.

View File

@@ -83,6 +83,22 @@ public class ConceptGamepadEdgeDetection extends LinearOpMode {
telemetry.addData("Gamepad 1 Right Bumper Released", gamepad1.rightBumperWasReleased());
telemetry.addData("Gamepad 1 Right Bumper Status", gamepad1.right_bumper);
// Add an empty line to separate the buttons in telemetry
telemetry.addLine();
// Add the status of the Gamepad 1 Left trigger
telemetry.addData("Gamepad 1 Left Trigger Pressed", gamepad1.leftTriggerWasPressed());
telemetry.addData("Gamepad 1 Left Trigger Released", gamepad1.leftTriggerWasReleased());
telemetry.addData("Gamepad 1 Left Trigger Status", gamepad1.left_trigger_pressed);
// Add an empty line to separate the buttons in telemetry
telemetry.addLine();
// Add the status of the Gamepad 1 Right trigger
telemetry.addData("Gamepad 1 Right Trigger Pressed", gamepad1.rightTriggerWasPressed());
telemetry.addData("Gamepad 1 Right Trigger Released", gamepad1.rightTriggerWasReleased());
telemetry.addData("Gamepad 1 Right Trigger Status", gamepad1.right_trigger_pressed);
// Add a note that the telemetry is only updated every 2 seconds
telemetry.addLine("\nTelemetry is updated every 2 seconds.");

View File

@@ -27,7 +27,7 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
package org.firstinspires.ftc.robotcontroller.external.samples;
package org.firstinspires.ftc.robotcontroller.external.samples.externalhardware;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;

View File

@@ -27,7 +27,7 @@
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
package org.firstinspires.ftc.robotcontroller.external.samples;
package org.firstinspires.ftc.robotcontroller.external.samples.externalhardware;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;