Skip to content

Commit

Permalink
Make VisionProcessors be automatically detected alongside pipelines
Browse files Browse the repository at this point in the history
  • Loading branch information
serivesmejia committed Aug 19, 2023
1 parent 8661940 commit 907fe5e
Show file tree
Hide file tree
Showing 11 changed files with 149 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,12 @@ import com.github.serivesmejia.eocvsim.EOCVSim
import com.github.serivesmejia.eocvsim.gui.DialogFactory
import com.github.serivesmejia.eocvsim.pipeline.compiler.CompiledPipelineManager
import com.github.serivesmejia.eocvsim.pipeline.handler.PipelineHandler
import com.github.serivesmejia.eocvsim.pipeline.instantiator.DefaultPipelineInstantiator
import com.github.serivesmejia.eocvsim.pipeline.instantiator.PipelineInstantiator
import com.github.serivesmejia.eocvsim.pipeline.instantiator.processor.ProcessorInstantiator
import com.github.serivesmejia.eocvsim.pipeline.util.PipelineExceptionTracker
import com.github.serivesmejia.eocvsim.pipeline.util.PipelineSnapshot
import com.github.serivesmejia.eocvsim.util.ReflectUtil
import com.github.serivesmejia.eocvsim.util.StrUtil
import com.github.serivesmejia.eocvsim.util.event.EventHandler
import com.github.serivesmejia.eocvsim.util.exception.MaxActiveContextsException
Expand All @@ -39,10 +43,12 @@ import io.github.deltacv.common.pipeline.util.PipelineStatisticsCalculator
import kotlinx.coroutines.*
import org.firstinspires.ftc.robotcore.external.Telemetry
import org.firstinspires.ftc.robotcore.internal.opmode.TelemetryImpl
import org.firstinspires.ftc.vision.VisionProcessor
import org.opencv.core.Mat
import org.openftc.easyopencv.OpenCvPipeline
import org.openftc.easyopencv.OpenCvViewport
import org.openftc.easyopencv.processFrameInternal
import java.lang.RuntimeException
import java.lang.reflect.Constructor
import java.lang.reflect.Field
import java.util.*
Expand Down Expand Up @@ -129,6 +135,7 @@ class PipelineManager(var eocvSim: EOCVSim, val pipelineStatisticsCalculator: Pi
@JvmField val compiledPipelineManager = CompiledPipelineManager(this)

private val pipelineHandlers = mutableListOf<PipelineHandler>()
private val pipelineInstantiators = mutableMapOf<Class<*>, PipelineInstantiator>()

//counting and tracking exceptions for logging and reporting purposes
val pipelineExceptionTracker = PipelineExceptionTracker(this)
Expand All @@ -138,6 +145,7 @@ class PipelineManager(var eocvSim: EOCVSim, val pipelineStatisticsCalculator: Pi
enum class PauseReason {
USER_REQUESTED, IMAGE_ONE_ANALYSIS, NOT_PAUSED
}

fun init() {
logger.info("Initializing...")

Expand All @@ -155,6 +163,11 @@ class PipelineManager(var eocvSim: EOCVSim, val pipelineStatisticsCalculator: Pi

logger.info("Found " + pipelines.size + " pipeline(s)")

// add instantiator for OpenCvPipeline
addInstantiator(OpenCvPipeline::class.java, DefaultPipelineInstantiator)
// add instantiator for VisionProcessor (wraps a VisionProcessor around an OpenCvPipeline)
addInstantiator(VisionProcessor::class.java, ProcessorInstantiator)

// changing to initial pipeline
onUpdate.doOnce {
if(compiledPipelineManager.isBuildRunning && staticSnapshot != null)
Expand Down Expand Up @@ -287,7 +300,7 @@ class PipelineManager(var eocvSim: EOCVSim, val pipelineStatisticsCalculator: Pi

pipelineStatisticsCalculator.beforeProcessFrame()

val pipelineResult =currentPipeline?.processFrameInternal(inputMat)
val pipelineResult = currentPipeline?.processFrameInternal(inputMat)

pipelineStatisticsCalculator.afterProcessFrame()

Expand Down Expand Up @@ -436,10 +449,24 @@ class PipelineManager(var eocvSim: EOCVSim, val pipelineStatisticsCalculator: Pi
pipelineHandlers.add(handler)
}

fun addInstantiator(instantiatorFor: Class<*>, instantiator: PipelineInstantiator) {
pipelineInstantiators.put(instantiatorFor, instantiator)
}

fun getInstantiatorFor(clazz: Class<*>): PipelineInstantiator? {
for((instantiatorFor, instantiator) in pipelineInstantiators) {
if(ReflectUtil.hasSuperclass(clazz, instantiatorFor)) {
return instantiator
}
}

return null
}

@Suppress("UNCHECKED_CAST")
@JvmOverloads fun addPipelineClass(C: Class<*>, source: PipelineSource = PipelineSource.CLASSPATH) {
try {
pipelines.add(PipelineData(source, C as Class<out OpenCvPipeline>))
pipelines.add(PipelineData(source, C))
} catch (ex: Exception) {
logger.warn("Error while adding pipeline class", ex)
updateExceptionTracker(ex)
Expand Down Expand Up @@ -527,21 +554,16 @@ class PipelineManager(var eocvSim: EOCVSim, val pipelineStatisticsCalculator: Pi

debugLogCalled("forceChangePipeline")

var constructor: Constructor<*>
val instantiator = getInstantiatorFor(pipelineClass)

try {
nextTelemetry = TelemetryImpl().apply {
// send telemetry updates to the ui
addTransmissionReceiver(eocvSim.visualizer.telemetryPanel)
}

try { //instantiate pipeline if it has a constructor of a telemetry parameter
constructor = pipelineClass.getConstructor(Telemetry::class.java)
nextPipeline = constructor.newInstance(nextTelemetry) as OpenCvPipeline
} catch (ex: NoSuchMethodException) { //instantiating with a constructor of no params
constructor = pipelineClass.getConstructor()
nextPipeline = constructor.newInstance() as OpenCvPipeline
}
nextPipeline = instantiator?.instantiate(pipelineClass, nextTelemetry)
?: throw RuntimeException("No instantiator found for pipeline class ${pipelineClass.name}")

logger.info("Instantiated pipeline class ${pipelineClass.name}")
} catch (ex: NoSuchMethodException) {
Expand Down Expand Up @@ -769,6 +791,6 @@ enum class PipelineFps(val fps: Int, val coolName: String) {
}
}

data class PipelineData(val source: PipelineSource, val clazz: Class<out OpenCvPipeline>)
data class PipelineData(val source: PipelineSource, val clazz: Class<*>)

enum class PipelineSource { CLASSPATH, COMPILED_ON_RUNTIME }
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ class CompiledPipelineManager(private val pipelineManager: PipelineManager) {
try {
currentPipelineClassLoader = PipelineClassLoader(PIPELINES_OUTPUT_JAR)

val pipelines = mutableListOf<Class<out OpenCvPipeline>>()
val pipelines = mutableListOf<Class<*>>()

for(pipelineClass in currentPipelineClassLoader!!.pipelineClasses) {
pipelines.add(pipelineClass)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ class PipelineClassLoader(pipelinesJar: File) : ClassLoader() {
private val zipFile = ZipFile(pipelinesJar)
private val loadedClasses = mutableMapOf<String, Class<*>>()

var pipelineClasses: List<Class<out OpenCvPipeline>>
var pipelineClasses: List<Class<*>>
private set

init {
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
package com.github.serivesmejia.eocvsim.pipeline.instantiator

import com.github.serivesmejia.eocvsim.pipeline.PipelineManager
import org.firstinspires.ftc.robotcore.external.Telemetry
import org.openftc.easyopencv.OpenCvPipeline

object DefaultPipelineInstantiator : PipelineInstantiator {

override fun instantiate(clazz: Class<*>, telemetry: Telemetry) = try {
//instantiate pipeline if it has a constructor of a telemetry parameter
val constructor = clazz.getConstructor(Telemetry::class.java)
constructor.newInstance(telemetry) as OpenCvPipeline
} catch (ex: NoSuchMethodException) {
//instantiating with a constructor of no params
val constructor = clazz.getConstructor()
constructor.newInstance() as OpenCvPipeline
}

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
package com.github.serivesmejia.eocvsim.pipeline.instantiator

import com.github.serivesmejia.eocvsim.pipeline.PipelineManager
import org.firstinspires.ftc.robotcore.external.Telemetry
import org.openftc.easyopencv.OpenCvPipeline

interface PipelineInstantiator {

fun instantiate(clazz: Class<*>, telemetry: Telemetry): OpenCvPipeline

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
package com.github.serivesmejia.eocvsim.pipeline.instantiator.processor

import com.github.serivesmejia.eocvsim.pipeline.PipelineManager
import com.github.serivesmejia.eocvsim.pipeline.instantiator.PipelineInstantiator
import com.github.serivesmejia.eocvsim.util.ReflectUtil
import org.firstinspires.ftc.robotcore.external.Telemetry
import org.firstinspires.ftc.vision.VisionProcessor
import org.openftc.easyopencv.OpenCvPipeline

object ProcessorInstantiator : PipelineInstantiator {

override fun instantiate(clazz: Class<*>, telemetry: Telemetry): OpenCvPipeline {
if(!ReflectUtil.hasSuperclass(clazz, VisionProcessor::class.java))
throw IllegalArgumentException("Class $clazz does not extend VisionProcessor")

val processor = try {
//instantiate pipeline if it has a constructor of a telemetry parameter
val constructor = clazz.getConstructor(Telemetry::class.java)
constructor.newInstance(telemetry) as VisionProcessor
} catch (ex: NoSuchMethodException) {
//instantiating with a constructor of no params
val constructor = clazz.getConstructor()
constructor.newInstance() as VisionProcessor
}

return ProcessorPipeline(processor)
}

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
package com.github.serivesmejia.eocvsim.pipeline.instantiator.processor;

import android.graphics.Canvas;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import org.firstinspires.ftc.vision.VisionProcessor;
import org.opencv.core.Mat;
import org.openftc.easyopencv.TimestampedOpenCvPipeline;

@Disabled
class ProcessorPipeline extends TimestampedOpenCvPipeline {

private VisionProcessor processor;

public ProcessorPipeline(VisionProcessor processor) {
this.processor = processor;
}

@Override
public void init(Mat mat) {
processor.init(mat.width(), mat.height(), null);
}

@Override
public Mat processFrame(Mat input, long captureTimeNanos) {
requestViewportDrawHook(processor.processFrame(input, captureTimeNanos));
return input;
}

@Override
public void onDrawFrame(Canvas canvas, int onscreenWidth, int onscreenHeight, float scaleBmpPxToCanvasPx, float scaleCanvasDensity, Object userContext) {
processor.onDrawFrame(canvas, onscreenWidth, onscreenHeight, scaleBmpPxToCanvasPx, scaleCanvasDensity, userContext);
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ import com.qualcomm.robotcore.eventloop.opmode.Disabled
import com.qualcomm.robotcore.util.ElapsedTime
import io.github.classgraph.ClassGraph
import kotlinx.coroutines.*
import org.firstinspires.ftc.vision.VisionProcessor
import org.openftc.easyopencv.OpenCvPipeline

class ClasspathScan {
Expand Down Expand Up @@ -58,7 +59,7 @@ class ClasspathScan {
private lateinit var scanResultJob: Job

@Suppress("UNCHECKED_CAST")
fun scan(jarFile: String? = null, classLoader: ClassLoader? = null): ScanResult {
fun scan(jarFile: String? = null, classLoader: ClassLoader? = null, addProcessorsAsPipelines: Boolean = true): ScanResult {
val timer = ElapsedTime()
val classGraph = ClassGraph()
.enableClassInfo()
Expand All @@ -79,12 +80,18 @@ class ClasspathScan {

val tunableFieldClassesInfo = scanResult.getClassesWithAnnotation(RegisterTunableField::class.java.name)

val pipelineClasses = mutableListOf<Class<out OpenCvPipeline>>()
val pipelineClasses = mutableListOf<Class<*>>()

// i...don't even know how to name this, sorry, future readers
// but classgraph for some reason does not have a recursive search for subclasses...
fun searchPipelinesOfSuperclass(superclass: String) {
val pipelineClassesInfo = scanResult.getSubclasses(superclass)
val superclassClazz = if(classLoader != null) {
classLoader.loadClass(superclass)
} else Class.forName(superclass)

val pipelineClassesInfo = if(superclassClazz.isInterface)
scanResult.getClassesImplementing(superclass)
else scanResult.getSubclasses(superclass)

for(pipelineClassInfo in pipelineClassesInfo) {
for(pipelineSubclassInfo in pipelineClassInfo.subclasses) {
Expand All @@ -99,12 +106,12 @@ class ClasspathScan {
classLoader.loadClass(pipelineClassInfo.name)
} else Class.forName(pipelineClassInfo.name)

if(!pipelineClasses.contains(clazz) && ReflectUtil.hasSuperclass(clazz, OpenCvPipeline::class.java)) {
if(!pipelineClasses.contains(clazz) && ReflectUtil.hasSuperclass(clazz, superclassClazz)) {
if(clazz.isAnnotationPresent(Disabled::class.java)) {
logger.info("Found @Disabled pipeline ${clazz.typeName}")
} else {
logger.info("Found pipeline ${clazz.typeName}")
pipelineClasses.add(clazz as Class<out OpenCvPipeline>)
pipelineClasses.add(clazz)
}
}
}
Expand All @@ -113,6 +120,11 @@ class ClasspathScan {
// start recursive hell
searchPipelinesOfSuperclass(OpenCvPipeline::class.java.name)

if(addProcessorsAsPipelines) {
logger.info("Searching for VisionProcessors...")
searchPipelinesOfSuperclass(VisionProcessor::class.java.name)
}

logger.info("Found ${pipelineClasses.size} pipelines")

val tunableFieldClasses = mutableListOf<Class<out TunableField<*>>>()
Expand Down Expand Up @@ -166,7 +178,7 @@ class ClasspathScan {
}

data class ScanResult(
val pipelineClasses: Array<Class<out OpenCvPipeline>>,
val pipelineClasses: Array<Class<*>>,
val tunableFieldClasses: Array<Class<out TunableField<*>>>,
val tunableFieldAcceptorClasses: Map<Class<out TunableField<*>>, Class<out TunableFieldAcceptor>>
)
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@ package io.github.deltacv.vision.external.gui

import android.graphics.Canvas
import io.github.deltacv.common.image.MatPoster
import io.github.deltacv.vision.internal.util.KillException
import org.firstinspires.ftc.robotcore.internal.collections.EvictingBlockingQueue
import org.jetbrains.skia.Color
import org.jetbrains.skiko.GenericSkikoView
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,4 +46,4 @@ interface VisionProcessorInternal
void init(int width, int height, CameraCalibration calibration);
Object processFrame(Mat frame, long captureTimeNanos);
void onDrawFrame(Canvas canvas, int onscreenWidth, int onscreenHeight, float scaleBmpPxToCanvasPx, float scaleCanvasDensity, Object userContext);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@

import android.graphics.Canvas;

import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.util.MovingStatistics;

import org.firstinspires.ftc.robotcore.external.matrices.GeneralMatrixF;
Expand All @@ -60,6 +61,7 @@

import java.util.ArrayList;

@Disabled
public class AprilTagProcessorImpl extends AprilTagProcessor
{
public static final String TAG = "AprilTagProcessorImpl";
Expand Down

0 comments on commit 907fe5e

Please sign in to comment.