Skip to content

Commit

Permalink
Merge branch 'PhotonVision:master' into update-sim-36h11
Browse files Browse the repository at this point in the history
  • Loading branch information
r4stered authored Dec 28, 2023
2 parents 6186afc + ece521c commit 4644237
Show file tree
Hide file tree
Showing 8 changed files with 148 additions and 30 deletions.
46 changes: 33 additions & 13 deletions photon-client/src/components/dashboard/tabs/TargetsTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,32 @@ import { useCameraSettingsStore } from "@/stores/settings/CameraSettingsStore";
import { PipelineType } from "@/types/PipelineTypes";
import { useStateStore } from "@/stores/StateStore";
const wrapToPi = (delta: number): number => {
let ret = delta;
while (ret < -Math.PI) ret += Math.PI * 2;
while (ret > Math.PI) ret -= Math.PI * 2;
return ret;
};
const calculateStdDev = (values: number[]): number => {
if (values.length < 2) return 0;
const mean = values.reduce((sum, number) => sum + number, 0) / values.length;
// Use mean of cosine/sine components to handle angle wrapping
const cosines = values.map((it) => Math.cos(it));
const sines = values.map((it) => Math.sin(it));
const cosmean = cosines.reduce((sum, number) => sum + number, 0) / values.length;
const sinmean = sines.reduce((sum, number) => sum + number, 0) / values.length;
// Borrowed from WPILib's Rotation2d
const hypot = Math.hypot(cosmean, sinmean);
let mean;
if (hypot > 1e-6) {
mean = Math.atan2(sinmean / hypot, cosmean / hypot);
} else {
mean = 0;
}
return Math.sqrt(values.map((x) => Math.pow(x - mean, 2)).reduce((a, b) => a + b) / values.length);
return Math.sqrt(values.map((x) => Math.pow(wrapToPi(x - mean), 2)).reduce((a, b) => a + b) / values.length);
};
const resetCurrentBuffer = () => {
// Need to clear the array in place
Expand Down Expand Up @@ -119,23 +139,23 @@ const resetCurrentBuffer = () => {
<td>
{{
(
useStateStore().currentPipelineResults?.multitagResult?.bestTransform.angle_x *
(useStateStore().currentPipelineResults?.multitagResult?.bestTransform.angle_x || 0) *
(180.0 / Math.PI)
).toFixed(2)
}}&deg;
</td>
<td>
{{
(
useStateStore().currentPipelineResults?.multitagResult?.bestTransform.angle_y *
(useStateStore().currentPipelineResults?.multitagResult?.bestTransform.angle_y || 0) *
(180.0 / Math.PI)
).toFixed(2)
}}&deg;
</td>
<td>
{{
(
useStateStore().currentPipelineResults?.multitagResult?.bestTransform.angle_z *
(useStateStore().currentPipelineResults?.multitagResult?.bestTransform.angle_z || 0) *
(180.0 / Math.PI)
).toFixed(2)
}}&deg;
Expand All @@ -146,8 +166,8 @@ const resetCurrentBuffer = () => {
</v-row>
<v-row class="pb-4 white--text" style="display: flex; flex-direction: column">
<v-card-subtitle class="ma-0 pa-0 pb-4 pr-4" style="font-size: 16px"
>Multi-tag pose standard deviation over the last {{ useStateStore().currentMultitagBuffer.length }}/100
samples
>Multi-tag pose standard deviation over the last
{{ useStateStore().currentMultitagBuffer?.length || "NaN" }}/100 samples
</v-card-subtitle>
<v-btn color="secondary" class="mb-4 mt-1" style="width: min-content" depressed @click="resetCurrentBuffer"
>Reset Samples</v-btn
Expand All @@ -164,37 +184,37 @@ const resetCurrentBuffer = () => {
<tbody v-show="useStateStore().currentPipelineResults?.multitagResult">
<td>
{{
calculateStdDev(useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.x)).toFixed(5)
calculateStdDev(useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.x) || []).toFixed(5)
}}&nbsp;m
</td>
<td>
{{
calculateStdDev(useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.y)).toFixed(5)
calculateStdDev(useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.y) || []).toFixed(5)
}}&nbsp;m
</td>
<td>
{{
calculateStdDev(useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.z)).toFixed(5)
calculateStdDev(useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.z) || []).toFixed(5)
}}&nbsp;m
</td>
<td>
{{
calculateStdDev(
useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.angle_x * (180.0 / Math.PI))
useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.angle_x * (180.0 / Math.PI)) || []
).toFixed(5)
}}&deg;
</td>
<td>
{{
calculateStdDev(
useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.angle_y * (180.0 / Math.PI))
useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.angle_y * (180.0 / Math.PI)) || []
).toFixed(5)
}}&deg;
</td>
<td>
{{
calculateStdDev(
useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.angle_z * (180.0 / Math.PI))
useStateStore().currentMultitagBuffer?.map((v) => v.bestTransform.angle_z * (180.0 / Math.PI)) || []
).toFixed(5)
}}&deg;
</td>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,5 @@
public enum ProgramStatus {
UHOH,
RUNNING,
RUNNING_NT,
RUNNING_NT_TARGET
RUNNING_NT
}
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
import org.photonvision.common.configuration.NetworkConfig;
import org.photonvision.common.dataflow.DataChangeService;
import org.photonvision.common.dataflow.events.OutgoingUIEvent;
import org.photonvision.common.hardware.HardwareManager;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.common.scripting.ScriptEventType;
Expand Down Expand Up @@ -91,6 +92,7 @@ public void accept(NetworkTableEvent event) {
event.connInfo.remote_port,
event.connInfo.protocol_version);
logger.error(msg);
HardwareManager.getInstance().setNTConnected(false);

hasReportedConnectionFailure = true;
getInstance().broadcastConnectedStatus();
Expand All @@ -102,6 +104,7 @@ public void accept(NetworkTableEvent event) {
event.connInfo.remote_port,
event.connInfo.protocol_version);
logger.info(msg);
HardwareManager.getInstance().setNTConnected(true);

hasReportedConnectionFailure = false;
ScriptManager.queueEvent(ScriptEventType.kNTConnected);
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
/*
* Copyright (C) Photon Vision.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/

package org.photonvision.common.dataflow.statusLEDs;

import org.photonvision.common.dataflow.CVPipelineResultConsumer;
import org.photonvision.common.hardware.HardwareManager;
import org.photonvision.vision.pipeline.result.CVPipelineResult;

public class StatusLEDConsumer implements CVPipelineResultConsumer {
private final int index;

public StatusLEDConsumer(int index) {
this.index = index;
}

@Override
public void accept(CVPipelineResult t) {
HardwareManager.getInstance().setTargetsVisibleStatus(this.index, t.hasTargets());
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,8 @@
import edu.wpi.first.networktables.IntegerPublisher;
import edu.wpi.first.networktables.IntegerSubscriber;
import java.io.IOException;
import org.photonvision.common.ProgramStatus;
import java.util.HashMap;
import java.util.Map;
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.configuration.HardwareConfig;
import org.photonvision.common.configuration.HardwareSettings;
Expand All @@ -32,6 +33,7 @@
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.common.util.ShellExec;
import org.photonvision.common.util.TimedTaskManager;

public class HardwareManager {
private static HardwareManager instance;
Expand Down Expand Up @@ -96,6 +98,10 @@ private HardwareManager(HardwareConfig hardwareConfig, HardwareSettings hardware
? new StatusLED(hardwareConfig.statusRGBPins)
: null;

if (statusLED != null) {
TimedTaskManager.getInstance().addTask("StatusLEDUpdate", this::statusLEDUpdate, 150);
}

var hasBrightnessRange = hardwareConfig.ledBrightnessRange.size() == 2;
visionLED =
hardwareConfig.ledPins.isEmpty()
Expand Down Expand Up @@ -160,21 +166,61 @@ public boolean restartDevice() {
}
}

public void setStatus(ProgramStatus status) {
switch (status) {
case UHOH:
// red flashing, green off
break;
case RUNNING:
// red solid, green off
break;
case RUNNING_NT:
// red off, green solid
break;
case RUNNING_NT_TARGET:
// red off, green flashing
break;
// API's supporting status LEDs

private Map<Integer, Boolean> pipelineTargets = new HashMap<Integer, Boolean>();
private boolean ntConnected = false;
private boolean systemRunning = false;
private int blinkCounter = 0;

public void setTargetsVisibleStatus(int pipelineIdx, boolean hasTargets) {
pipelineTargets.put(pipelineIdx, hasTargets);
}

public void setNTConnected(boolean isConnected) {
this.ntConnected = isConnected;
}

public void setRunning(boolean isRunning) {
this.systemRunning = isRunning;
}

private void statusLEDUpdate() {
// make blinky
boolean blinky = ((blinkCounter % 3) > 0);

// check if any pipeline has a visible target
boolean anyTarget = false;
for (var t : this.pipelineTargets.values()) {
if (t) {
anyTarget = true;
}
}

if (this.systemRunning) {
if (!this.ntConnected) {
if (anyTarget) {
// Blue Flashing
statusLED.setRGB(false, false, blinky);
} else {
// Yellow flashing
statusLED.setRGB(blinky, blinky, false);
}
} else {
if (anyTarget) {
// Blue
statusLED.setRGB(false, false, blinky);
} else {
// blinky green
statusLED.setRGB(false, blinky, false);
}
}
} else {
// Faulted, not running... blinky red
statusLED.setRGB(blinky, false, false);
}

blinkCounter++;
}

public HardwareConfig getConfig() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,4 +45,14 @@ public StatusLED(List<Integer> statusLedPins) {
blueLED = new CustomGPIO(statusLedPins.get(2));
}
}

public void setRGB(boolean r, boolean g, boolean b) {
// Outputs are active-low, so invert the level applied
redLED.setState(!r);
redLED.setBrightness(r ? 0 : 100);
greenLED.setState(!g);
greenLED.setBrightness(g ? 0 : 100);
blueLED.setState(!b);
blueLED.setBrightness(b ? 0 : 100);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
import org.photonvision.common.dataflow.DataChangeService;
import org.photonvision.common.dataflow.events.OutgoingUIEvent;
import org.photonvision.common.dataflow.networktables.NTDataPublisher;
import org.photonvision.common.dataflow.statusLEDs.StatusLEDConsumer;
import org.photonvision.common.dataflow.websocket.UIDataPublisher;
import org.photonvision.common.hardware.HardwareManager;
import org.photonvision.common.logging.LogGroup;
Expand Down Expand Up @@ -72,6 +73,7 @@ public class VisionModule {
new LinkedList<>();
private final NTDataPublisher ntConsumer;
private final UIDataPublisher uiDataConsumer;
private final StatusLEDConsumer statusLEDsConsumer;
protected final int moduleIndex;
protected final QuirkyCamera cameraQuirks;

Expand Down Expand Up @@ -143,8 +145,10 @@ public VisionModule(PipelineManager pipelineManager, VisionSource visionSource,
pipelineManager::getDriverMode,
this::setDriverMode);
uiDataConsumer = new UIDataPublisher(index);
statusLEDsConsumer = new StatusLEDConsumer(index);
addResultConsumer(ntConsumer);
addResultConsumer(uiDataConsumer);
addResultConsumer(statusLEDsConsumer);
addResultConsumer(
(result) ->
lastPipelineResultBestTarget = result.hasTargets() ? result.targets.get(0) : null);
Expand Down
1 change: 1 addition & 0 deletions photon-server/src/main/java/org/photonvision/Main.java
Original file line number Diff line number Diff line change
Expand Up @@ -375,6 +375,7 @@ public static void main(String[] args) {
}

logger.info("Starting server...");
HardwareManager.getInstance().setRunning(true);
Server.start(DEFAULT_WEBPORT);
}
}

0 comments on commit 4644237

Please sign in to comment.