Skip to content

Commit

Permalink
Merge v3.5.2
Browse files Browse the repository at this point in the history
v3.5.2
  • Loading branch information
serivesmejia authored Sep 24, 2023
2 parents 128a1c7 + 5728aec commit e75c3da
Show file tree
Hide file tree
Showing 20 changed files with 226 additions and 53 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,14 @@ class PipelineListIconRenderer(
list, value, index, isSelected, cellHasFocus
) as JLabel

val source = pipelineManager.pipelines[indexMapProvider()[index]!!].source

label.icon = when(source) {
PipelineSource.COMPILED_ON_RUNTIME -> gearsIcon
else -> hammerIcon
}
try {
val source = pipelineManager.pipelines[indexMapProvider()[index]!!].source

label.icon = when (source) {
PipelineSource.COMPILED_ON_RUNTIME -> gearsIcon
else -> hammerIcon
}
} catch(ignored: Exception) { }

return label
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
import com.github.serivesmejia.eocvsim.gui.Visualizer;
import com.github.serivesmejia.eocvsim.gui.component.visualizer.pipeline.SourceSelectorPanel;
import com.github.serivesmejia.eocvsim.input.source.ImageSource;
import com.github.serivesmejia.eocvsim.input.source.NullSource;
import com.github.serivesmejia.eocvsim.pipeline.PipelineManager;
import com.github.serivesmejia.eocvsim.util.SysUtil;
import org.opencv.core.Mat;
Expand Down Expand Up @@ -70,6 +71,7 @@ public void init() {
lastMatFromSource = new Mat();

Size size = new Size(640, 480);

createDefaultImgInputSource("/images/ug_4.jpg", "ug_eocvsim_4.jpg", "Ultimate Goal 4 Ring", size);
createDefaultImgInputSource("/images/ug_1.jpg", "ug_eocvsim_1.jpg", "Ultimate Goal 1 Ring", size);
createDefaultImgInputSource("/images/ug_0.jpg", "ug_eocvsim_0.jpg", "Ultimate Goal 0 Ring", size);
Expand Down Expand Up @@ -202,7 +204,13 @@ public boolean setInputSource(String sourceName, boolean makeDefault) {
}

public boolean setInputSource(String sourceName) {
InputSource src = sources.get(sourceName);
InputSource src = null;

if(sourceName == null) {
src = new NullSource();
} else {
src = sources.get(sourceName);
}

if (src != null) {
src.reset();
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
package com.github.serivesmejia.eocvsim.input.source;

import com.github.serivesmejia.eocvsim.input.InputSource;
import org.opencv.core.Mat;

import javax.swing.filechooser.FileFilter;

public class NullSource extends InputSource {
@Override
public boolean init() {
return true;
}

@Override
public void reset() {

}

@Override
public void close() {

}

Mat emptyMat = new Mat();

@Override
public Mat update() {
return emptyMat;
}

@Override
public void onPause() {

}

@Override
public void onResume() {

}

@Override
protected InputSource internalCloneSource() {
return new NullSource();
}

@Override
public FileFilter getFileFilters() {
return null;
}

@Override
public long getCaptureTimeNanos() {
return System.nanoTime();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -56,10 +56,13 @@ import kotlin.coroutines.EmptyCoroutineContext
import kotlin.math.roundToLong

@OptIn(DelicateCoroutinesApi::class)
class PipelineManager(var eocvSim: EOCVSim, val pipelineStatisticsCalculator: PipelineStatisticsCalculator) {
class PipelineManager(
var eocvSim: EOCVSim,
val pipelineStatisticsCalculator: PipelineStatisticsCalculator
) {

companion object {
const val MAX_ALLOWED_ACTIVE_PIPELINE_CONTEXTS = 5
const val MAX_ALLOWED_ACTIVE_PIPELINE_CONTEXTS = 18

var staticSnapshot: PipelineSnapshot? = null
private set
Expand Down Expand Up @@ -190,7 +193,7 @@ class PipelineManager(var eocvSim: EOCVSim, val pipelineStatisticsCalculator: Pi

if(telemetry is TelemetryImpl) {
telemetry.errItem.caption = "[/!\\]"
telemetry.errItem.setValue("Uncaught exception thrown in\n pipeline, check Workspace -> Output.")
telemetry.errItem.setValue("Uncaught exception thrown, check Workspace -> Output.")
telemetry.forceTelemetryTransmission()
}
}
Expand Down Expand Up @@ -222,6 +225,14 @@ class PipelineManager(var eocvSim: EOCVSim, val pipelineStatisticsCalculator: Pi
}
}
}

pipelineExceptionTracker.onPipelineException {
if(currentPipeline != null) {
for (pipelineHandler in pipelineHandlers) {
pipelineHandler.onException()
}
}
}
}

private fun applyStaticSnapOrDef() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@ interface PipelineHandler {

fun processFrame(currentInputSource: InputSource?)

fun onException()

fun onChange(beforePipeline: OpenCvPipeline?, newPipeline: OpenCvPipeline, telemetry: Telemetry)

}
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ import com.github.serivesmejia.eocvsim.util.loggerForThis
class PipelineExceptionTracker(private val pipelineManager: PipelineManager) {

companion object {
const val millisExceptionExpire = 25000L
const val millisExceptionExpire = 35000L
const val cutStacktraceLines = 9
}

Expand Down Expand Up @@ -70,8 +70,8 @@ class PipelineExceptionTracker(private val pipelineManager: PipelineManager) {
ex
)

logger.warn("Note that to avoid spam, continuously equal thrown exceptions are only logged once.")
logger.warn("It will be reported once the pipeline stops throwing the exception after $millisExceptionExpire ms")
logger.info("Note that to avoid spam, continuously equal thrown exceptions are only logged once.")
logger.info("It will be reported if the pipeline stops throwing the exception after $millisExceptionExpire ms")

exceptionsThrown[ex] = PipelineException(
0, exStr, System.currentTimeMillis()
Expand Down Expand Up @@ -111,17 +111,17 @@ class PipelineExceptionTracker(private val pipelineManager: PipelineManager) {

val message: String get() {
if(currentPipeline == null)
return "**No pipeline selected**"
return "**Nothing currently running**"

val messageBuilder = StringBuilder()
val pipelineName = currentPipeline!!.clazz.simpleName

if(exceptionsThrown.isNotEmpty()) {
messageBuilder
.append("**Pipeline $pipelineName is throwing ${exceptionsThrown.size} exception(s)**")
.append("**\"$pipelineName\" is throwing ${exceptionsThrown.size} exception(s)**")
.appendLine("\n")
} else {
messageBuilder.append("**Pipeline $pipelineName ")
messageBuilder.append("**\"$pipelineName\" ")

if(pipelineManager.paused) {
messageBuilder.append("is paused (last time was running at ${pipelineManager.pipelineFpsCounter.fps} FPS)")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,18 +23,25 @@ class OpModePipelineHandler(val inputSourceManager: InputSourceManager, private
override fun preInit() {
if(pipeline == null) return

inputSourceManager.setInputSource(inputSourceManager.defaultInputSource)
ThreadSourceHander.register(VisionInputSourceHander(pipeline!!.notifier, viewport))
inputSourceManager.setInputSource(null)
ThreadSourceHander.register(VisionInputSourceHander(pipeline?.notifier ?: return, viewport))

pipeline?.telemetry = telemetry
pipeline?.hardwareMap = HardwareMap()
pipeline?.hardwareMap = HardwareMap();
}

override fun init() { }

override fun processFrame(currentInputSource: InputSource?) {
}

override fun onException() {
if(pipeline != null) {
pipeline!!.forceStop()
onStop.run()
}
}

override fun onChange(beforePipeline: OpenCvPipeline?, newPipeline: OpenCvPipeline, telemetry: Telemetry) {
if(beforePipeline is OpMode) {
beforePipeline.forceStop()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,15 @@ package io.github.deltacv.eocvsim.input
import com.github.serivesmejia.eocvsim.input.InputSource
import com.github.serivesmejia.eocvsim.util.loggerForThis
import io.github.deltacv.vision.external.source.VisionSourceBase
import io.github.deltacv.vision.external.util.ThrowableHandler
import io.github.deltacv.vision.external.util.Timestamped
import org.opencv.core.Mat
import org.opencv.core.Size

class VisionInputSource(
private val inputSource: InputSource
) : VisionSourceBase() {
private val inputSource: InputSource,
throwableHandler: ThrowableHandler? = null
) : VisionSourceBase(throwableHandler) {

val logger by loggerForThis()

Expand Down Expand Up @@ -37,11 +39,11 @@ class VisionInputSource(
private val emptyMat = Mat()

override fun pullFrame(): Timestamped<Mat> {
try {
return try {
val frame = inputSource.update();
return Timestamped(frame, inputSource.captureTimeNanos)
Timestamped(frame, inputSource.captureTimeNanos)
} catch(e: Exception) {
return Timestamped(emptyMat, 0)
Timestamped(emptyMat, 0)
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ import io.github.deltacv.vision.external.source.VisionSource
import io.github.deltacv.vision.external.source.VisionSourceHander
import io.github.deltacv.vision.internal.opmode.OpModeNotifier
import io.github.deltacv.vision.internal.opmode.OpModeState
import io.github.deltacv.vision.internal.opmode.RedirectToOpModeThrowableHandler
import org.opencv.core.Mat
import org.opencv.core.Size
import org.opencv.videoio.VideoCapture
Expand Down Expand Up @@ -52,7 +53,7 @@ class VisionInputSourceHander(val notifier: OpModeNotifier, val viewport: OpenCv
else throw IllegalArgumentException("Unknown source $name")

CameraSource(index, Size(640.0, 480.0))
})
}, RedirectToOpModeThrowableHandler(notifier))

notifier.onStateChange {
when(notifier.state) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,4 +41,7 @@ class TimestampedPipelineHandler : SpecificPipelineHandler<TimestampedOpenCvPipe
override fun processFrame(currentInputSource: InputSource?) {
pipeline?.setTimestamp(currentInputSource?.captureTimeNanos ?: 0L)
}

override fun onException() {
}
}
7 changes: 7 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,13 @@ For bug reporting or feature requesting, use the [issues tab](https://github.com

### Formerly, EOCV-Sim was hosted on a [personal account repo](https://github.com/serivesmejia/EOCV-Sim/). Released prior to 3.0.0 can be found there for historic purposes.

### [v3.5.2 - CenterStage AprilTags](https://github.com/deltacv/EOCV-Sim/releases/tag/v3.5.2)
- This is the 20th release for EOCV-Sim
- Changelog
- Addresses the changes made in the FTC SDK 9.0 for the 2023-2024 season:
- Adds the CENTERSTAGE AprilTag Library with accurate tag locations
- Exceptions thrown from OpenCvCamera/VisionPortal's attached user code created within OpModes is now reported as part of EOCV-Sim's output dialog to allow for easier debugging

### [v3.5.1 - FTC SDK 9.0](https://github.com/deltacv/EOCV-Sim/releases/tag/v3.5.1)
- This is the 19th release for EOCV-Sim
- Changelog
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,9 @@ OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
import org.slf4j.LoggerFactory;

public abstract class LinearOpMode extends OpMode {

protected final Object lock = new Object();
private LinearOpModeHelperThread helper = new LinearOpModeHelperThread(this);
private RuntimeException catchedException = null;

public LinearOpMode() {
}
Expand Down Expand Up @@ -174,11 +174,6 @@ public final void start() {

@Override
public final void loop() {
synchronized (lock) {
if (catchedException != null) {
throw catchedException;
}
}
}

@Override
Expand Down Expand Up @@ -221,9 +216,7 @@ public void run() {
Thread.currentThread().interrupt();
logger.info("{}: interrupted", opMode.getClass().getSimpleName());
} catch (RuntimeException e) {
synchronized (opMode.lock) {
opMode.catchedException = e;
}
opMode.notifier.notify(e);
}

logger.info("{}: stopped", opMode.getClass().getSimpleName());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,6 @@ public void requestOpModeStop() {
}

/* BEGIN OpenCvPipeline Impl */

private boolean stopped = false;

@Override
Expand Down Expand Up @@ -178,14 +177,26 @@ public final Mat processFrame(Mat input, long captureTimeNanos) {
break;
}

Throwable e = notifier.pollException();

if(e != null) {
if(e instanceof RuntimeException) {
throw (RuntimeException) e;
} else if(e instanceof Error) {
throw (Error) e;
} else {
throw new RuntimeException(e);
}
}

return null; // OpModes don't actually show anything to the viewport, we'll delegate that to OpenCvCamera-s
}

@Override
public final void onViewportTapped() {
}

public void forceStop() {
protected void forceStop() {
if(stopped) return;

notifier.notify(OpModeState.STOP);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,6 @@ public void onFrameStart() {
//
// Inheritance from Sourced
//

@Override
public void onNewFrame(Mat frame, long timestamp) {
if(!isStreaming()) return;
Expand Down
Loading

0 comments on commit e75c3da

Please sign in to comment.