Skip to content

Commit 6af9bb6

Browse files
authored
Merge pull request #1074 from FIRST-Tech-Challenge/20240919-122750-release-candidate
FtcRobotController v10.1
2 parents 442c867 + 054017d commit 6af9bb6

File tree

6 files changed

+360
-12
lines changed

6 files changed

+360
-12
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="55"
5-
android:versionName="10.0">
4+
android:versionCode="56"
5+
android:versionName="10.1">
66

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

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

+3
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,9 @@
5858
* When an AprilTag in the TagLibrary is detected, the SDK provides location and orientation of the robot, relative to the field origin.
5959
* This information is provided in the "robotPose" member of the returned "detection".
6060
*
61+
* To learn about the Field Coordinate System that is defined for FTC (and used by this OpMode), see the FTC-DOCS link below:
62+
* https://ftc-docs.firstinspires.org/en/latest/game_specific_resources/field_coordinate_system/field-coordinate-system.html
63+
*
6164
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
6265
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list.
6366
*/
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,191 @@
1+
/*
2+
* Copyright (c) 2024 Phil Malone
3+
*
4+
* Permission is hereby granted, free of charge, to any person obtaining a copy
5+
* of this software and associated documentation files (the "Software"), to deal
6+
* in the Software without restriction, including without limitation the rights
7+
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
8+
* copies of the Software, and to permit persons to whom the Software is
9+
* furnished to do so, subject to the following conditions:
10+
*
11+
* The above copyright notice and this permission notice shall be included in all
12+
* copies or substantial portions of the Software.
13+
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
14+
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
15+
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
16+
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
17+
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
18+
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
19+
* SOFTWARE.
20+
*/
21+
22+
package org.firstinspires.ftc.robotcontroller.external.samples;
23+
24+
import android.util.Size;
25+
26+
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
27+
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
28+
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
29+
import com.qualcomm.robotcore.util.SortOrder;
30+
31+
import org.firstinspires.ftc.robotcore.external.Telemetry;
32+
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
33+
import org.firstinspires.ftc.vision.VisionPortal;
34+
import org.firstinspires.ftc.vision.opencv.ColorBlobLocatorProcessor;
35+
import org.firstinspires.ftc.vision.opencv.ColorRange;
36+
import org.firstinspires.ftc.vision.opencv.ImageRegion;
37+
import org.opencv.core.RotatedRect;
38+
39+
import java.util.List;
40+
41+
/*
42+
* This OpMode illustrates how to use a video source (camera) to locate specifically colored regions
43+
*
44+
* Unlike a "color sensor" which determines the color of an object in the field of view, this "color locator"
45+
* will search the Region Of Interest (ROI) in a camera image, and find any "blobs" of color that match the requested color range.
46+
* These blobs can be further filtered and sorted to find the one most likely to be the item the user is looking for.
47+
*
48+
* To perform this function, a VisionPortal runs a ColorBlobLocatorProcessor process.
49+
* The ColorBlobLocatorProcessor process is created first, and then the VisionPortal is built to use this process.
50+
* The ColorBlobLocatorProcessor analyses the ROI and locates pixels that match the ColorRange to form a "mask".
51+
* The matching pixels are then collected into contiguous "blobs" of pixels. The outer boundaries of these blobs are called its "contour".
52+
* For each blob, the process then creates the smallest possible rectangle "boxFit" that will fully encase the contour.
53+
* The user can then call getBlobs() to retrieve the list of Blobs, where each Blob contains the contour and the boxFit data.
54+
* Note: The default sort order for Blobs is ContourArea, in descending order, so the biggest contours are listed first.
55+
*
56+
* To aid the user, a colored boxFit rectangle is drawn on the camera preview to show the location of each Blob
57+
* The original Blob contour can also be added to the preview. This is helpful when configuring the ColorBlobLocatorProcessor parameters.
58+
*
59+
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
60+
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list
61+
*/
62+
63+
@Disabled
64+
@TeleOp(name = "Concept: Vision Color-Locator", group = "Concept")
65+
public class ConceptVisionColorLocator extends LinearOpMode
66+
{
67+
@Override
68+
public void runOpMode()
69+
{
70+
/* Build a "Color Locator" vision processor based on the ColorBlobLocatorProcessor class.
71+
* - Specify the color range you are looking for. You can use a predefined color, or create you own color range
72+
* .setTargetColorRange(ColorRange.BLUE) // use a predefined color match
73+
* Available predefined colors are: RED, BLUE YELLOW GREEN
74+
* .setTargetColorRange(new ColorRange(ColorSpace.YCrCb, // or define your own color match
75+
* new Scalar( 32, 176, 0),
76+
* new Scalar(255, 255, 132)))
77+
*
78+
* - Focus the color locator by defining a RegionOfInterest (ROI) which you want to search.
79+
* This can be the entire frame, or a sub-region defined using:
80+
* 1) standard image coordinates or 2) a normalized +/- 1.0 coordinate system.
81+
* Use one form of the ImageRegion class to define the ROI.
82+
* ImageRegion.entireFrame()
83+
* ImageRegion.asImageCoordinates(50, 50, 150, 150) 100x100 pixel square near the upper left corner
84+
* ImageRegion.asUnityCenterCoordinates(-0.5, 0.5, 0.5, -0.5) 50% width/height square centered on screen
85+
*
86+
* - Define which contours are included.
87+
* You can get ALL the contours, or you can skip any contours that are completely inside another contour.
88+
* .setContourMode(ColorBlobLocatorProcessor.ContourMode.ALL_FLATTENED_HIERARCHY) // return all contours
89+
* .setContourMode(ColorBlobLocatorProcessor.ContourMode.EXTERNAL_ONLY) // exclude contours inside other contours
90+
* note: EXTERNAL_ONLY helps to avoid bright reflection spots from breaking up areas of solid color.
91+
*
92+
* - turn the display of contours ON or OFF. Turning this on helps debugging but takes up valuable CPU time.
93+
* .setDrawContours(true)
94+
*
95+
* - include any pre-processing of the image or mask before looking for Blobs.
96+
* There are some extra processing you can include to improve the formation of blobs. Using these features requires
97+
* an understanding of how they may effect the final blobs. The "pixels" argument sets the NxN kernel size.
98+
* .setBlurSize(int pixels) Blurring an image helps to provide a smooth color transition between objects, and smoother contours.
99+
* The higher the number of pixels, the more blurred the image becomes.
100+
* Note: Even "pixels" values will be incremented to satisfy the "odd number" requirement.
101+
* Blurring too much may hide smaller features. A "pixels" size of 5 is good for a 320x240 image.
102+
* .setErodeSize(int pixels) Erosion removes floating pixels and thin lines so that only substantive objects remain.
103+
* Erosion can grow holes inside regions, and also shrink objects.
104+
* "pixels" in the range of 2-4 are suitable for low res images.
105+
* .setDilateSize(int pixels) Dilation makes objects more visible by filling in small holes, making lines appear thicker,
106+
* and making filled shapes appear larger. Dilation is useful for joining broken parts of an
107+
* object, such as when removing noise from an image.
108+
* "pixels" in the range of 2-4 are suitable for low res images.
109+
*/
110+
ColorBlobLocatorProcessor colorLocator = new ColorBlobLocatorProcessor.Builder()
111+
.setTargetColorRange(ColorRange.BLUE) // use a predefined color match
112+
.setContourMode(ColorBlobLocatorProcessor.ContourMode.EXTERNAL_ONLY) // exclude blobs inside blobs
113+
.setRoi(ImageRegion.asUnityCenterCoordinates(-0.5, 0.5, 0.5, -0.5)) // search central 1/4 of camera view
114+
.setDrawContours(true) // Show contours on the Stream Preview
115+
.setBlurSize(5) // Smooth the transitions between different colors in image
116+
.build();
117+
118+
/*
119+
* Build a vision portal to run the Color Locator process.
120+
*
121+
* - Add the colorLocator process created above.
122+
* - Set the desired video resolution.
123+
* Since a high resolution will not improve this process, choose a lower resolution that is
124+
* supported by your camera. This will improve overall performance and reduce latency.
125+
* - Choose your video source. This may be
126+
* .setCamera(hardwareMap.get(WebcamName.class, "Webcam 1")) ..... for a webcam
127+
* or
128+
* .setCamera(BuiltinCameraDirection.BACK) ... for a Phone Camera
129+
*/
130+
VisionPortal portal = new VisionPortal.Builder()
131+
.addProcessor(colorLocator)
132+
.setCameraResolution(new Size(320, 240))
133+
.setCamera(hardwareMap.get(WebcamName.class, "Webcam 1"))
134+
.build();
135+
136+
telemetry.setMsTransmissionInterval(50); // Speed up telemetry updates, Just use for debugging.
137+
telemetry.setDisplayFormat(Telemetry.DisplayFormat.MONOSPACE);
138+
139+
// WARNING: To be able to view the stream preview on the Driver Station, this code runs in INIT mode.
140+
while (opModeIsActive() || opModeInInit())
141+
{
142+
telemetry.addData("preview on/off", "... Camera Stream\n");
143+
144+
// Read the current list
145+
List<ColorBlobLocatorProcessor.Blob> blobs = colorLocator.getBlobs();
146+
147+
/*
148+
* The list of Blobs can be filtered to remove unwanted Blobs.
149+
* Note: All contours will be still displayed on the Stream Preview, but only those that satisfy the filter
150+
* conditions will remain in the current list of "blobs". Multiple filters may be used.
151+
*
152+
* Use any of the following filters.
153+
*
154+
* ColorBlobLocatorProcessor.Util.filterByArea(minArea, maxArea, blobs);
155+
* A Blob's area is the number of pixels contained within the Contour. Filter out any that are too big or small.
156+
* Start with a large range and then refine the range based on the likely size of the desired object in the viewfinder.
157+
*
158+
* ColorBlobLocatorProcessor.Util.filterByDensity(minDensity, maxDensity, blobs);
159+
* A blob's density is an indication of how "full" the contour is.
160+
* If you put a rubber band around the contour you would get the "Convex Hull" of the contour.
161+
* The density is the ratio of Contour-area to Convex Hull-area.
162+
*
163+
* ColorBlobLocatorProcessor.Util.filterByAspectRatio(minAspect, maxAspect, blobs);
164+
* A blob's Aspect ratio is the ratio of boxFit long side to short side.
165+
* A perfect Square has an aspect ratio of 1. All others are > 1
166+
*/
167+
ColorBlobLocatorProcessor.Util.filterByArea(50, 20000, blobs); // filter out very small blobs.
168+
169+
/*
170+
* The list of Blobs can be sorted using the same Blob attributes as listed above.
171+
* 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);
175+
*/
176+
177+
telemetry.addLine(" Area Density Aspect Center");
178+
179+
// Display the size (area) and center location for each Blob.
180+
for(ColorBlobLocatorProcessor.Blob b : blobs)
181+
{
182+
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));
185+
}
186+
187+
telemetry.update();
188+
sleep(50);
189+
}
190+
}
191+
}

0 commit comments

Comments
 (0)