Skip to content

Commit 471c90e

Browse files
authored
UI Message Passing (#1448)
Bring the UI setting changes in thread with the camera.
1 parent 142e22f commit 471c90e

File tree

5 files changed

+130
-33
lines changed

5 files changed

+130
-33
lines changed

photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipelineSettings.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ public ArucoPipelineSettings() {
4747
pipelineType = PipelineType.Aruco;
4848
outputShowMultipleTargets = true;
4949
targetModel = TargetModel.kAprilTag6p5in_36h11;
50-
cameraExposureRaw = -1;
50+
cameraExposureRaw = 20;
5151
cameraAutoExposure = true;
5252
ledMode = false;
5353
}

photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java

Lines changed: 17 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -69,8 +69,10 @@ public class VisionModule {
6969
protected final VisionSource visionSource;
7070
private final VisionRunner visionRunner;
7171
private final StreamRunnable streamRunnable;
72+
private final VisionModuleChangeSubscriber changeSubscriber;
7273
private final LinkedList<CVPipelineResultConsumer> resultConsumers = new LinkedList<>();
73-
// Raw result consumers run before any drawing has been done by the OutputStreamPipeline
74+
// Raw result consumers run before any drawing has been done by the
75+
// OutputStreamPipeline
7476
private final LinkedList<BiConsumer<Frame, List<TrackedTarget>>> streamResultConsumers =
7577
new LinkedList<>();
7678
private final NTDataPublisher ntConsumer;
@@ -102,7 +104,8 @@ public VisionModule(PipelineManager pipelineManager, VisionSource visionSource,
102104
if (visionSource.getCameraConfiguration().cameraQuirks == null)
103105
visionSource.getCameraConfiguration().cameraQuirks = QuirkyCamera.DefaultCamera;
104106

105-
// We don't show gain if the config says it's -1. So check here to make sure it's non-negative
107+
// We don't show gain if the config says it's -1. So check here to make sure
108+
// it's non-negative
106109
// if it _is_ supported
107110
if (cameraQuirks.hasQuirk(CameraQuirk.Gain)) {
108111
pipelineManager.userPipelineSettings.forEach(
@@ -120,16 +123,18 @@ public VisionModule(PipelineManager pipelineManager, VisionSource visionSource,
120123

121124
this.pipelineManager = pipelineManager;
122125
this.visionSource = visionSource;
126+
changeSubscriber = new VisionModuleChangeSubscriber(this);
123127
this.visionRunner =
124128
new VisionRunner(
125129
this.visionSource.getFrameProvider(),
126130
this.pipelineManager::getCurrentPipeline,
127131
this::consumeResult,
128-
this.cameraQuirks);
132+
this.cameraQuirks,
133+
getChangeSubscriber());
129134
this.streamRunnable = new StreamRunnable(new OutputStreamPipeline());
130135
this.moduleIndex = index;
131136

132-
DataChangeService.getInstance().addSubscriber(new VisionModuleChangeSubscriber(this));
137+
DataChangeService.getInstance().addSubscriber(changeSubscriber);
133138

134139
createStreams();
135140

@@ -315,6 +320,10 @@ private boolean isVendorCamera() {
315320
return visionSource.isVendorCamera();
316321
}
317322

323+
public VisionModuleChangeSubscriber getChangeSubscriber() {
324+
return changeSubscriber;
325+
}
326+
318327
void changePipelineType(int newType) {
319328
pipelineManager.changePipelineType(newType);
320329
setPipeline(pipelineManager.getRequestedIndex());
@@ -449,9 +458,11 @@ boolean setPipeline(int index) {
449458
}
450459

451460
private boolean camShouldControlLEDs() {
452-
// Heuristic - if the camera has a known FOV or is a piCam, assume it's in use for
461+
// Heuristic - if the camera has a known FOV or is a piCam, assume it's in use
462+
// for
453463
// vision processing, and should command stuff to the LED's.
454-
// TODO: Make LED control a property of the camera itself and controllable in the UI.
464+
// TODO: Make LED control a property of the camera itself and controllable in
465+
// the UI.
455466
return isVendorCamera();
456467
}
457468

Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
/*
2+
* Copyright (C) Photon Vision.
3+
*
4+
* This program is free software: you can redistribute it and/or modify
5+
* it under the terms of the GNU General Public License as published by
6+
* the Free Software Foundation, either version 3 of the License, or
7+
* (at your option) any later version.
8+
*
9+
* This program is distributed in the hope that it will be useful,
10+
* but WITHOUT ANY WARRANTY; without even the implied warranty of
11+
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12+
* GNU General Public License for more details.
13+
*
14+
* You should have received a copy of the GNU General Public License
15+
* along with this program. If not, see <https://www.gnu.org/licenses/>.
16+
*/
17+
18+
package org.photonvision.vision.processes;
19+
20+
import io.javalin.websocket.WsContext;
21+
import org.photonvision.vision.pipeline.CVPipelineSettings;
22+
23+
public class VisionModuleChange<T> {
24+
private final String propName;
25+
private final T newPropValue;
26+
private final CVPipelineSettings currentSettings;
27+
private final WsContext originContext;
28+
29+
public VisionModuleChange(
30+
String propName,
31+
T newPropValue,
32+
CVPipelineSettings currentSettings,
33+
WsContext originContext) {
34+
this.propName = propName;
35+
this.newPropValue = newPropValue;
36+
this.currentSettings = currentSettings;
37+
this.originContext = originContext;
38+
}
39+
40+
public String getPropName() {
41+
return propName;
42+
}
43+
44+
public T getNewPropValue() {
45+
return newPropValue;
46+
}
47+
48+
public CVPipelineSettings getCurrentSettings() {
49+
return currentSettings;
50+
}
51+
52+
public WsContext getOriginContext() {
53+
return originContext;
54+
}
55+
}

photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java

Lines changed: 51 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,9 @@
1818
package org.photonvision.vision.processes;
1919

2020
import java.util.ArrayList;
21+
import java.util.List;
2122
import java.util.Map;
23+
import java.util.concurrent.locks.ReentrantLock;
2224
import org.apache.commons.lang3.tuple.Pair;
2325
import org.opencv.core.Point;
2426
import org.photonvision.common.dataflow.DataChangeSubscriber;
@@ -39,6 +41,8 @@
3941
public class VisionModuleChangeSubscriber extends DataChangeSubscriber {
4042
private final VisionModule parentModule;
4143
private final Logger logger;
44+
private List<VisionModuleChange<?>> settingChanges = new ArrayList<>();
45+
private final ReentrantLock changeListLock = new ReentrantLock();
4246

4347
public VisionModuleChangeSubscriber(VisionModule parentModule) {
4448
this.parentModule = parentModule;
@@ -54,28 +58,47 @@ public void onDataChangeEvent(DataChangeEvent<?> event) {
5458
if (event instanceof IncomingWebSocketEvent) {
5559
var wsEvent = (IncomingWebSocketEvent<?>) event;
5660

57-
// Camera index -1 means a "multicast event" (i.e. the event is received by all cameras)
61+
// Camera index -1 means a "multicast event" (i.e. the event is received by all
62+
// cameras)
5863
if (wsEvent.cameraIndex != null
5964
&& (wsEvent.cameraIndex == parentModule.moduleIndex || wsEvent.cameraIndex == -1)) {
6065
logger.trace("Got PSC event - propName: " + wsEvent.propertyName);
66+
changeListLock.lock();
67+
try {
68+
getSettingChanges()
69+
.add(
70+
new VisionModuleChange(
71+
wsEvent.propertyName,
72+
wsEvent.data,
73+
parentModule.pipelineManager.getCurrentPipeline().getSettings(),
74+
wsEvent.originContext));
75+
} finally {
76+
changeListLock.unlock();
77+
}
78+
}
79+
}
80+
}
6181

62-
var propName = wsEvent.propertyName;
63-
var newPropValue = wsEvent.data;
64-
var currentSettings = parentModule.pipelineManager.getCurrentPipeline().getSettings();
82+
public List<VisionModuleChange<?>> getSettingChanges() {
83+
return settingChanges;
84+
}
6585

66-
// special case for non-PipelineSetting changes
86+
public void processSettingChanges() {
87+
// special case for non-PipelineSetting changes
88+
changeListLock.lock();
89+
try {
90+
for (var change : settingChanges) {
91+
var propName = change.getPropName();
92+
var newPropValue = change.getNewPropValue();
93+
var currentSettings = change.getCurrentSettings();
94+
var originContext = change.getOriginContext();
6795
switch (propName) {
68-
// case "cameraNickname": // rename camera
69-
// var newNickname = (String) newPropValue;
70-
// logger.info("Changing nickname to " + newNickname);
71-
// parentModule.setCameraNickname(newNickname);
72-
// return;
7396
case "pipelineName": // rename current pipeline
7497
logger.info("Changing nick to " + newPropValue);
7598
parentModule.pipelineManager.getCurrentPipelineSettings().pipelineNickname =
7699
(String) newPropValue;
77100
parentModule.saveAndBroadcastAll();
78-
return;
101+
continue;
79102
case "newPipelineInfo": // add new pipeline
80103
var typeName = (Pair<String, PipelineType>) newPropValue;
81104
var type = typeName.getRight();
@@ -86,23 +109,23 @@ public void onDataChangeEvent(DataChangeEvent<?> event) {
86109
var addedSettings = parentModule.pipelineManager.addPipeline(type);
87110
addedSettings.pipelineNickname = name;
88111
parentModule.saveAndBroadcastAll();
89-
return;
112+
continue;
90113
case "deleteCurrPipeline":
91114
var indexToDelete = parentModule.pipelineManager.getRequestedIndex();
92115
logger.info("Deleting current pipe at index " + indexToDelete);
93116
int newIndex = parentModule.pipelineManager.removePipeline(indexToDelete);
94117
parentModule.setPipeline(newIndex);
95118
parentModule.saveAndBroadcastAll();
96-
return;
119+
continue;
97120
case "changePipeline": // change active pipeline
98121
var index = (Integer) newPropValue;
99122
if (index == parentModule.pipelineManager.getRequestedIndex()) {
100123
logger.debug("Skipping pipeline change, index " + index + " already active");
101-
return;
124+
continue;
102125
}
103126
parentModule.setPipeline(index);
104127
parentModule.saveAndBroadcastAll();
105-
return;
128+
continue;
106129
case "startCalibration":
107130
try {
108131
var data =
@@ -113,25 +136,25 @@ public void onDataChangeEvent(DataChangeEvent<?> event) {
113136
} catch (Exception e) {
114137
logger.error("Error deserailizing start-cal request", e);
115138
}
116-
return;
139+
continue;
117140
case "saveInputSnapshot":
118141
parentModule.saveInputSnapshot();
119-
return;
142+
continue;
120143
case "saveOutputSnapshot":
121144
parentModule.saveOutputSnapshot();
122-
return;
145+
continue;
123146
case "takeCalSnapshot":
124147
parentModule.takeCalibrationSnapshot();
125-
return;
148+
continue;
126149
case "duplicatePipeline":
127150
int idx = parentModule.pipelineManager.duplicatePipeline((Integer) newPropValue);
128151
parentModule.setPipeline(idx);
129152
parentModule.saveAndBroadcastAll();
130-
return;
153+
continue;
131154
case "calibrationUploaded":
132155
if (newPropValue instanceof CameraCalibrationCoefficients)
133156
parentModule.addCalibrationToConfig((CameraCalibrationCoefficients) newPropValue);
134-
return;
157+
continue;
135158
case "robotOffsetPoint":
136159
if (currentSettings instanceof AdvancedPipelineSettings) {
137160
var curAdvSettings = (AdvancedPipelineSettings) currentSettings;
@@ -176,14 +199,14 @@ public void onDataChangeEvent(DataChangeEvent<?> event) {
176199
}
177200
}
178201
}
179-
return;
202+
continue;
180203
case "changePipelineType":
181204
parentModule.changePipelineType((Integer) newPropValue);
182205
parentModule.saveAndBroadcastAll();
183-
return;
206+
continue;
184207
case "isDriverMode":
185208
parentModule.setDriverMode((Boolean) newPropValue);
186-
return;
209+
continue;
187210
}
188211

189212
// special case for camera settables
@@ -218,8 +241,11 @@ public void onDataChangeEvent(DataChangeEvent<?> event) {
218241
logger.error("Unknown exception when setting PSC prop!", e);
219242
}
220243

221-
parentModule.saveAndBroadcastSelective(wsEvent.originContext, propName, newPropValue);
244+
parentModule.saveAndBroadcastSelective(originContext, propName, newPropValue);
222245
}
246+
getSettingChanges().clear();
247+
} finally {
248+
changeListLock.unlock();
223249
}
224250
}
225251

photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@ public class VisionRunner {
3737
private final FrameProvider frameSupplier;
3838
private final Supplier<CVPipeline> pipelineSupplier;
3939
private final Consumer<CVPipelineResult> pipelineResultConsumer;
40+
private final VisionModuleChangeSubscriber changeSubscriber;
4041
private final QuirkyCamera cameraQuirks;
4142

4243
private long loopCount;
@@ -53,15 +54,18 @@ public VisionRunner(
5354
FrameProvider frameSupplier,
5455
Supplier<CVPipeline> pipelineSupplier,
5556
Consumer<CVPipelineResult> pipelineResultConsumer,
56-
QuirkyCamera cameraQuirks) {
57+
QuirkyCamera cameraQuirks,
58+
VisionModuleChangeSubscriber changeSubscriber) {
5759
this.frameSupplier = frameSupplier;
5860
this.pipelineSupplier = pipelineSupplier;
5961
this.pipelineResultConsumer = pipelineResultConsumer;
6062
this.cameraQuirks = cameraQuirks;
63+
this.changeSubscriber = changeSubscriber;
6164

6265
visionProcessThread = new Thread(this::update);
6366
visionProcessThread.setName("VisionRunner - " + frameSupplier.getName());
6467
logger = new Logger(VisionRunner.class, frameSupplier.getName(), LogGroup.VisionModule);
68+
changeSubscriber.processSettingChanges();
6569
}
6670

6771
public void startProcess() {
@@ -70,6 +74,7 @@ public void startProcess() {
7074

7175
private void update() {
7276
while (!Thread.interrupted()) {
77+
changeSubscriber.processSettingChanges();
7378
var pipeline = pipelineSupplier.get();
7479

7580
// Tell our camera implementation here what kind of pre-processing we need it to be doing

0 commit comments

Comments
 (0)