Package ftclib.vision
Class FtcCameraStreamProcessor
java.lang.Object
ftclib.vision.FtcCameraStreamProcessor
- All Implemented Interfaces:
org.firstinspires.ftc.robotcore.external.stream.CameraStreamSource
,org.firstinspires.ftc.vision.VisionProcessor
public class FtcCameraStreamProcessor
extends Object
implements org.firstinspires.ftc.vision.VisionProcessor, org.firstinspires.ftc.robotcore.external.stream.CameraStreamSource
-
Nested Class Summary
Nested Classes -
Field Summary
FieldsModifier and TypeFieldDescriptionprivate static final int
private static final float
private static final int
private static final float
private final ArrayList<FtcCameraStreamProcessor.RectInfo>
private final AtomicReference<android.graphics.Bitmap>
private final android.graphics.Paint
private boolean
private final android.graphics.Paint
-
Constructor Summary
ConstructorsConstructorDescriptionConstructor: Create an instance of the object.FtcCameraStreamProcessor
(Integer lineColor, Float lineWidth, Integer textColor, Float textSize) Constructor: Create an instance of the object. -
Method Summary
Modifier and TypeMethodDescriptionvoid
addRectInfo
(String label, org.opencv.core.Point[] vertices) This method adds info about a detected object so that we can annotate a rectangle around the object in the video stream.void
getFrameBitmap
(org.firstinspires.ftc.robotcore.external.function.Continuation<? extends org.firstinspires.ftc.robotcore.external.function.Consumer<android.graphics.Bitmap>> continuation) Requests a single frame bitmap.void
init
(int width, int height, org.firstinspires.ftc.robotcore.internal.camera.calibration.CameraCalibration calibration) boolean
This method checks if the camera stream is enabled.void
onDrawFrame
(android.graphics.Canvas canvas, int onscreenWidth, int onscreenHeight, float scaleBmpPxToCanvasPx, float scaleCanvasDensity, Object userContext) processFrame
(org.opencv.core.Mat frame, long captureTimeNanos) void
setAnnotationAttributes
(Integer lineColor, Float lineWidth, Integer textColor, Float textSize) This method sets the annotation rectangle and text attributes such as rectangle line width/color and label text color/size.void
setCameraStreamEnabled
(FtcVision vision, boolean enabled) This method enables/disables camera stream.
-
Field Details
-
DEF_LINE_COLOR
private static final int DEF_LINE_COLOR- See Also:
-
DEF_LINE_WIDTH
private static final float DEF_LINE_WIDTH- See Also:
-
DEF_TEXT_COLOR
private static final int DEF_TEXT_COLOR- See Also:
-
DEF_TEXT_SIZE
private static final float DEF_TEXT_SIZE- See Also:
-
lastFrame
-
detectedRects
-
linePaint
private final android.graphics.Paint linePaint -
textPaint
private final android.graphics.Paint textPaint -
processorEnabled
private boolean processorEnabled
-
-
Constructor Details
-
FtcCameraStreamProcessor
public FtcCameraStreamProcessor(Integer lineColor, Float lineWidth, Integer textColor, Float textSize) Constructor: Create an instance of the object.- Parameters:
lineColor
- specifies the line color to draw the bounding rectangle, can be null if not provided in which case default color is used.lineWidth
- specifies the line width to draw the bounding rectangle, can be null if not provided in which case default width is used.textColor
- specifies the text color to draw the label text, can be null if not provided in which case default color is used.textSize
- specifies the text size to draw the label text, can be null if not provided in which case default text size is used.
-
FtcCameraStreamProcessor
public FtcCameraStreamProcessor()Constructor: Create an instance of the object.
-
-
Method Details
-
setAnnotationAttributes
public void setAnnotationAttributes(Integer lineColor, Float lineWidth, Integer textColor, Float textSize) This method sets the annotation rectangle and text attributes such as rectangle line width/color and label text color/size.- Parameters:
lineColor
- specifies the line color to draw the bounding rectangle, can be null if not provided in which case default color or previously set color is used.lineWidth
- specifies the line width to draw the bounding rectangle, can be null if not provided in which case default width or previously set width is used.textColor
- specifies the text color to draw the label text, can be null if not provided in which case default color or previously set color is used.textSize
- specifies the text size to draw the label text, can be null if not provided in which case default text size or previously set size is used.
-
setCameraStreamEnabled
This method enables/disables camera stream.- Parameters:
vision
- specifies the FtcVision object.enabled
- specifies true to enable camera stream, false to disable.
-
isCameraStreamEnabled
public boolean isCameraStreamEnabled()This method checks if the camera stream is enabled.- Returns:
- true if the camera stream is enabled, false otherwise.
-
addRectInfo
This method adds info about a detected object so that we can annotate a rectangle around the object in the video stream.- Parameters:
label
- specifies the label of the object.vertices
- specifies the vertices of the rectangle around the detected object.
-
init
public void init(int width, int height, org.firstinspires.ftc.robotcore.internal.camera.calibration.CameraCalibration calibration) -
processFrame
-
onDrawFrame
public void onDrawFrame(android.graphics.Canvas canvas, int onscreenWidth, int onscreenHeight, float scaleBmpPxToCanvasPx, float scaleCanvasDensity, Object userContext) -
getFrameBitmap
public void getFrameBitmap(org.firstinspires.ftc.robotcore.external.function.Continuation<? extends org.firstinspires.ftc.robotcore.external.function.Consumer<android.graphics.Bitmap>> continuation) Requests a single frame bitmap.- Specified by:
getFrameBitmap
in interfaceorg.firstinspires.ftc.robotcore.external.stream.CameraStreamSource
- Parameters:
continuation
- frame bitmap consumer continuation
-