Skip to content

Commit

Permalink
Implement virtualreflect onto the codebase and pipeline streaming wor…
Browse files Browse the repository at this point in the history
…king
  • Loading branch information
serivesmejia committed Sep 12, 2024
1 parent ae25bc0 commit 0d2cb2e
Show file tree
Hide file tree
Showing 35 changed files with 676 additions and 210 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,7 @@ class EventHandler(val name: String) : Runnable {
throw ex
} else {
logger.error("Error while running \"once\" ${listener.javaClass.name}", ex)
removeOnceListener(listener)
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ class TunableFieldPanelOptions(val fieldPanel: TunableFieldPanel,
if(i < colorScalar.`val`.size) {
val colorVal = colorScalar.`val`[i]
fieldPanel.setFieldValue(i, colorVal)
fieldPanel.tunableField.setGuiFieldValue(i, colorVal.toString())
fieldPanel.tunableField.setFieldValueFromGui(i, colorVal.toString())
} else { break } //keep looping until we write the entire scalar value
}
colorPickButton.isSelected = false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ private void init() {

addItemListener(evt -> eocvSim.onMainUpdate.doOnce(() -> {
try {
tunableField.setGuiComboBoxValue(index, Objects.requireNonNull(getSelectedItem()).toString());
tunableField.setComboBoxValueFromGui(index, Objects.requireNonNull(getSelectedItem()).toString());
} catch (IllegalAccessException ex) {
ex.printStackTrace();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class TunableSlider(val index: Int,

private val changeFieldValue = EventListener {
if(inControl) {
tunableField.setGuiFieldValue(index, scaledValue.toString())
tunableField.setFieldValueFromGui(index, scaledValue.toString())

if (eocvSim.pipelineManager.paused)
eocvSim.pipelineManager.setPaused(false)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ public void replace(FilterBypass fb, int offset, int length, String text, Attrib
Runnable changeFieldValue = () -> {
if ((!hasValidText || !tunableField.isOnlyNumbers() || !getText().trim().equals(""))) {
try {
tunableField.setGuiFieldValue(index, getText());
tunableField.setFieldValueFromGui(index, getText());
} catch (Exception e) {
setRedBorder();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,10 @@ import com.github.serivesmejia.eocvsim.util.fps.FpsCounter
import com.github.serivesmejia.eocvsim.util.loggerForThis
import io.github.deltacv.common.image.MatPoster
import io.github.deltacv.common.pipeline.util.PipelineStatisticsCalculator
import io.github.deltacv.eocvsim.virtualreflect.VirtualField
import io.github.deltacv.eocvsim.virtualreflect.VirtualReflectContext
import io.github.deltacv.eocvsim.virtualreflect.VirtualReflection
import io.github.deltacv.eocvsim.virtualreflect.jvm.JvmVirtualReflection
import kotlinx.coroutines.*
import org.firstinspires.ftc.robotcore.external.Telemetry
import org.firstinspires.ftc.robotcore.internal.opmode.TelemetryImpl
Expand Down Expand Up @@ -89,14 +93,21 @@ class PipelineManager(
private set
@Volatile var currentPipelineData: PipelineData? = null
private set
var currentTunerTarget: Any? = null
private set
var currentPipelineName = ""
private set
var currentPipelineIndex = -1
private set
var previousPipelineIndex = 0

var virtualReflect: VirtualReflection = JvmVirtualReflection
set(value) {
eocvSim.tunerManager.setVirtualReflection(value)
field = value
}

var reflectTarget: Any? = null
private set

@Volatile var previousPipeline: OpenCvPipeline? = null
private set

Expand Down Expand Up @@ -130,7 +141,7 @@ class PipelineManager(

var applyLatestSnapshotOnChange = false

val snapshotFieldFilter: (Field) -> Boolean = {
val snapshotFieldFilter: (VirtualField) -> Boolean = {
// only snapshot fields managed by the variable tuner
// when getTunableFieldOf returns null, it means that
// it wasn't able to find a suitable TunableField for
Expand Down Expand Up @@ -354,15 +365,15 @@ class PipelineManager(
updateExceptionTracker()
} catch (ex: Exception) { //handling exceptions from pipelines
if(!hasInitCurrentPipeline) {
pipelineExceptionTracker.addMessage("Error while initializing requested pipeline, \"$currentPipelineName\". Falling back to previous one.")
pipelineExceptionTracker.addMessage("Error while initializing requested pipeline, \"$currentPipelineName\". Falling back to default.")
pipelineExceptionTracker.addMessage(
StrUtil.fromException(ex).trim()
)

eocvSim.visualizer.pipelineSelectorPanel.selectedIndex = previousPipelineIndex
changePipeline(previousPipelineIndex)
eocvSim.visualizer.pipelineSelectorPanel.selectedIndex = 0
changePipeline(0)

logger.error("Error while initializing requested pipeline, $currentPipelineName. Falling back to previous one.", ex)
logger.error("Error while initializing requested pipeline, $currentPipelineName. Falling back to default.", ex)
} else {
updateExceptionTracker(ex)
}
Expand Down Expand Up @@ -605,16 +616,18 @@ class PipelineManager(
previousPipelineIndex = currentPipelineIndex
previousPipeline = currentPipeline

currentPipeline = nextPipeline
currentPipelineData = pipelines[index]
currentTelemetry = nextTelemetry
currentPipelineIndex = index
currentPipelineName = currentPipeline!!.javaClass.simpleName
currentTunerTarget = instantiator.variableTunerTargetObject(currentPipeline!!)
currentPipeline = nextPipeline
currentPipelineData = pipelines[index]
currentTelemetry = nextTelemetry
currentPipelineIndex = index
currentPipelineName = currentPipeline!!.javaClass.simpleName

virtualReflect = instantiator.virtualReflectOf(currentPipeline!!)
reflectTarget = instantiator.variableTunerTarget(currentPipeline!!)

currentTelemetry?.update() // clear telemetry

val snap = PipelineSnapshot(currentPipeline!!, snapshotFieldFilter)
val snap = PipelineSnapshot(virtualReflect.contextOf(reflectTarget!!)!!, snapshotFieldFilter)

lastInitialSnapshot = if(applyLatestSnapshot) {
applyLatestSnapshot()
Expand Down Expand Up @@ -672,13 +685,13 @@ class PipelineManager(

fun captureSnapshot() {
if(currentPipeline != null) {
latestSnapshot = PipelineSnapshot(currentPipeline!!, snapshotFieldFilter)
latestSnapshot = PipelineSnapshot(virtualReflect.contextOf(reflectTarget!!)!!, snapshotFieldFilter)
}
}

fun captureStaticSnapshot() {
if(currentPipeline != null) {
staticSnapshot = PipelineSnapshot(currentPipeline!!, snapshotFieldFilter)
staticSnapshot = PipelineSnapshot(virtualReflect.contextOf(reflectTarget!!)!!, snapshotFieldFilter)
}
}

Expand All @@ -702,7 +715,7 @@ class PipelineManager(
fun getIndexOf(pipeline: OpenCvPipeline, source: PipelineSource = PipelineSource.CLASSPATH) =
getIndexOf(pipeline::class.java, source)

fun getIndexOf(pipelineClass: Class<out OpenCvPipeline>, source: PipelineSource = PipelineSource.CLASSPATH): Int? {
fun getIndexOf(pipelineClass: Class<*>, source: PipelineSource = PipelineSource.CLASSPATH): Int? {
for((i, pipelineData) in pipelines.withIndex()) {
if(pipelineData.clazz.name == pipelineClass.name && pipelineData.source == source) {
return i
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@

package com.github.serivesmejia.eocvsim.pipeline.instantiator

import io.github.deltacv.eocvsim.virtualreflect.VirtualReflectContext
import io.github.deltacv.eocvsim.virtualreflect.jvm.JvmVirtualReflection
import org.firstinspires.ftc.robotcore.external.Telemetry
import org.openftc.easyopencv.OpenCvPipeline

Expand All @@ -38,6 +40,8 @@ object DefaultPipelineInstantiator : PipelineInstantiator {
constructor.newInstance() as OpenCvPipeline
}

override fun variableTunerTargetObject(pipeline: OpenCvPipeline) = pipeline
override fun virtualReflectOf(pipeline: OpenCvPipeline) = JvmVirtualReflection

override fun variableTunerTarget(pipeline: OpenCvPipeline) = pipeline

}
Original file line number Diff line number Diff line change
Expand Up @@ -24,13 +24,16 @@
package com.github.serivesmejia.eocvsim.pipeline.instantiator

import com.github.serivesmejia.eocvsim.pipeline.PipelineManager
import io.github.deltacv.eocvsim.virtualreflect.VirtualReflectContext
import io.github.deltacv.eocvsim.virtualreflect.VirtualReflection
import org.firstinspires.ftc.robotcore.external.Telemetry
import org.openftc.easyopencv.OpenCvPipeline

interface PipelineInstantiator {

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

fun variableTunerTargetObject(pipeline: OpenCvPipeline): Any
fun virtualReflectOf(pipeline: OpenCvPipeline): VirtualReflection
fun variableTunerTarget(pipeline: OpenCvPipeline): Any?

}
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ 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 io.github.deltacv.eocvsim.virtualreflect.jvm.JvmVirtualReflection
import org.firstinspires.ftc.robotcore.external.Telemetry
import org.firstinspires.ftc.vision.VisionProcessor
import org.openftc.easyopencv.OpenCvPipeline
Expand All @@ -48,7 +49,8 @@ object ProcessorInstantiator : PipelineInstantiator {
return ProcessorPipeline(processor)
}

override fun variableTunerTargetObject(pipeline: OpenCvPipeline): VisionProcessor =
(pipeline as ProcessorPipeline).processor
override fun virtualReflectOf(pipeline: OpenCvPipeline) = JvmVirtualReflection

override fun variableTunerTarget(pipeline: OpenCvPipeline) = (pipeline as ProcessorPipeline).processor

}
Original file line number Diff line number Diff line change
Expand Up @@ -24,30 +24,33 @@
package com.github.serivesmejia.eocvsim.pipeline.util

import com.github.serivesmejia.eocvsim.util.loggerForThis
import io.github.deltacv.eocvsim.virtualreflect.VirtualField
import io.github.deltacv.eocvsim.virtualreflect.VirtualReflectContext
import io.github.deltacv.eocvsim.virtualreflect.jvm.JvmVirtualReflectContext
import io.github.deltacv.eocvsim.virtualreflect.jvm.JvmVirtualReflection
import org.openftc.easyopencv.OpenCvPipeline
import java.lang.reflect.Field
import java.lang.reflect.Modifier
import java.util.*

class PipelineSnapshot(holdingPipeline: OpenCvPipeline, val filter: ((Field) -> Boolean)? = null) {
class PipelineSnapshot(val virtualReflectContext: VirtualReflectContext, filter: ((VirtualField) -> Boolean)? = null) {

val logger by loggerForThis()

val holdingPipelineName = holdingPipeline::class.simpleName
val holdingPipelineName = virtualReflectContext.simpleName

val pipelineFieldValues: Map<Field, Any?>
val pipelineClass = holdingPipeline::class.java
val pipelineClass get() = (virtualReflectContext as JvmVirtualReflectContext).clazz

val pipelineFieldValues: Map<VirtualField, Any?>

init {
val fieldValues = mutableMapOf<Field, Any?>()
val fieldValues = mutableMapOf<VirtualField, Any?>()

for(field in pipelineClass.declaredFields) {
if(Modifier.isFinal(field.modifiers) || !Modifier.isPublic(field.modifiers))
for(field in virtualReflectContext.fields) {
if(field.isFinal || field.isFinal)
continue

if(filter?.invoke(field) == false) continue

fieldValues[field] = field.get(holdingPipeline)
fieldValues[field] = field.get()
}

pipelineFieldValues = fieldValues.toMap()
Expand All @@ -60,7 +63,7 @@ class PipelineSnapshot(holdingPipeline: OpenCvPipeline, val filter: ((Field) ->
if(pipelineClass.name != otherPipeline::class.java.name) return

val changedList = if(lastInitialPipelineSnapshot != null)
getChangedFieldsComparedTo(PipelineSnapshot(otherPipeline), lastInitialPipelineSnapshot)
getChangedFieldsComparedTo(PipelineSnapshot(JvmVirtualReflection.contextOf(otherPipeline)), lastInitialPipelineSnapshot)
else Collections.emptyList()

fieldValuesLoop@
Expand All @@ -76,7 +79,7 @@ class PipelineSnapshot(holdingPipeline: OpenCvPipeline, val filter: ((Field) ->
}

try {
field.set(otherPipeline, value)
field.set(value)
} catch(e: Exception) {
logger.trace(
"Failed to set field ${field.name} from snapshot of ${pipelineClass.name}. " +
Expand All @@ -96,7 +99,7 @@ class PipelineSnapshot(holdingPipeline: OpenCvPipeline, val filter: ((Field) ->
}
}

fun getField(name: String): Pair<Field, Any?>? {
fun getField(name: String): Pair<VirtualField, Any?>? {
for((field, value) in pipelineFieldValues) {
if(field.name == name) {
return Pair(field, value)
Expand All @@ -109,11 +112,11 @@ class PipelineSnapshot(holdingPipeline: OpenCvPipeline, val filter: ((Field) ->
private fun getChangedFieldsComparedTo(
pipelineSnapshotA: PipelineSnapshot,
pipelineSnapshotB: PipelineSnapshot
): List<Field> = pipelineSnapshotA.run {
): List<VirtualField> = pipelineSnapshotA.run {
if(holdingPipelineName != pipelineSnapshotB.holdingPipelineName && pipelineClass != pipelineSnapshotB.pipelineClass)
return Collections.emptyList()

val changedList = mutableListOf<Field>()
val changedList = mutableListOf<VirtualField>()

for((field, value) in pipelineFieldValues) {
val (otherField, otherValue) = pipelineSnapshotB.getField(field.name) ?: continue
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,14 @@
import com.github.serivesmejia.eocvsim.gui.component.tuner.TunableFieldPanel;
import com.github.serivesmejia.eocvsim.gui.component.tuner.TunableFieldPanelConfig;
import com.github.serivesmejia.eocvsim.util.event.EventHandler;
import io.github.deltacv.eocvsim.virtualreflect.VirtualField;
import org.openftc.easyopencv.OpenCvPipeline;

import java.lang.reflect.Field;

public abstract class TunableField<T> {

protected Field reflectionField;
protected VirtualField reflectionField;
protected TunableFieldPanel fieldPanel;

protected Object target;
Expand All @@ -49,16 +50,16 @@ public abstract class TunableField<T> {

private TunableFieldPanel.Mode recommendedMode = null;

public TunableField(Object target, Field reflectionField, EOCVSim eocvSim, AllowMode allowMode) throws IllegalAccessException {
public TunableField(Object target, VirtualField reflectionField, EOCVSim eocvSim, AllowMode allowMode) throws IllegalAccessException {
this.reflectionField = reflectionField;
this.target = target;
this.allowMode = allowMode;
this.eocvSim = eocvSim;

initialFieldValue = reflectionField.get(target);
initialFieldValue = reflectionField.get();
}

public TunableField(Object target, Field reflectionField, EOCVSim eocvSim) throws IllegalAccessException {
public TunableField(Object target, VirtualField reflectionField, EOCVSim eocvSim) throws IllegalAccessException {
this(target, reflectionField, eocvSim, AllowMode.TEXT);
}

Expand All @@ -70,14 +71,15 @@ public TunableField(Object target, Field reflectionField, EOCVSim eocvSim) throw

public void setPipelineFieldValue(T newValue) throws IllegalAccessException {
if (hasChanged()) { //execute if value is not the same to save resources
reflectionField.set(target, newValue);
reflectionField.set(newValue);
onValueChange.run();
}
}

public abstract void setGuiFieldValue(int index, String newValue) throws IllegalAccessException;
public abstract void setFieldValue(int index, Object newValue) throws IllegalAccessException;
public abstract void setFieldValueFromGui(int index, String newValue) throws IllegalAccessException;

public void setGuiComboBoxValue(int index, String newValue) throws IllegalAccessException { }
public void setComboBoxValueFromGui(int index, String newValue) throws IllegalAccessException { }

public final void setTunableFieldPanel(TunableFieldPanel fieldPanel) {
this.fieldPanel = fieldPanel;
Expand Down
Loading

0 comments on commit 0d2cb2e

Please sign in to comment.