Skip to content

Commit 1271986

Browse files
authored
Merge pull request #1503 from FIRST-Tech-Challenge/20250625-090416-release-candidate
FtcRobotController v10.3
2 parents 28d5246 + a5d843e commit 1271986

12 files changed

+657
-127
lines changed

FtcRobotController/src/main/AndroidManifest.xml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
<?xml version="1.0" encoding="utf-8"?>
22
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
33
xmlns:tools="http://schemas.android.com/tools"
4-
android:versionCode="58"
5-
android:versionName="10.2">
4+
android:versionCode="59"
5+
android:versionName="10.3">
66

77
<uses-permission android:name="android.permission.RECEIVE_BOOT_COMPLETED" />
88

FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/BasicOmniOpMode_Linear.java

Lines changed: 33 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -69,20 +69,20 @@ public class BasicOmniOpMode_Linear extends LinearOpMode {
6969

7070
// Declare OpMode members for each of the 4 motors.
7171
private ElapsedTime runtime = new ElapsedTime();
72-
private DcMotor leftFrontDrive = null;
73-
private DcMotor leftBackDrive = null;
74-
private DcMotor rightFrontDrive = null;
75-
private DcMotor rightBackDrive = null;
72+
private DcMotor frontLeftDrive = null;
73+
private DcMotor backLeftDrive = null;
74+
private DcMotor frontRightDrive = null;
75+
private DcMotor backRightDrive = null;
7676

7777
@Override
7878
public void runOpMode() {
7979

8080
// Initialize the hardware variables. Note that the strings used here must correspond
8181
// to the names assigned during the robot configuration step on the DS or RC devices.
82-
leftFrontDrive = hardwareMap.get(DcMotor.class, "left_front_drive");
83-
leftBackDrive = hardwareMap.get(DcMotor.class, "left_back_drive");
84-
rightFrontDrive = hardwareMap.get(DcMotor.class, "right_front_drive");
85-
rightBackDrive = hardwareMap.get(DcMotor.class, "right_back_drive");
82+
frontLeftDrive = hardwareMap.get(DcMotor.class, "front_left_drive");
83+
backLeftDrive = hardwareMap.get(DcMotor.class, "back_left_drive");
84+
frontRightDrive = hardwareMap.get(DcMotor.class, "front_right_drive");
85+
backRightDrive = hardwareMap.get(DcMotor.class, "back_right_drive");
8686

8787
// ########################################################################################
8888
// !!! IMPORTANT Drive Information. Test your motor directions. !!!!!
@@ -94,10 +94,10 @@ public void runOpMode() {
9494
// when you first test your robot, push the left joystick forward and observe the direction the wheels turn.
9595
// Reverse the direction (flip FORWARD <-> REVERSE ) of any wheel that runs backward
9696
// Keep testing until ALL the wheels move the robot forward when you push the left joystick forward.
97-
leftFrontDrive.setDirection(DcMotor.Direction.REVERSE);
98-
leftBackDrive.setDirection(DcMotor.Direction.REVERSE);
99-
rightFrontDrive.setDirection(DcMotor.Direction.FORWARD);
100-
rightBackDrive.setDirection(DcMotor.Direction.FORWARD);
97+
frontLeftDrive.setDirection(DcMotor.Direction.REVERSE);
98+
backLeftDrive.setDirection(DcMotor.Direction.REVERSE);
99+
frontRightDrive.setDirection(DcMotor.Direction.FORWARD);
100+
backRightDrive.setDirection(DcMotor.Direction.FORWARD);
101101

102102
// Wait for the game to start (driver presses START)
103103
telemetry.addData("Status", "Initialized");
@@ -117,22 +117,22 @@ public void runOpMode() {
117117

118118
// Combine the joystick requests for each axis-motion to determine each wheel's power.
119119
// Set up a variable for each drive wheel to save the power level for telemetry.
120-
double leftFrontPower = axial + lateral + yaw;
121-
double rightFrontPower = axial - lateral - yaw;
122-
double leftBackPower = axial - lateral + yaw;
123-
double rightBackPower = axial + lateral - yaw;
120+
double frontLeftPower = axial + lateral + yaw;
121+
double frontRightPower = axial - lateral - yaw;
122+
double backLeftPower = axial - lateral + yaw;
123+
double backRightPower = axial + lateral - yaw;
124124

125125
// Normalize the values so no wheel power exceeds 100%
126126
// This ensures that the robot maintains the desired motion.
127-
max = Math.max(Math.abs(leftFrontPower), Math.abs(rightFrontPower));
128-
max = Math.max(max, Math.abs(leftBackPower));
129-
max = Math.max(max, Math.abs(rightBackPower));
127+
max = Math.max(Math.abs(frontLeftPower), Math.abs(frontRightPower));
128+
max = Math.max(max, Math.abs(backLeftPower));
129+
max = Math.max(max, Math.abs(backRightPower));
130130

131131
if (max > 1.0) {
132-
leftFrontPower /= max;
133-
rightFrontPower /= max;
134-
leftBackPower /= max;
135-
rightBackPower /= max;
132+
frontLeftPower /= max;
133+
frontRightPower /= max;
134+
backLeftPower /= max;
135+
backRightPower /= max;
136136
}
137137

138138
// This is test code:
@@ -146,22 +146,22 @@ public void runOpMode() {
146146
// Once the correct motors move in the correct direction re-comment this code.
147147

148148
/*
149-
leftFrontPower = gamepad1.x ? 1.0 : 0.0; // X gamepad
150-
leftBackPower = gamepad1.a ? 1.0 : 0.0; // A gamepad
151-
rightFrontPower = gamepad1.y ? 1.0 : 0.0; // Y gamepad
152-
rightBackPower = gamepad1.b ? 1.0 : 0.0; // B gamepad
149+
frontLeftPower = gamepad1.x ? 1.0 : 0.0; // X gamepad
150+
backLeftPower = gamepad1.a ? 1.0 : 0.0; // A gamepad
151+
frontRightPower = gamepad1.y ? 1.0 : 0.0; // Y gamepad
152+
backRightPower = gamepad1.b ? 1.0 : 0.0; // B gamepad
153153
*/
154154

155155
// Send calculated power to wheels
156-
leftFrontDrive.setPower(leftFrontPower);
157-
rightFrontDrive.setPower(rightFrontPower);
158-
leftBackDrive.setPower(leftBackPower);
159-
rightBackDrive.setPower(rightBackPower);
156+
frontLeftDrive.setPower(frontLeftPower);
157+
frontRightDrive.setPower(frontRightPower);
158+
backLeftDrive.setPower(backLeftPower);
159+
backRightDrive.setPower(backRightPower);
160160

161161
// Show the elapsed game time and wheel power.
162162
telemetry.addData("Status", "Run Time: " + runtime.toString());
163-
telemetry.addData("Front left/Right", "%4.2f, %4.2f", leftFrontPower, rightFrontPower);
164-
telemetry.addData("Back left/Right", "%4.2f, %4.2f", leftBackPower, rightBackPower);
163+
telemetry.addData("Front left/Right", "%4.2f, %4.2f", frontLeftPower, frontRightPower);
164+
telemetry.addData("Back left/Right", "%4.2f, %4.2f", backLeftPower, backRightPower);
165165
telemetry.update();
166166
}
167167
}}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,87 @@
1+
/* Copyright (c) 2025 FIRST. All rights reserved.
2+
*
3+
* Redistribution and use in source and binary forms, with or without modification,
4+
* are permitted (subject to the limitations in the disclaimer below) provided that
5+
* the following conditions are met:
6+
*
7+
* Redistributions of source code must retain the above copyright notice, this list
8+
* of conditions and the following disclaimer.
9+
*
10+
* Redistributions in binary form must reproduce the above copyright notice, this
11+
* list of conditions and the following disclaimer in the documentation and/or
12+
* other materials provided with the distribution.
13+
*
14+
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
15+
* promote products derived from this software without specific prior written permission.
16+
*
17+
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
18+
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
20+
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
22+
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23+
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24+
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26+
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27+
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28+
*/
29+
30+
package org.firstinspires.ftc.robotcontroller.external.samples;
31+
32+
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
33+
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
34+
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
35+
36+
/*
37+
* Demonstrates how to use an OpMode to store data in the blackboard and retrieve it.
38+
* This is useful for storing information in Auto and then retrieving it in your TeleOp.
39+
*
40+
* Be aware that this is NOT saved across power reboots or downloads or robot resets.
41+
*
42+
* You also need to make sure that both the storing and retrieving are done using the same
43+
* type. For example, storing a Double in the blackboard and retrieving it as an Integer
44+
* will fail when you typecast it.
45+
*
46+
* The blackboard is a standard hashmap so you can use methods like:
47+
* put, get, containsKey, remove, etc.
48+
*/
49+
@TeleOp(name = "Concept: Blackboard", group = "Concept")
50+
@Disabled
51+
public class ConceptBlackboard extends OpMode {
52+
// We use constants here so we won't have the problem of typos in different places when we
53+
// meant to refer to the same thing.
54+
public static final String TIMES_STARTED_KEY = "Times started";
55+
public static final String ALLIANCE_KEY = "Alliance";
56+
57+
/**
58+
* This method will be called once, when the INIT button is pressed.
59+
*/
60+
@Override
61+
public void init() {
62+
// This gets us what is in the blackboard or the default if it isn't in there.
63+
Object timesStarted = blackboard.getOrDefault(TIMES_STARTED_KEY, 0);
64+
blackboard.put(TIMES_STARTED_KEY, (int) timesStarted + 1);
65+
66+
telemetry.addData("OpMode started times", blackboard.get(TIMES_STARTED_KEY));
67+
}
68+
69+
/**
70+
* This method will be called repeatedly during the period between when
71+
* the START button is pressed and when the OpMode is stopped.
72+
* <p>
73+
* If the left bumper is pressed it will store the value "RED" in the blackboard for alliance.
74+
* If the right bumper is pressed it will store the value "BLUE" in the blackboard for alliance.
75+
* <p>
76+
* You'll notice that if you quit the OpMode and come back in, the value will persist.
77+
*/
78+
@Override
79+
public void loop() {
80+
if (gamepad1.left_bumper) {
81+
blackboard.put(ALLIANCE_KEY, "RED");
82+
} else if (gamepad1.right_bumper) {
83+
blackboard.put(ALLIANCE_KEY, "BLUE");
84+
}
85+
telemetry.addData("Alliance", blackboard.get(ALLIANCE_KEY));
86+
}
87+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,92 @@
1+
/*
2+
Copyright (c) 2024 Miriam Sinton-Remes
3+
4+
All rights reserved.
5+
6+
Redistribution and use in source and binary forms, with or without modification,
7+
are permitted (subject to the limitations in the disclaimer below) provided that
8+
the following conditions are met:
9+
10+
Redistributions of source code must retain the above copyright notice, this list
11+
of conditions and the following disclaimer.
12+
13+
Redistributions in binary form must reproduce the above copyright notice, this
14+
list of conditions and the following disclaimer in the documentation and/or
15+
other materials provided with the distribution.
16+
17+
Neither the name of FIRST nor the names of its contributors may be used to
18+
endorse or promote products derived from this software without specific prior
19+
written permission.
20+
21+
NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
22+
LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23+
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
24+
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESSFOR A PARTICULAR PURPOSE
25+
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
26+
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27+
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28+
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR
30+
TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
31+
THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32+
*/
33+
34+
package org.firstinspires.ftc.robotcontroller.external.samples;
35+
36+
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
37+
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
38+
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
39+
40+
/*
41+
* This OpMode illustrates using edge detection on a gamepad.
42+
*
43+
* Simply checking the state of a gamepad button each time could result in triggering an effect
44+
* multiple times. Edge detection ensures that you only detect one button press, regardless of how
45+
* long the button is held.
46+
*
47+
* There are two main types of edge detection. Rising edge detection will trigger when a button is
48+
* first pressed. Falling edge detection will trigger when the button is released.
49+
*
50+
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
51+
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list.
52+
*/
53+
54+
@Disabled
55+
@TeleOp(name="Concept: Gamepad Edge Detection", group ="Concept")
56+
public class ConceptGamepadEdgeDetection extends LinearOpMode {
57+
58+
@Override
59+
public void runOpMode() {
60+
// Wait for the DS start button to be pressed
61+
waitForStart();
62+
63+
while (opModeIsActive()) {
64+
// Update the telemetry
65+
telemetryButtonData();
66+
67+
// Wait 2 seconds before doing another check
68+
sleep(2000);
69+
}
70+
}
71+
72+
public void telemetryButtonData() {
73+
// Add the status of the Gamepad 1 Left Bumper
74+
telemetry.addData("Gamepad 1 Left Bumper Pressed", gamepad1.leftBumperWasPressed());
75+
telemetry.addData("Gamepad 1 Left Bumper Released", gamepad1.leftBumperWasReleased());
76+
telemetry.addData("Gamepad 1 Left Bumper Status", gamepad1.left_bumper);
77+
78+
// Add an empty line to seperate the buttons in telemetry
79+
telemetry.addLine();
80+
81+
// Add the status of the Gamepad 1 Right Bumper
82+
telemetry.addData("Gamepad 1 Right Bumper Pressed", gamepad1.rightBumperWasPressed());
83+
telemetry.addData("Gamepad 1 Right Bumper Released", gamepad1.rightBumperWasReleased());
84+
telemetry.addData("Gamepad 1 Right Bumper Status", gamepad1.right_bumper);
85+
86+
// Add a note that the telemetry is only updated every 2 seconds
87+
telemetry.addLine("\nTelemetry is updated every 2 seconds.");
88+
89+
// Update the telemetry on the DS screen
90+
telemetry.update();
91+
}
92+
}

FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/external/samples/ConceptVisionColorLocator.java

Lines changed: 26 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -149,39 +149,54 @@ public void runOpMode()
149149
* Note: All contours will be still displayed on the Stream Preview, but only those that satisfy the filter
150150
* conditions will remain in the current list of "blobs". Multiple filters may be used.
151151
*
152-
* Use any of the following filters.
152+
* To perform a filter
153+
* ColorBlobLocatorProcessor.Util.filterByCriteria(criteria, minValue, maxValue, blobs);
153154
*
154-
* ColorBlobLocatorProcessor.Util.filterByArea(minArea, maxArea, blobs);
155+
* The following criteria are currently supported.
156+
*
157+
* ColorBlobLocatorProcessor.BlobCriteria.BY_CONTOUR_AREA
155158
* A Blob's area is the number of pixels contained within the Contour. Filter out any that are too big or small.
156159
* Start with a large range and then refine the range based on the likely size of the desired object in the viewfinder.
157160
*
158-
* ColorBlobLocatorProcessor.Util.filterByDensity(minDensity, maxDensity, blobs);
161+
* ColorBlobLocatorProcessor.BlobCriteria.BY_DENSITY
159162
* A blob's density is an indication of how "full" the contour is.
160163
* If you put a rubber band around the contour you would get the "Convex Hull" of the contour.
161164
* The density is the ratio of Contour-area to Convex Hull-area.
162165
*
163-
* ColorBlobLocatorProcessor.Util.filterByAspectRatio(minAspect, maxAspect, blobs);
166+
* ColorBlobLocatorProcessor.BlobCriteria.BY_ASPECT_RATIO
164167
* A blob's Aspect ratio is the ratio of boxFit long side to short side.
165168
* A perfect Square has an aspect ratio of 1. All others are > 1
169+
*
170+
* ColorBlobLocatorProcessor.BlobCriteria.BY_ARC_LENGTH
171+
* A blob's arc length is the perimeter of the blob.
172+
* This can be used in conjunction with an area filter to detect oddly shaped blobs.
173+
*
174+
* ColorBlobLocatorProcessor.BlobCriteria.BY_CIRCULARITY
175+
* A blob's circularity is how circular it is based on the known area and arc length.
176+
* A perfect circle has a circularity of 1. All others are < 1
166177
*/
167-
ColorBlobLocatorProcessor.Util.filterByArea(50, 20000, blobs); // filter out very small blobs.
178+
ColorBlobLocatorProcessor.Util.filterByCriteria(
179+
ColorBlobLocatorProcessor.BlobCriteria.BY_CONTOUR_AREA,
180+
50, 20000, blobs); // filter out very small blobs.
168181

169182
/*
170183
* The list of Blobs can be sorted using the same Blob attributes as listed above.
171184
* No more than one sort call should be made. Sorting can use ascending or descending order.
172-
* ColorBlobLocatorProcessor.Util.sortByArea(SortOrder.DESCENDING, blobs); // Default
173-
* ColorBlobLocatorProcessor.Util.sortByDensity(SortOrder.DESCENDING, blobs);
174-
* ColorBlobLocatorProcessor.Util.sortByAspectRatio(SortOrder.DESCENDING, blobs);
185+
* ColorBlobLocatorProcessor.Util.sortByCriteria(ColorBlobLocatorProcessor.BlobCriteria.BY_CONTOUR_AREA SortOrder.DESCENDING, blobs); // Default
186+
* ColorBlobLocatorProcessor.Util.sortByCriteria(ColorBlobLocatorProcessor.BlobCriteria.BY_DENSITY SortOrder.DESCENDING, blobs);
187+
* ColorBlobLocatorProcessor.Util.sortByCriteria(ColorBlobLocatorProcessor.BlobCriteria.BY_ASPECT_RATIO SortOrder.DESCENDING, blobs);
188+
* ColorBlobLocatorProcessor.Util.sortByCriteria(ColorBlobLocatorProcessor.BlobCriteria.BY_ARC_LENGTH SortOrder.DESCENDING, blobs);
189+
* ColorBlobLocatorProcessor.Util.sortByCriteria(ColorBlobLocatorProcessor.BlobCriteria.BY_CIRCULARITY SortOrder.DESCENDING, blobs);
175190
*/
176191

177-
telemetry.addLine(" Area Density Aspect Center");
192+
telemetry.addLine("Area Density Aspect Arc Circle Center");
178193

179194
// Display the size (area) and center location for each Blob.
180195
for(ColorBlobLocatorProcessor.Blob b : blobs)
181196
{
182197
RotatedRect boxFit = b.getBoxFit();
183-
telemetry.addLine(String.format("%5d %4.2f %5.2f (%3d,%3d)",
184-
b.getContourArea(), b.getDensity(), b.getAspectRatio(), (int) boxFit.center.x, (int) boxFit.center.y));
198+
telemetry.addLine(String.format("%5d %4.2f %5.2f %3d %5.3f (%3d,%3d)",
199+
b.getContourArea(), b.getDensity(), b.getAspectRatio(), (int) b.getArcLength(), b.getCircularity(), (int) boxFit.center.x, (int) boxFit.center.y));
185200
}
186201

187202
telemetry.update();

0 commit comments

Comments
 (0)