Updated ftclib.

Fixed CameraStreamProcessor bug to prevent adding RectInfo if the processor is not enabled.
Made the CameraStreamProcessor easier to use.
This commit is contained in:
Titan Robotics Club
2024-10-13 13:10:01 -07:00
parent 54de20bce1
commit 02dc2b49c5
4 changed files with 29 additions and 4 deletions

View File

@ -223,6 +223,7 @@ public class FtcTest extends FtcTeleOp
case VISION_TEST: case VISION_TEST:
if (robot.vision != null) if (robot.vision != null)
{ {
robot.vision.setCameraStreamEnabled(true);
if (robot.vision.vision != null) if (robot.vision.vision != null)
{ {
exposure = robot.vision.vision.getCurrentExposure(); exposure = robot.vision.vision.getCurrentExposure();
@ -258,6 +259,7 @@ public class FtcTest extends FtcTeleOp
if (robot.vision != null && robot.vision.rawColorBlobVision != null) if (robot.vision != null && robot.vision.rawColorBlobVision != null)
{ {
robot.globalTracer.traceInfo(moduleName, "Enabling FtcRawEocvVision."); robot.globalTracer.traceInfo(moduleName, "Enabling FtcRawEocvVision.");
robot.vision.setCameraStreamEnabled(true);
robot.vision.setRawColorBlobVisionEnabled(true); robot.vision.setRawColorBlobVisionEnabled(true);
colorThresholds = robot.vision.getRawColorBlobThresholds(); colorThresholds = robot.vision.getRawColorBlobThresholds();
colorThresholdIndex = 0; colorThresholdIndex = 0;

View File

@ -195,6 +195,7 @@ public class Robot
// //
if (vision != null) if (vision != null)
{ {
vision.setCameraStreamEnabled(false);
if (vision.rawColorBlobVision != null) if (vision.rawColorBlobVision != null)
{ {
globalTracer.traceInfo(moduleName, "Disabling RawColorBlobVision."); globalTracer.traceInfo(moduleName, "Disabling RawColorBlobVision.");

View File

@ -239,7 +239,7 @@ public class Vision
{ {
if (vision != null) if (vision != null)
{ {
vision.getVisionPortal().close(); vision.close();
} }
} //close } //close
@ -375,6 +375,12 @@ public class Vision
TrcVisionTargetInfo<TrcOpenCvDetector.DetectedObject<?>> colorBlobInfo = TrcVisionTargetInfo<TrcOpenCvDetector.DetectedObject<?>> colorBlobInfo =
rawColorBlobVision != null? rawColorBlobVision.getBestDetectedTargetInfo(null, null, 0.0, 0.0): null; rawColorBlobVision != null? rawColorBlobVision.getBestDetectedTargetInfo(null, null, 0.0, 0.0): null;
if (cameraStreamProcessor != null && colorBlobInfo != null)
{
cameraStreamProcessor.addRectInfo(
colorBlobInfo.detectedObj.label, colorBlobInfo.detectedObj.getRotatedRectVertices());
}
if (lineNum != -1) if (lineNum != -1)
{ {
robot.dashboard.displayPrintf( robot.dashboard.displayPrintf(
@ -481,7 +487,10 @@ public class Vision
*/ */
public void setCameraStreamEnabled(boolean enabled) public void setCameraStreamEnabled(boolean enabled)
{ {
setVisionProcessorEnabled(cameraStreamProcessor, enabled); if (vision != null && cameraStreamProcessor != null)
{
cameraStreamProcessor.setCameraStreamEnabled(vision, enabled);
}
} //setCameraStreamEnabled } //setCameraStreamEnabled
/** /**
@ -491,7 +500,7 @@ public class Vision
*/ */
public boolean isCameraStreamEnabled() public boolean isCameraStreamEnabled()
{ {
return isVisionProcessorEnabled(cameraStreamProcessor); return cameraStreamProcessor != null && cameraStreamProcessor.isCameraStreamEnabled();
} //isAprilTagVisionEnabled } //isAprilTagVisionEnabled
/** /**
@ -526,6 +535,13 @@ public class Vision
TrcVisionTargetInfo<FtcVisionAprilTag.DetectedObject> aprilTagInfo = TrcVisionTargetInfo<FtcVisionAprilTag.DetectedObject> aprilTagInfo =
aprilTagVision.getBestDetectedTargetInfo(id, null); aprilTagVision.getBestDetectedTargetInfo(id, null);
if (cameraStreamProcessor != null && aprilTagInfo != null)
{
cameraStreamProcessor.addRectInfo(
Integer.toString(aprilTagInfo.detectedObj.aprilTagDetection.id),
aprilTagInfo.detectedObj.getRotatedRectVertices());
}
if (aprilTagInfo != null && robot.blinkin != null) if (aprilTagInfo != null && robot.blinkin != null)
{ {
robot.blinkin.setDetectedPattern(BlinkinLEDs.APRIL_TAG); robot.blinkin.setDetectedPattern(BlinkinLEDs.APRIL_TAG);
@ -704,6 +720,12 @@ public class Vision
break; break;
} }
if (cameraStreamProcessor != null && colorBlobInfo != null)
{
cameraStreamProcessor.addRectInfo(
colorBlobInfo.detectedObj.label, colorBlobInfo.detectedObj.getRotatedRectVertices());
}
if (colorBlobInfo != null && robot.blinkin != null) if (colorBlobInfo != null && robot.blinkin != null)
{ {
robot.blinkin.setDetectedPattern(colorBlobName); robot.blinkin.setDetectedPattern(colorBlobName);