mirror of
https://github.com/trc492/FtcTemplate.git
synced 2025-07-01 13:01:24 -07:00
Updated ftclib.
Added support to annotate detected object rect for the camera stream processor.
This commit is contained in:
Submodule TeamCode/src/main/java/ftclib updated: 4102f159ad...2af0213e99
@ -1,49 +0,0 @@
|
|||||||
package teamcode.vision;
|
|
||||||
|
|
||||||
import android.graphics.Bitmap;
|
|
||||||
import android.graphics.Canvas;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.function.Consumer;
|
|
||||||
import org.firstinspires.ftc.robotcore.external.function.Continuation;
|
|
||||||
import org.firstinspires.ftc.robotcore.external.stream.CameraStreamSource;
|
|
||||||
import org.firstinspires.ftc.robotcore.internal.camera.calibration.CameraCalibration;
|
|
||||||
import org.firstinspires.ftc.vision.VisionProcessor;
|
|
||||||
import org.opencv.android.Utils;
|
|
||||||
import org.opencv.core.Mat;
|
|
||||||
|
|
||||||
import java.util.concurrent.atomic.AtomicReference;
|
|
||||||
|
|
||||||
public class CameraStreamProcessor implements VisionProcessor, CameraStreamSource
|
|
||||||
{
|
|
||||||
private final AtomicReference<Bitmap> lastFrame =
|
|
||||||
new AtomicReference<>(Bitmap.createBitmap(1, 1, Bitmap.Config.RGB_565));
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void init(int width, int height, CameraCalibration calibration)
|
|
||||||
{
|
|
||||||
lastFrame.set(Bitmap.createBitmap(width, height, Bitmap.Config.RGB_565));
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public Object processFrame(Mat frame, long captureTimeNanos)
|
|
||||||
{
|
|
||||||
Bitmap b = Bitmap.createBitmap(frame.width(), frame.height(), Bitmap.Config.RGB_565);
|
|
||||||
Utils.matToBitmap(frame, b);
|
|
||||||
lastFrame.set(b);
|
|
||||||
return null;
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void onDrawFrame(
|
|
||||||
Canvas canvas, int onscreenWidth, int onscreenHeight, float scaleBmpPxToCanvasPx, float scaleCanvasDensity,
|
|
||||||
Object userContext)
|
|
||||||
{
|
|
||||||
// do nothing
|
|
||||||
}
|
|
||||||
|
|
||||||
@Override
|
|
||||||
public void getFrameBitmap(Continuation<? extends Consumer<Bitmap>> continuation)
|
|
||||||
{
|
|
||||||
continuation.dispatch(bitmapConsumer -> bitmapConsumer.accept(lastFrame.get()));
|
|
||||||
}
|
|
||||||
}
|
|
@ -35,6 +35,7 @@ import org.openftc.easyopencv.OpenCvCameraFactory;
|
|||||||
import java.util.ArrayList;
|
import java.util.ArrayList;
|
||||||
|
|
||||||
import ftclib.robotcore.FtcOpMode;
|
import ftclib.robotcore.FtcOpMode;
|
||||||
|
import ftclib.vision.FtcCameraStreamProcessor;
|
||||||
import ftclib.vision.FtcEocvColorBlobProcessor;
|
import ftclib.vision.FtcEocvColorBlobProcessor;
|
||||||
import ftclib.vision.FtcLimelightVision;
|
import ftclib.vision.FtcLimelightVision;
|
||||||
import ftclib.vision.FtcRawEocvColorBlobPipeline;
|
import ftclib.vision.FtcRawEocvColorBlobPipeline;
|
||||||
@ -90,7 +91,7 @@ public class Vision
|
|||||||
private FtcRawEocvColorBlobPipeline rawColorBlobPipeline;
|
private FtcRawEocvColorBlobPipeline rawColorBlobPipeline;
|
||||||
public FtcRawEocvVision rawColorBlobVision;
|
public FtcRawEocvVision rawColorBlobVision;
|
||||||
public FtcLimelightVision limelightVision;
|
public FtcLimelightVision limelightVision;
|
||||||
public CameraStreamProcessor cameraStreamProcessor;
|
public FtcCameraStreamProcessor cameraStreamProcessor;
|
||||||
public FtcVisionAprilTag aprilTagVision;
|
public FtcVisionAprilTag aprilTagVision;
|
||||||
private AprilTagProcessor aprilTagProcessor;
|
private AprilTagProcessor aprilTagProcessor;
|
||||||
public FtcVisionEocvColorBlob redBlobVision;
|
public FtcVisionEocvColorBlob redBlobVision;
|
||||||
@ -165,7 +166,7 @@ public class Vision
|
|||||||
|
|
||||||
if (RobotParams.Preferences.useCameraStreamProcessor)
|
if (RobotParams.Preferences.useCameraStreamProcessor)
|
||||||
{
|
{
|
||||||
cameraStreamProcessor = new CameraStreamProcessor();
|
cameraStreamProcessor = new FtcCameraStreamProcessor();
|
||||||
visionProcessorsList.add(cameraStreamProcessor);
|
visionProcessorsList.add(cameraStreamProcessor);
|
||||||
// FtcDashboard.getInstance().startCameraStream(cameraStreamProcessor, 0);
|
// FtcDashboard.getInstance().startCameraStream(cameraStreamProcessor, 0);
|
||||||
}
|
}
|
||||||
|
Reference in New Issue
Block a user