From 9dc1329ef6e63855066c6e59aadd70ecccfd9acb Mon Sep 17 00:00:00 2001 From: Rafael Araujo Lehmkuhl Date: Mon, 2 Mar 2026 16:03:30 -0300 Subject: [PATCH 1/9] refactor: migrate VirtualHorizon widget to the data-lake Replaces the vehicle store attitude watch with useDataLakeVariable composable. Roll and pitch are now read from configurable data lake variable IDs (default: /mavlink/1/1/ATTITUDE/roll and pitch). Removes useMainVehicleStore dependency. --- src/components/widgets/VirtualHorizon.vue | 49 ++++++++++++----------- 1 file changed, 26 insertions(+), 23 deletions(-) diff --git a/src/components/widgets/VirtualHorizon.vue b/src/components/widgets/VirtualHorizon.vue index 3bc2e49159..a5225f9df2 100644 --- a/src/components/widgets/VirtualHorizon.vue +++ b/src/components/widgets/VirtualHorizon.vue @@ -12,11 +12,11 @@ From 377e4b514da3c6c8fe892afc1a0253c1853c968b Mon Sep 17 00:00:00 2001 From: Rafael Araujo Lehmkuhl Date: Mon, 2 Mar 2026 16:03:30 -0300 Subject: [PATCH 6/9] refactor: migrate BatteryIndicator mini-widget to the data-lake Replaces vehicle store powerSupply/instantaneousWatts access with useDataLakeVariable composable. Voltage, current, and remaining are now read from configurable data lake variable IDs. Raw MAVLink units (mV, cA, %) are converted in local computed properties. Watts is computed locally as voltage * current instead of reading from the store. Removes useMainVehicleStore dependency. Default variable IDs: - voltageVariableId: /mavlink/1/1/SYS_STATUS/voltage_battery - currentVariableId: /mavlink/1/1/SYS_STATUS/current_battery - remainingVariableId: /mavlink/1/1/SYS_STATUS/battery_remaining --- .../mini-widgets/BatteryIndicator.vue | 39 +++++++++++++------ 1 file changed, 28 insertions(+), 11 deletions(-) diff --git a/src/components/mini-widgets/BatteryIndicator.vue b/src/components/mini-widgets/BatteryIndicator.vue index 7410ac2e21..f74d89472b 100644 --- a/src/components/mini-widgets/BatteryIndicator.vue +++ b/src/components/mini-widgets/BatteryIndicator.vue @@ -215,9 +215,9 @@ import { useDebounce } from '@vueuse/core' import { computed, onBeforeMount, onUnmounted, ref, toRefs, watch } from 'vue' import { defaultBatteryLevelColorScheme, defaultBatteryLevelThresholds } from '@/assets/defaults' +import { useDataLakeVariable } from '@/composables/useDataLakeVariable' import { datalogger, DatalogVariable } from '@/libs/sensors-logging' import { useAppInterfaceStore } from '@/stores/appInterface' -import { useMainVehicleStore } from '@/stores/mainVehicle' import { useWidgetManagerStore } from '@/stores/widgetManager' import { BatteryLevel, BatteryLevelThresholds } from '@/types/general' import type { MiniWidget } from '@/types/widgets' @@ -237,9 +237,11 @@ const defaultOptions = { showCurrent: true, showPower: true, toggleInterval: 1000, + voltageVariableId: '/mavlink/1/1/SYS_STATUS/voltage_battery', + currentVariableId: '/mavlink/1/1/SYS_STATUS/current_battery', + remainingVariableId: '/mavlink/1/1/SYS_STATUS/battery_remaining', } -const store = useMainVehicleStore() const widgetStore = useWidgetManagerStore() const interfaceStore = useAppInterfaceStore() @@ -261,13 +263,28 @@ const resetToDefaults = (): void => { miniWidget.value.options.batteryThresholds = Object.assign({}, defaultBatteryLevelThresholds) } +const { value: rawVoltageFromDL } = useDataLakeVariable(() => miniWidget.value.options.voltageVariableId) +const { value: rawCurrentFromDL } = useDataLakeVariable(() => miniWidget.value.options.currentVariableId) +const { value: rawRemainingFromDL } = useDataLakeVariable(() => miniWidget.value.options.remainingVariableId) + +const rawVoltage = computed(() => { + if (rawVoltageFromDL.value === undefined) return null + return (rawVoltageFromDL.value as number) / 1000 +}) + // Round voltage to 0.1V precision for values < 100V, integer precision for >= 100V -const roundedVoltage = computed(() => { - const voltage = store?.powerSupply?.voltage +const roundedVoltage = computed(() => { + const voltage = rawVoltage.value if (voltage === undefined || voltage === null) return null return Math.abs(voltage) >= 100 ? Math.round(voltage) : Math.round(voltage * 10) / 10 }) +const current = computed(() => { + const raw = rawCurrentFromDL.value as number | undefined + if (raw === undefined || raw === -1) return undefined + return raw / 100 +}) + // Keeps a stable voltage reading for 4 seconds to avoid rapid battery level changes const debouncedVoltage = useDebounce(roundedVoltage, 4000) @@ -297,19 +314,19 @@ const voltageDisplayValue = computed(() => { }) const currentDisplayValue = computed(() => { - if (store?.powerSupply?.current === undefined) return '--' - return Math.abs(store.powerSupply.current) >= 100 - ? store.powerSupply.current.toFixed(0) - : store.powerSupply.current.toFixed(1) + if (current.value === undefined) return '--' + return Math.abs(current.value) >= 100 ? current.value.toFixed(0) : current.value.toFixed(1) }) const instantaneousWattsDisplayValue = computed(() => { - return store.instantaneousWatts !== undefined ? store.instantaneousWatts.toFixed(1) : '--' + if (rawVoltage.value === null || current.value === undefined) return '--' + return (rawVoltage.value * current.value).toFixed(1) }) const remainingDisplayValue = computed(() => { - if (store?.powerSupply?.remaining === undefined) return -1 - return Math.abs(store.powerSupply.remaining) > 100 ? 100 : store.powerSupply.remaining + const remaining = rawRemainingFromDL.value as number | undefined + if (remaining === undefined) return -1 + return Math.abs(remaining) > 100 ? 100 : remaining }) const setupToggleInterval = (): void => { From 0a2ba91f31d7ec0dbbf56b97a299b4f03e2f029a Mon Sep 17 00:00:00 2001 From: Rafael Araujo Lehmkuhl Date: Tue, 3 Mar 2026 13:59:46 -0300 Subject: [PATCH 7/9] refactor: migrate DepthHUD widget to the data-lake --- src/components/widgets/DepthHUD.vue | 28 ++++++++++++++++------------ 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/src/components/widgets/DepthHUD.vue b/src/components/widgets/DepthHUD.vue index ddfac6c25a..be7b915dba 100644 --- a/src/components/widgets/DepthHUD.vue +++ b/src/components/widgets/DepthHUD.vue @@ -40,19 +40,19 @@ import gsap from 'gsap' import { unit } from 'mathjs' import { computed, nextTick, onBeforeMount, onMounted, reactive, ref, toRefs, watch } from 'vue' +import { useDataLakeVariable } from '@/composables/useDataLakeVariable' import { datalogger, DatalogVariable } from '@/libs/sensors-logging' import { unitAbbreviation } from '@/libs/units' import { range, resetCanvas, round } from '@/libs/utils' import { useAppInterfaceStore } from '@/stores/appInterface' -import { useMainVehicleStore } from '@/stores/mainVehicle' import { useWidgetManagerStore } from '@/stores/widgetManager' import type { Widget } from '@/types/widgets' -const interfaceStore = useAppInterfaceStore() +const interfaceStore = useAppInterfaceStore() const widgetStore = useWidgetManagerStore() datalogger.registerUsage(DatalogVariable.depth) -const store = useMainVehicleStore() + const props = defineProps<{ /** * Widget reference @@ -64,6 +64,12 @@ const widget = toRefs(props).widget // Pre-defined HUD colors const colorSwatches = ref([['#FF2D2D'], ['#0ADB0ACC'], ['#FFFFFF']]) +const defaultOptions = { + showDepthValue: true, + hudColor: '#FFFFFF', + depthVariableId: '/mavlink/1/1/AHRS2/altitude', +} + type RenderVariables = { /** * Object that stores the current state of the variables used on rendering @@ -90,12 +96,7 @@ const currentUnit = computed(() => unitAbbreviation[interfaceStore.displayUnitPr onBeforeMount(() => { // Set initial widget options if they don't exist - if (Object.keys(widget.value.options).length === 0) { - widget.value.options = { - showDepthValue: true, - hudColor: colorSwatches.value[2][0], - } - } + widget.value.options = { ...defaultOptions, ...widget.value.options } }) onMounted(() => { depthGraphDistances.value.forEach((distance: number) => (renderVars.depthLinesY[distance] = distanceY(distance))) @@ -111,9 +112,12 @@ const canvasSize = computed(() => ({ // The implementation below makes sure we don't update the Depth value in the widget whenever // the system Depth (from vehicle) updates, preventing unnecessary performance bottlenecks. -watch(store.altitude, () => { - const altitude = store.altitude.msl - const newDepth = unit(-altitude.value, altitude.toJSON().unit) +const { value: rawAltitude } = useDataLakeVariable(() => widget.value.options.depthVariableId) + +watch(rawAltitude, (newAlt) => { + if (newAlt === undefined) return + const altMeters = newAlt as number + const newDepth = unit(-altMeters, 'm') const depthDiff = Math.abs(newDepth.value - (depth.value || 0)) if (depthDiff < 0.1) return From cacf723b4a1fafa67e5821691f6e0a29340c0677 Mon Sep 17 00:00:00 2001 From: Rafael Araujo Lehmkuhl Date: Tue, 3 Mar 2026 13:59:51 -0300 Subject: [PATCH 8/9] refactor: migrate SatelliteIndicator mini-widget to the data-lake --- .../mini-widgets/SatelliteIndicator.vue | 48 +++++++++++++++++-- 1 file changed, 44 insertions(+), 4 deletions(-) diff --git a/src/components/mini-widgets/SatelliteIndicator.vue b/src/components/mini-widgets/SatelliteIndicator.vue index 88fb240375..e48ecf1e6e 100644 --- a/src/components/mini-widgets/SatelliteIndicator.vue +++ b/src/components/mini-widgets/SatelliteIndicator.vue @@ -2,17 +2,57 @@
- {{ store.statusGPS.visibleSatellites }} sats - {{ store.statusGPS.fixType }} + {{ satellitesDisplay }} sats + {{ fixTypeDisplay }}
From f774b22b0f3e5aa8bb4f432ccd298aa54a81550c Mon Sep 17 00:00:00 2001 From: Rafael Araujo Lehmkuhl Date: Tue, 3 Mar 2026 13:59:58 -0300 Subject: [PATCH 9/9] refactor: migrate CompassHUD widget to the data-lake --- src/components/widgets/CompassHUD.vue | 72 ++++++++++++++++----------- 1 file changed, 42 insertions(+), 30 deletions(-) diff --git a/src/components/widgets/CompassHUD.vue b/src/components/widgets/CompassHUD.vue index aad0d725c7..5395087c13 100644 --- a/src/components/widgets/CompassHUD.vue +++ b/src/components/widgets/CompassHUD.vue @@ -134,11 +134,11 @@ import { colord } from 'colord' import gsap from 'gsap' import { computed, onBeforeMount, onBeforeUnmount, onMounted, reactive, ref, toRefs, watch } from 'vue' +import { useDataLakeVariable } from '@/composables/useDataLakeVariable' import { calculateHaversineDistance } from '@/libs/mission/general-estimates' import { datalogger, DatalogVariable } from '@/libs/sensors-logging' import { degrees, radians, resetCanvas } from '@/libs/utils' import { useAppInterfaceStore } from '@/stores/appInterface' -import { useMainVehicleStore } from '@/stores/mainVehicle' import { useMissionStore } from '@/stores/mission' import { useWidgetManagerStore } from '@/stores/widgetManager' import type { HighlightedPoiMarker, HighlightedPoiMarkerDisplay, PoiMarker, ReachedPoiMarker } from '@/types/mission' @@ -149,7 +149,6 @@ const interfaceStore = useAppInterfaceStore() const missionStore = useMissionStore() datalogger.registerUsage(DatalogVariable.heading) -const store = useMainVehicleStore() const props = defineProps<{ /** * Widget reference @@ -201,17 +200,20 @@ while (i < 181) { i += 3 } +const defaultOptions = { + showYawValue: true, + hudColor: colorSwatches.value[0][0], + useNegativeRange: false, + yawVariableId: '/mavlink/1/1/ATTITUDE/yaw', + latVariableId: '/mavlink/1/1/GLOBAL_POSITION_INT/lat', + lonVariableId: '/mavlink/1/1/GLOBAL_POSITION_INT/lon', + poi: { + showPoiOnHUD: true, + showDistances: 'onHudSide', + }, +} + onBeforeMount(() => { - // Set initial widget options if they don't exist - const defaultOptions = { - showYawValue: true, - hudColor: colorSwatches.value[0][0], - useNegativeRange: false, - poi: { - showPoiOnHUD: true, - showDistances: 'onHudSide', - }, - } widget.value.options = { ...defaultOptions, ...widget.value.options } }) @@ -231,15 +233,31 @@ const canvasSize = computed(() => ({ height: 64, })) +const { value: rawYaw } = useDataLakeVariable(() => widget.value.options.yawVariableId) +const { value: rawLat } = useDataLakeVariable(() => widget.value.options.latVariableId) +const { value: rawLon } = useDataLakeVariable(() => widget.value.options.lonVariableId) + +const vehicleLatitude = computed(() => { + if (rawLat.value === undefined) return undefined + return (rawLat.value as number) / 1e7 +}) + +const vehicleLongitude = computed(() => { + if (rawLon.value === undefined) return undefined + return (rawLon.value as number) / 1e7 +}) + // The implementation below makes sure we don't update the Yaw value in the widget whenever // the system Yaw (from vehicle) updates, preventing unnecessary performance bottlenecks. const yaw = ref(0) let oldYaw: number | undefined = undefined -watch(store.attitude, (attitude) => { - const yawDiff = Math.abs(degrees(attitude.yaw - (oldYaw || 0))) +watch(rawYaw, (newYaw) => { + if (newYaw === undefined) return + const yawRad = newYaw as number + const yawDiff = Math.abs(degrees(yawRad - (oldYaw || 0))) if (yawDiff > 0.1) { - oldYaw = attitude.yaw - yaw.value = degrees(store.attitude.yaw) + oldYaw = yawRad + yaw.value = degrees(yawRad) } }) @@ -271,16 +289,13 @@ const calculateBearing = (vehicleLat: number, vehicleLng: number, poiLat: number // Get POI data with bearing and distance relative to vehicle const poiData = computed(() => { - if (!store.coordinates.latitude || !store.coordinates.longitude) return [] + if (!vehicleLatitude.value || !vehicleLongitude.value) return [] return missionStore.pointsOfInterest.map((poi) => { - const distance = calculateHaversineDistance( - [store.coordinates.latitude!, store.coordinates.longitude!], - poi.coordinates - ) + const distance = calculateHaversineDistance([vehicleLatitude.value!, vehicleLongitude.value!], poi.coordinates) const bearing = calculateBearing( - store.coordinates.latitude!, - store.coordinates.longitude!, + vehicleLatitude.value!, + vehicleLongitude.value!, poi.coordinates[0], poi.coordinates[1] ) @@ -429,7 +444,7 @@ const renderCanvas = (): void => { } const updatePoiMarkers = (): void => { - if (!widget.value.options.poi?.showPoiOnHUD || !store.coordinates.latitude || !store.coordinates.longitude) { + if (!widget.value.options.poi?.showPoiOnHUD || !vehicleLatitude.value || !vehicleLongitude.value) { poiMarkers.value = [] return } @@ -546,11 +561,8 @@ const updatePoiMarkers = (): void => { lastCardShownAt = now } else { const poi = missionStore.pointsOfInterest.find((p) => p.id === selectedId) - if (poi && store.coordinates.latitude && store.coordinates.longitude) { - const distance = calculateHaversineDistance( - [store.coordinates.latitude, store.coordinates.longitude], - poi.coordinates - ) + if (poi && vehicleLatitude.value && vehicleLongitude.value) { + const distance = calculateHaversineDistance([vehicleLatitude.value, vehicleLongitude.value], poi.coordinates) // How far from a POI to mark as reached highlightedPoiMarker.value = { name: poi.name, @@ -622,7 +634,7 @@ const stopAnimationLoop = (): void => { } const debouncedUpdatePoiMarkers = useDebounceFn(updatePoiMarkers, 16) -watch([poiData, store.coordinates, canvasSize, yaw], debouncedUpdatePoiMarkers) +watch([poiData, vehicleLatitude, vehicleLongitude, canvasSize, yaw], debouncedUpdatePoiMarkers) // Start both canvas and POI markers animation loop when widget becomes visible or data changes watch([renderVars, canvasSize, widget.value.options], () => {