Skip to content
Open
39 changes: 28 additions & 11 deletions src/components/mini-widgets/BatteryIndicator.vue
Original file line number Diff line number Diff line change
Expand Up @@ -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'
Expand All @@ -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()

Expand All @@ -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<number | null>(() => {
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<number | null>(() => {
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<number | undefined>(() => {
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)

Expand Down Expand Up @@ -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 => {
Expand Down
32 changes: 26 additions & 6 deletions src/components/mini-widgets/DepthIndicator.vue
Original file line number Diff line number Diff line change
Expand Up @@ -17,21 +17,40 @@

<script setup lang="ts">
import { unit } from 'mathjs'
import { computed, ref, watch } from 'vue'
import { computed, onBeforeMount, ref, toRefs, watch } from 'vue'

import { useDataLakeVariable } from '@/composables/useDataLakeVariable'
import { datalogger, DatalogVariable } from '@/libs/sensors-logging'
import { unitAbbreviation } from '@/libs/units'
import { useAppInterfaceStore } from '@/stores/appInterface'
import { useMainVehicleStore } from '@/stores/mainVehicle'
import type { MiniWidget } from '@/types/widgets'

const props = defineProps<{
/**
* Mini widget reference
*/
miniWidget: MiniWidget
}>()
const miniWidget = toRefs(props).miniWidget

const defaultOptions = {
depthVariableId: '/mavlink/1/1/AHRS2/altitude',
}

onBeforeMount(() => {
miniWidget.value.options = { ...defaultOptions, ...miniWidget.value.options }
})

const vehicleStore = useMainVehicleStore()
const { displayUnitPreferences } = useAppInterfaceStore()
datalogger.registerUsage(DatalogVariable.depth)

const { value: rawAltitude } = useDataLakeVariable(() => miniWidget.value.options.depthVariableId)

const currentDepth = ref<undefined | number>(undefined)
watch(vehicleStore.altitude, () => {
const altitude = vehicleStore.altitude.msl
const depth = unit(-altitude.value, altitude.toJSON().unit)
watch(rawAltitude, (newAlt) => {
if (newAlt === undefined) return
const altMeters = newAlt as number
const depth = unit(-altMeters, 'm')
if (depth.value < 0.01) {
currentDepth.value = 0
return
Expand All @@ -40,6 +59,7 @@ watch(vehicleStore.altitude, () => {
const depthConverted = depth.to(displayUnitPreferences.distance)
currentDepth.value = depthConverted.toJSON().value
})

const parsedState = computed(() => {
const fDepth = currentDepth.value
if (fDepth === undefined) return '--'
Expand Down
28 changes: 24 additions & 4 deletions src/components/mini-widgets/RelativeAltitudeIndicator.vue
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,33 @@
</template>

<script setup lang="ts">
import { ref, watch } from 'vue'
import { onBeforeMount, ref, toRefs, watch } from 'vue'

import { useDataLakeVariable } from '@/composables/useDataLakeVariable'
import { round } from '@/libs/utils'
import { useMainVehicleStore } from '@/stores/mainVehicle'
import type { MiniWidget } from '@/types/widgets'

const store = useMainVehicleStore()
const props = defineProps<{
/**
* Mini widget reference
*/
miniWidget: MiniWidget
}>()
const miniWidget = toRefs(props).miniWidget

const defaultOptions = {
altitudeVariableId: '/mavlink/1/1/GLOBAL_POSITION_INT/relative_alt',
}

onBeforeMount(() => {
miniWidget.value.options = { ...defaultOptions, ...miniWidget.value.options }
})

const { value: rawAlt } = useDataLakeVariable(() => miniWidget.value.options.altitudeVariableId)

const altitude = ref(0)
watch(store.altitude, () => (altitude.value = store.altitude.rel))
watch(rawAlt, (newAlt) => {
if (newAlt === undefined) return
altitude.value = (newAlt as number) / 1000
})
</script>
48 changes: 44 additions & 4 deletions src/components/mini-widgets/SatelliteIndicator.vue
Original file line number Diff line number Diff line change
Expand Up @@ -2,17 +2,57 @@
<div class="flex items-center w-fit min-w-[8rem] max-w-[9rem] h-12 p-1 text-white justify-center">
<span class="relative w-[2.25rem] mdi mdi-satellite-variant text-4xl"></span>
<div class="flex flex-col items-start justify-center ml-1 min-w-[4rem] max-w-[6rem] select-none">
<span class="font-mono font-semibold leading-4 text-end w-fit">{{ store.statusGPS.visibleSatellites }} sats</span>
<span class="font-mono text-sm font-semibold leading-4 text-end w-fit">{{ store.statusGPS.fixType }}</span>
<span class="font-mono font-semibold leading-4 text-end w-fit">{{ satellitesDisplay }} sats</span>
<span class="font-mono text-sm font-semibold leading-4 text-end w-fit">{{ fixTypeDisplay }}</span>
</div>
</div>
</template>

<script setup lang="ts">
import { computed, onBeforeMount, toRefs } from 'vue'

import { useDataLakeVariable } from '@/composables/useDataLakeVariable'
import { datalogger, DatalogVariable } from '@/libs/sensors-logging'
import { useMainVehicleStore } from '@/stores/mainVehicle'
import type { MiniWidget } from '@/types/widgets'

const gpsFixTypeLabels: Record<string, string> = {
GPS_FIX_TYPE_NO_GPS: 'No GPS',
GPS_FIX_TYPE_NO_FIX: 'No fix',
GPS_FIX_TYPE_2D_FIX: '2D fix',
GPS_FIX_TYPE_3D_FIX: '3D fix',
GPS_FIX_TYPE_DGPS: 'DGPS fix',
GPS_FIX_TYPE_RTK_FLOAT: 'RTK float',
GPS_FIX_TYPE_RTK_FIXED: 'RTK fix',
GPS_FIX_TYPE_STATIC: 'Static',
GPS_FIX_TYPE_PPP: 'PPP fix',
}

const props = defineProps<{
/**
* Mini widget reference
*/
miniWidget: MiniWidget
}>()
const miniWidget = toRefs(props).miniWidget

const defaultOptions = {
satellitesVariableId: '/mavlink/1/1/GPS_RAW_INT/satellites_visible',
fixTypeVariableId: '/mavlink/1/1/GPS_RAW_INT/fix_type',
}

onBeforeMount(() => {
miniWidget.value.options = { ...defaultOptions, ...miniWidget.value.options }
})

datalogger.registerUsage(DatalogVariable.gpsFixType)
datalogger.registerUsage(DatalogVariable.gpsVisibleSatellites)
const store = useMainVehicleStore()

const { value: rawSatellites } = useDataLakeVariable(() => miniWidget.value.options.satellitesVariableId)
const { value: rawFixType } = useDataLakeVariable(() => miniWidget.value.options.fixTypeVariableId)

const satellitesDisplay = computed(() => rawSatellites.value ?? '--')
const fixTypeDisplay = computed(() => {
if (rawFixType.value === undefined) return '--'
return gpsFixTypeLabels[rawFixType.value as string] ?? rawFixType.value
})
</script>
53 changes: 28 additions & 25 deletions src/components/widgets/Attitude.vue
Original file line number Diff line number Diff line change
Expand Up @@ -72,10 +72,10 @@ import { useElementVisibility, useWindowSize } from '@vueuse/core'
import gsap from 'gsap'
import { computed, nextTick, onBeforeMount, onMounted, reactive, ref, toRefs, watch } from 'vue'

import { useDataLakeVariable } from '@/composables/useDataLakeVariable'
import { datalogger, DatalogVariable } from '@/libs/sensors-logging'
import { constrain, degrees, radians, 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'

Expand All @@ -84,7 +84,6 @@ const interfaceStore = useAppInterfaceStore()

datalogger.registerUsage(DatalogVariable.roll)
datalogger.registerUsage(DatalogVariable.pitch)
const store = useMainVehicleStore()
const props = defineProps<{
/**
* Widget reference
Expand Down Expand Up @@ -142,14 +141,14 @@ const defaultOptions = {
desiredAimRadius: 150,
hudColor: colorSwatches.value[0][0],
cameraFOV: 64,
rollVariableId: '/mavlink/1/1/ATTITUDE/roll',
pitchVariableId: '/mavlink/1/1/ATTITUDE/pitch',
cameraTiltVariableId: 'cameraTiltDeg',
}

onBeforeMount(() => {
// Set initial widget options if they don't exist
Object.entries(defaultOptions).forEach(([key, value]) => {
if (widget.value.options[key] === undefined) {
widget.value.options[key] = value
}
})
widget.value.options = { ...defaultOptions, ...widget.value.options }
})

onMounted(() => {
Expand All @@ -172,27 +171,31 @@ const aimRadius = computed(() => constrain(widget.value.options.desiredAimRadius
* Deal with high frequency update and decrease cpu usage when drawing
* low degrees changes
*/
let oldRoll: number | undefined = undefined
let oldPitch: number | undefined = undefined
watch(store.attitude, (attitude) => {
const rollDiff = Math.abs(degrees(attitude.roll - (oldRoll || 0)))
const pitchDiff = Math.abs(degrees(attitude.pitch - (oldPitch || 0)))

if (rollDiff > 0.1) {
oldRoll = attitude.roll
rollAngleDeg.value = degrees(store.attitude.roll)
const { value: rawRoll } = useDataLakeVariable(() => widget.value.options.rollVariableId)
const { value: rawPitch } = useDataLakeVariable(() => widget.value.options.pitchVariableId)
const { value: rawCameraTilt } = useDataLakeVariable(() => widget.value.options.cameraTiltVariableId)

watch(rawRoll, (newRoll) => {
if (newRoll === undefined) return
const deg = degrees(newRoll as number)
if (Math.abs(deg - rollAngleDeg.value) > 0.1) {
rollAngleDeg.value = deg
}
})

if (pitchDiff > 0.1) {
oldPitch = attitude.pitch
pitchAngleDeg.value = degrees(store.attitude.pitch)
watch(rawPitch, (newPitch) => {
if (newPitch === undefined) return
const deg = degrees(newPitch as number)
if (Math.abs(deg - pitchAngleDeg.value) > 0.1) {
pitchAngleDeg.value = deg
}
})

watch(store.genericVariables, (message: Record<string, unknown>) => {
const new_tilt = message.cameraTiltDeg as number
if (cameraTiltDeg.value === undefined || Math.abs(new_tilt - cameraTiltDeg.value) > 0.1) {
cameraTiltDeg.value = new_tilt
watch(rawCameraTilt, (newTilt) => {
if (newTilt === undefined) return
const tilt = newTilt as number
if (cameraTiltDeg.value === undefined || Math.abs(tilt - cameraTiltDeg.value) > 0.1) {
cameraTiltDeg.value = tilt
}
})

Expand Down Expand Up @@ -328,7 +331,7 @@ const renderCanvas = (): void => {
// Update the height of each pitch line when the vehicle pitch is updated
watch(pitchAngleDeg, () => {
pitchAngles.forEach((angle: number) => {
const y = -round(angleY(angle + renderVars.cameraTiltDeg - degrees(store.attitude.pitch)), 2)
const y = -round(angleY(angle + renderVars.cameraTiltDeg - pitchAngleDeg.value), 2)
gsap.to(renderVars.pitchLinesHeights, 0.1, { [angle]: y })
})
gsap.to(renderVars, 0.1, { pitchDegrees: pitchAngleDeg.value })
Expand All @@ -342,7 +345,7 @@ watch(rollAngleDeg, () => {
watch(cameraTiltDeg, () => {
gsap.to(renderVars, 0.1, { cameraTiltDeg: cameraTiltDeg.value })
pitchAngles.forEach((angle: number) => {
const y = -round(angleY(angle + renderVars.cameraTiltDeg - degrees(store.attitude.pitch)), 2)
const y = -round(angleY(angle + renderVars.cameraTiltDeg - pitchAngleDeg.value), 2)
gsap.to(renderVars.pitchLinesHeights, 0.1, { [angle]: y })
})
})
Expand Down
Loading
Loading