Skip to content

Commit f326c0d

Browse files
authored
Merge pull request #731 from FIRST-Tech-Challenge/20230929-083754-release-candidate
FtcRobotController v9.0.1
2 parents f3a5a54 + c023e97 commit f326c0d

8 files changed

+154
-36
lines changed

FtcRobotController/src/main/AndroidManifest.xml

+2-2
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="51"
5-
android:versionName="9.0">
4+
android:versionCode="52"
5+
android:versionName="9.0.1">
66

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

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

+29-2
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,23 @@
4444
* This OpMode illustrates the basics of AprilTag recognition and pose estimation,
4545
* including Java Builder structures for specifying Vision parameters.
4646
*
47+
* For an introduction to AprilTags, see the FTC-DOCS link below:
48+
* https://ftc-docs.firstinspires.org/en/latest/apriltag/vision_portal/apriltag_intro/apriltag-intro.html
49+
*
50+
* In this sample, any visible tag ID will be detected and displayed, but only tags that are included in the default
51+
* "TagLibrary" will have their position and orientation information displayed. This default TagLibrary contains
52+
* the current Season's AprilTags and a small set of "test Tags" in the high number range.
53+
*
54+
* When an AprilTag in the TagLibrary is detected, the SDK provides location and orientation of the tag, relative to the camera.
55+
* This information is provided in the "ftcPose" member of the returned "detection", and is explained in the ftc-docs page linked below.
56+
* https://ftc-docs.firstinspires.org/apriltag-detection-values
57+
*
58+
* To experiment with using AprilTags to navigate, try out these two driving samples:
59+
* RobotAutoDriveToAprilTagOmni and RobotAutoDriveToAprilTagTank
60+
*
61+
* There are many "default" VisionPortal and AprilTag configuration parameters that may be overridden if desired.
62+
* These default parameters are shown as comments in the code below.
63+
*
4764
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
4865
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list.
4966
*/
@@ -106,6 +123,8 @@ private void initAprilTag() {
106123

107124
// Create the AprilTag processor.
108125
aprilTag = new AprilTagProcessor.Builder()
126+
127+
// The following default settings are available to un-comment and edit as needed.
109128
//.setDrawAxes(false)
110129
//.setDrawCubeProjection(false)
111130
//.setDrawTagOutline(true)
@@ -117,11 +136,19 @@ private void initAprilTag() {
117136
// If you do not manually specify calibration parameters, the SDK will attempt
118137
// to load a predefined calibration for your camera.
119138
//.setLensIntrinsics(578.272, 578.272, 402.145, 221.506)
120-
121139
// ... these parameters are fx, fy, cx, cy.
122140

123141
.build();
124142

143+
// Adjust Image Decimation to trade-off detection-range for detection-rate.
144+
// eg: Some typical detection data using a Logitech C920 WebCam
145+
// Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second
146+
// Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second
147+
// Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second (default)
148+
// Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second (default)
149+
// Note: Decimation can be changed on-the-fly to adapt during a match.
150+
//aprilTag.setDecimation(3);
151+
125152
// Create the vision portal by using a builder.
126153
VisionPortal.Builder builder = new VisionPortal.Builder();
127154

@@ -136,7 +163,7 @@ private void initAprilTag() {
136163
//builder.setCameraResolution(new Size(640, 480));
137164

138165
// Enable the RC preview (LiveView). Set "false" to omit camera monitoring.
139-
//builder.enableCameraMonitoring(true);
166+
//builder.enableLiveView(true);
140167

141168
// Set the stream format; MJPEG uses less bandwidth than default YUY2.
142169
//builder.setStreamFormat(VisionPortal.StreamFormat.YUY2);

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

+14
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,20 @@
4444
* This OpMode illustrates the basics of AprilTag recognition and pose estimation, using
4545
* the easy way.
4646
*
47+
* For an introduction to AprilTags, see the FTC-DOCS link below:
48+
* https://ftc-docs.firstinspires.org/en/latest/apriltag/vision_portal/apriltag_intro/apriltag-intro.html
49+
*
50+
* In this sample, any visible tag ID will be detected and displayed, but only tags that are included in the default
51+
* "TagLibrary" will have their position and orientation information displayed. This default TagLibrary contains
52+
* the current Season's AprilTags and a small set of "test Tags" in the high number range.
53+
*
54+
* When an AprilTag in the TagLibrary is detected, the SDK provides location and orientation of the tag, relative to the camera.
55+
* This information is provided in the "ftcPose" member of the returned "detection", and is explained in the ftc-docs page linked below.
56+
* https://ftc-docs.firstinspires.org/apriltag-detection-values
57+
*
58+
* To experiment with using AprilTags to navigate, try out these two driving samples:
59+
* RobotAutoDriveToAprilTagOmni and RobotAutoDriveToAprilTagTank
60+
*
4761
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
4862
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list.
4963
*/

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

+19-3
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,17 @@ public class ConceptTensorFlowObjectDetection extends LinearOpMode {
5353

5454
private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera
5555

56+
// TFOD_MODEL_ASSET points to a model file stored in the project Asset location,
57+
// this is only used for Android Studio when using models in Assets.
58+
private static final String TFOD_MODEL_ASSET = "MyModelStoredAsAsset.tflite";
59+
// TFOD_MODEL_FILE points to a model file stored onboard the Robot Controller's storage,
60+
// this is used when uploading models directly to the RC using the model upload interface.
61+
private static final String TFOD_MODEL_FILE = "/sdcard/FIRST/tflitemodels/myCustomModel.tflite";
62+
// Define the labels recognized in the model for TFOD (must be in training order!)
63+
private static final String[] LABELS = {
64+
"Pixel",
65+
};
66+
5667
/**
5768
* The variable to store our instance of the TensorFlow Object Detection processor.
5869
*/
@@ -107,11 +118,16 @@ private void initTfod() {
107118
// Create the TensorFlow processor by using a builder.
108119
tfod = new TfodProcessor.Builder()
109120

110-
// Use setModelAssetName() if the TF Model is built in as an asset.
111-
// Use setModelFileName() if you have downloaded a custom team model to the Robot Controller.
121+
// With the following lines commented out, the default TfodProcessor Builder
122+
// will load the default model for the season. To define a custom model to load,
123+
// choose one of the following:
124+
// Use setModelAssetName() if the custom TF Model is built in as an asset (AS only).
125+
// Use setModelFileName() if you have downloaded a custom team model to the Robot Controller.
112126
//.setModelAssetName(TFOD_MODEL_ASSET)
113127
//.setModelFileName(TFOD_MODEL_FILE)
114128

129+
// The following default settings are available to un-comment and edit as needed to
130+
// set parameters for custom models.
115131
//.setModelLabels(LABELS)
116132
//.setIsModelTensorFlow2(true)
117133
//.setIsModelQuantized(true)
@@ -134,7 +150,7 @@ private void initTfod() {
134150
//builder.setCameraResolution(new Size(640, 480));
135151

136152
// Enable the RC preview (LiveView). Set "false" to omit camera monitoring.
137-
//builder.enableCameraMonitoring(true);
153+
//builder.enableLiveView(true);
138154

139155
// Set the stream format; MJPEG uses less bandwidth than default YUY2.
140156
//builder.setStreamFormat(VisionPortal.StreamFormat.YUY2);

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

+34-10
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,13 @@
4949
* This OpMode illustrates using a camera to locate and drive towards a specific AprilTag.
5050
* The code assumes a Holonomic (Mecanum or X Drive) Robot.
5151
*
52+
* For an introduction to AprilTags, see the ftc-docs link below:
53+
* https://ftc-docs.firstinspires.org/en/latest/apriltag/vision_portal/apriltag_intro/apriltag-intro.html
54+
*
55+
* When an AprilTag in the TagLibrary is detected, the SDK provides location and orientation of the tag, relative to the camera.
56+
* This information is provided in the "ftcPose" member of the returned "detection", and is explained in the ftc-docs page linked below.
57+
* https://ftc-docs.firstinspires.org/apriltag-detection-values
58+
*
5259
* The drive goal is to rotate to keep the Tag centered in the camera, while strafing to be directly in front of the tag, and
5360
* driving towards the tag to achieve the desired distance.
5461
* To reduce any motion blur (which will interrupt the detection process) the Camera exposure is reduced to a very low value (5mS)
@@ -102,7 +109,7 @@ public class RobotAutoDriveToAprilTagOmni extends LinearOpMode
102109
private DcMotor rightBackDrive = null; // Used to control the right back drive wheel
103110

104111
private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera
105-
private static final int DESIRED_TAG_ID = 0; // Choose the tag you want to approach or set to -1 for ANY tag.
112+
private static final int DESIRED_TAG_ID = -1; // Choose the tag you want to approach or set to -1 for ANY tag.
106113
private VisionPortal visionPortal; // Used to manage the video source.
107114
private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process.
108115
private AprilTagDetection desiredTag = null; // Used to hold the data for a detected AprilTag
@@ -150,25 +157,33 @@ public class RobotAutoDriveToAprilTagOmni extends LinearOpMode
150157
// Step through the list of detected tags and look for a matching tag
151158
List<AprilTagDetection> currentDetections = aprilTag.getDetections();
152159
for (AprilTagDetection detection : currentDetections) {
153-
if ((detection.metadata != null) &&
154-
((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) ){
155-
targetFound = true;
156-
desiredTag = detection;
157-
break; // don't look any further.
160+
// Look to see if we have size info on this tag.
161+
if (detection.metadata != null) {
162+
// Check to see if we want to track towards this tag.
163+
if ((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) {
164+
// Yes, we want to use this tag.
165+
targetFound = true;
166+
desiredTag = detection;
167+
break; // don't look any further.
168+
} else {
169+
// This tag is in the library, but we do not want to track it right now.
170+
telemetry.addData("Skipping", "Tag ID %d is not desired", detection.id);
171+
}
158172
} else {
159-
telemetry.addData("Unknown Target", "Tag ID %d is not in TagLibrary\n", detection.id);
173+
// This tag is NOT in the library, so we don't have enough information to track to it.
174+
telemetry.addData("Unknown", "Tag ID %d is not in TagLibrary", detection.id);
160175
}
161176
}
162177

163178
// Tell the driver what we see, and what to do.
164179
if (targetFound) {
165-
telemetry.addData(">","HOLD Left-Bumper to Drive to Target\n");
166-
telemetry.addData("Target", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name);
180+
telemetry.addData("\n>","HOLD Left-Bumper to Drive to Target\n");
181+
telemetry.addData("Found", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name);
167182
telemetry.addData("Range", "%5.1f inches", desiredTag.ftcPose.range);
168183
telemetry.addData("Bearing","%3.0f degrees", desiredTag.ftcPose.bearing);
169184
telemetry.addData("Yaw","%3.0f degrees", desiredTag.ftcPose.yaw);
170185
} else {
171-
telemetry.addData(">","Drive using joysticks to find valid target\n");
186+
telemetry.addData("\n>","Drive using joysticks to find valid target\n");
172187
}
173188

174189
// If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically .
@@ -243,6 +258,15 @@ private void initAprilTag() {
243258
// Create the AprilTag processor by using a builder.
244259
aprilTag = new AprilTagProcessor.Builder().build();
245260

261+
// Adjust Image Decimation to trade-off detection-range for detection-rate.
262+
// eg: Some typical detection data using a Logitech C920 WebCam
263+
// Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second
264+
// Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second
265+
// Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second
266+
// Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second
267+
// Note: Decimation can be changed on-the-fly to adapt during a match.
268+
aprilTag.setDecimation(2);
269+
246270
// Create the vision portal by using a builder.
247271
if (USE_WEBCAM) {
248272
visionPortal = new VisionPortal.Builder()

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

+34-10
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,13 @@
4949
* This OpMode illustrates using a camera to locate and drive towards a specific AprilTag.
5050
* The code assumes a basic two-wheel (Tank) Robot Drivetrain
5151
*
52+
* For an introduction to AprilTags, see the ftc-docs link below:
53+
* https://ftc-docs.firstinspires.org/en/latest/apriltag/vision_portal/apriltag_intro/apriltag-intro.html
54+
*
55+
* When an AprilTag in the TagLibrary is detected, the SDK provides location and orientation of the tag, relative to the camera.
56+
* This information is provided in the "ftcPose" member of the returned "detection", and is explained in the ftc-docs page linked below.
57+
* https://ftc-docs.firstinspires.org/apriltag-detection-values
58+
*
5259
* The driving goal is to rotate to keep the tag centered in the camera, while driving towards the tag to achieve the desired distance.
5360
* To reduce any motion blur (which will interrupt the detection process) the Camera exposure is reduced to a very low value (5mS)
5461
* You can determine the best exposure and gain values by using the ConceptAprilTagOptimizeExposure OpMode in this Samples folder.
@@ -97,7 +104,7 @@ public class RobotAutoDriveToAprilTagTank extends LinearOpMode
97104
private DcMotor rightDrive = null; // Used to control the right drive wheel
98105

99106
private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera
100-
private static final int DESIRED_TAG_ID = 0; // Choose the tag you want to approach or set to -1 for ANY tag.
107+
private static final int DESIRED_TAG_ID = -1; // Choose the tag you want to approach or set to -1 for ANY tag.
101108
private VisionPortal visionPortal; // Used to manage the video source.
102109
private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process.
103110
private AprilTagDetection desiredTag = null; // Used to hold the data for a detected AprilTag
@@ -140,24 +147,32 @@ public class RobotAutoDriveToAprilTagTank extends LinearOpMode
140147
// Step through the list of detected tags and look for a matching tag
141148
List<AprilTagDetection> currentDetections = aprilTag.getDetections();
142149
for (AprilTagDetection detection : currentDetections) {
143-
if ((detection.metadata != null) &&
144-
((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) ){
145-
targetFound = true;
146-
desiredTag = detection;
147-
break; // don't look any further.
150+
// Look to see if we have size info on this tag.
151+
if (detection.metadata != null) {
152+
// Check to see if we want to track towards this tag.
153+
if ((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) {
154+
// Yes, we want to use this tag.
155+
targetFound = true;
156+
desiredTag = detection;
157+
break; // don't look any further.
158+
} else {
159+
// This tag is in the library, but we do not want to track it right now.
160+
telemetry.addData("Skipping", "Tag ID %d is not desired", detection.id);
161+
}
148162
} else {
149-
telemetry.addData("Unknown Target", "Tag ID %d is not in TagLibrary\n", detection.id);
163+
// This tag is NOT in the library, so we don't have enough information to track to it.
164+
telemetry.addData("Unknown", "Tag ID %d is not in TagLibrary", detection.id);
150165
}
151166
}
152167

153168
// Tell the driver what we see, and what to do.
154169
if (targetFound) {
155-
telemetry.addData(">","HOLD Left-Bumper to Drive to Target\n");
156-
telemetry.addData("Target", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name);
170+
telemetry.addData("\n>","HOLD Left-Bumper to Drive to Target\n");
171+
telemetry.addData("Found", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name);
157172
telemetry.addData("Range", "%5.1f inches", desiredTag.ftcPose.range);
158173
telemetry.addData("Bearing","%3.0f degrees", desiredTag.ftcPose.bearing);
159174
} else {
160-
telemetry.addData(">","Drive using joysticks to find valid target\n");
175+
telemetry.addData("\n>","Drive using joysticks to find valid target\n");
161176
}
162177

163178
// If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically .
@@ -218,6 +233,15 @@ private void initAprilTag() {
218233
// Create the AprilTag processor by using a builder.
219234
aprilTag = new AprilTagProcessor.Builder().build();
220235

236+
// Adjust Image Decimation to trade-off detection-range for detection-rate.
237+
// eg: Some typical detection data using a Logitech C920 WebCam
238+
// Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second
239+
// Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second
240+
// Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second
241+
// Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second
242+
// Note: Decimation can be changed on-the-fly to adapt during a match.
243+
aprilTag.setDecimation(2);
244+
221245
// Create the vision portal by using a builder.
222246
if (USE_WEBCAM) {
223247
visionPortal = new VisionPortal.Builder()

README.md

+13
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,19 @@ The readme.md file located in the [/TeamCode/src/main/java/org/firstinspires/ftc
5959

6060
# Release Information
6161

62+
## Version 9.0.1 (20230929-083754)
63+
64+
### Enhancements
65+
* Updates AprilTag samples to include Decimation and additional Comments. Also corrects misleading tag ID warnings
66+
* Increases maximum size of Blocks inline comments to 140 characters
67+
* Adds Blocks sample BasicOmniOpMode.
68+
* Updated CENTERSTAGE library AprilTag orientation quaternions
69+
* Thanks [@FromenActual](https://github.com/FromenActual)
70+
* Updated Java Sample ConceptTensorFlowObjectDetection.java to include missing elements needed for custom model support.
71+
72+
### Bug Fixes
73+
* Fixes a problem where after October 1 the Driver Station will report as obsolete on v9.0 and prompt the user to update.
74+
6275
## Version 9.0 (20230830-154348)
6376

6477
### Breaking Changes

0 commit comments

Comments
 (0)