Skip to content

Commit

Permalink
units: Implement unit usage on altitude/depth data
Browse files Browse the repository at this point in the history
  • Loading branch information
rafaellehmkuhl authored and ArturoManzoli committed Jul 24, 2024
1 parent 2e9b3e0 commit f69d057
Show file tree
Hide file tree
Showing 5 changed files with 53 additions and 24 deletions.
29 changes: 22 additions & 7 deletions src/components/mini-widgets/DepthIndicator.vue
Original file line number Diff line number Diff line change
Expand Up @@ -3,28 +3,43 @@
<img src="@/assets/depth-icon.svg" class="h-[80%] left-[0.5rem] top-[13%] absolute" :draggable="false" />
<div class="absolute left-[3rem] flex flex-col items-start justify-center select-none">
<div>
<span class="font-mono text-xl font-semibold leading-6 w-fit">{{ finalDepth.toFixed(precision) }}</span>
<span class="text-xl font-semibold leading-6 w-fit"> m</span>
<span class="font-mono text-xl font-semibold leading-6 w-fit">{{ currentDepth.toFixed(precision) }}</span>
<span class="text-xl font-semibold leading-6 w-fit">
{{ String.fromCharCode(0x20) }}{{ unitAbbreviation[displayUnitPreferences.distance] }}
</span>
</div>
<span class="w-full text-sm font-semibold leading-4 whitespace-nowrap">Depth</span>
</div>
</div>
</template>

<script setup lang="ts">
import { unit } from 'mathjs'
import { computed, ref, watch } from 'vue'
import { datalogger, DatalogVariable } from '@/libs/sensors-logging'
import { unitAbbreviation } from '@/libs/units'
import { useAppInterfaceStore } from '@/stores/appInterface'
import { useMainVehicleStore } from '@/stores/mainVehicle'
const store = useMainVehicleStore()
const vehicleStore = useMainVehicleStore()
const { displayUnitPreferences } = useAppInterfaceStore()
datalogger.registerUsage(DatalogVariable.depth)
const depth = ref(0)
watch(store.altitude, () => (depth.value = -store.altitude.msl))
const finalDepth = computed(() => (depth.value < 0.01 ? 0 : depth.value))
const currentDepth = ref(0)
watch(vehicleStore.altitude, () => {
const altitude = vehicleStore.altitude.msl
const depth = unit(-altitude.value, altitude.toJSON().unit)
if (depth.value < 0.01) {
currentDepth.value = 0
return
}
const depthConverted = depth.to(displayUnitPreferences.distance)
currentDepth.value = depthConverted.toJSON().value
})
const precision = computed(() => {
const fDepth = finalDepth.value
const fDepth = currentDepth.value
if (fDepth < 10) return 2
if (fDepth >= 10 && fDepth < 1000) return 1
return 0
Expand Down
29 changes: 16 additions & 13 deletions src/components/widgets/DepthHUD.vue
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,12 @@
import { useWindowSize } from '@vueuse/core'
import { colord } from 'colord'
import gsap from 'gsap'
import { unit } from 'mathjs'
import { computed, nextTick, onBeforeMount, onMounted, reactive, ref, toRefs, watch } from 'vue'
import { datalogger, DatalogVariable } from '@/libs/sensors-logging'
import { constrain, range, resetCanvas, round } from '@/libs/utils'
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'
Expand Down Expand Up @@ -84,6 +86,7 @@ const maxRecentDepth = computed(() => Math.max(...recentDepths.value))
const maxGraphDepth = computed(() => (1.3 * maxRecentDepth.value > 10 ? 1.3 * maxRecentDepth.value : 10))
const depthGraphDistances = computed(() => range(0, maxGraphDepth.value + 1))
const maxDepth = computed(() => Math.max(...depthGraphDistances.value))
const currentUnit = computed(() => unitAbbreviation[interfaceStore.displayUnitPreferences.distance])
onBeforeMount(() => {
// Set initial widget options if they don't exist
Expand All @@ -108,16 +111,16 @@ 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.msl,
(newMslAltitude) => {
const newDepth = -1 * constrain(newMslAltitude, newMslAltitude, 0)
const depthDiff = Math.abs(newDepth - (depth.value || 0))
if (depthDiff > 0.1) {
passedDepths.value.push(newDepth)
}
}
)
watch(store.altitude, () => {
const altitude = store.altitude.msl
const newDepth = unit(-altitude.value, altitude.toJSON().unit)
const depthDiff = Math.abs(newDepth.value - (depth.value || 0))
if (depthDiff < 0.1) return
const depthConverted = newDepth.to(interfaceStore.displayUnitPreferences.distance)
passedDepths.value.push(depthConverted.toJSON().value)
})
// Returns the projected Y position of the depth line for a given distance
const distanceY = (altitude: number): number => {
Expand Down Expand Up @@ -173,7 +176,7 @@ const renderCanvas = (): void => {
ctx.lineWidth = '2'
ctx.moveTo(canvasWidth - stdPad - 3.3 * linesFontSize, y + initialPaddingY)
ctx.lineTo(stdPad + 3.9 * refFontSize + refTriangleSize, y + initialPaddingY)
ctx.fillText(`${distance} m`, canvasWidth - stdPad - 3 * linesFontSize, y + initialPaddingY)
ctx.fillText(`${distance} ${currentUnit.value}`, canvasWidth - stdPad - 3 * linesFontSize, y + initialPaddingY)
}
ctx.stroke()
}
Expand All @@ -188,7 +191,7 @@ const renderCanvas = (): void => {
ctx.textAlign = 'right'
ctx.font = `bold ${refFontSize}px Arial`
ctx.fillText(
`${depth.value.toFixed(1)} m`,
`${depth.value.toFixed(1)} ${currentUnit.value}`,
stdPad + 4.3 * refFontSize - refTriangleSize - stdPad,
indicatorY + initialPaddingY
)
Expand Down
10 changes: 9 additions & 1 deletion src/libs/sensors-logging.ts
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,11 @@ import Swal from 'sweetalert2'

import { defaultSensorDataloggerProfile } from '@/assets/defaults'
import { useBlueOsStorage } from '@/composables/settingsSyncer'
import { useAppInterfaceStore } from '@/stores/appInterface'
import { useMainVehicleStore } from '@/stores/mainVehicle'
import { useMissionStore } from '@/stores/mission'

import { unitAbbreviation } from './units'
import { degrees } from './utils'

/**
Expand Down Expand Up @@ -239,6 +241,7 @@ class DataLogger {

const vehicleStore = useMainVehicleStore()
const missionStore = useMissionStore()
const interfaceStore = useAppInterfaceStore()

const initialTime = new Date()
const fileName = `Cockpit (${format(initialTime, `${logDateFormat} - HH꞉mm꞉ss O`)}).clog`
Expand All @@ -250,12 +253,17 @@ class DataLogger {

const timeNowObj = { lastChanged: timeNow.getTime() }

const unitPrefs = interfaceStore.displayUnitPreferences

const depthValue = (-vehicleStore.altitude.msl?.to(unitPrefs.distance).toJSON().value).toPrecision(4)
const depthUnit = unitAbbreviation[unitPrefs.distance]

/* eslint-disable vue/max-len, prettier/prettier, max-len */
let variablesData: ExtendedVariablesData = {
[DatalogVariable.roll]: { value: `${degrees(vehicleStore.attitude.roll)?.toFixed(1)} °`, ...timeNowObj },
[DatalogVariable.pitch]: { value: `${degrees(vehicleStore.attitude.pitch)?.toFixed(1)} °`, ...timeNowObj },
[DatalogVariable.heading]: { value: `${degrees(vehicleStore.attitude.yaw)?.toFixed(1)} °`, ...timeNowObj },
[DatalogVariable.depth]: { value: `${vehicleStore.altitude.msl?.toPrecision(4)} m`, ...timeNowObj },
[DatalogVariable.depth]: { value: `${depthValue} ${depthUnit}`, ...timeNowObj },
[DatalogVariable.mode]: { value: vehicleStore.mode || 'Unknown', ...timeNowObj },
[DatalogVariable.batteryVoltage]: { value: `${vehicleStore.powerSupply.voltage?.toFixed(2)} V` || 'Unknown', ...timeNowObj },
[DatalogVariable.batteryCurrent]: { value: `${vehicleStore.powerSupply.current?.toFixed(2)} A` || 'Unknown', ...timeNowObj },
Expand Down
5 changes: 3 additions & 2 deletions src/libs/vehicle/ardupilot/ardupilot.ts
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
import { differenceInMilliseconds } from 'date-fns'
import { unit } from 'mathjs'

import { sendMavlinkMessage } from '@/libs/communication/mavlink'
import type { MAVLinkMessageDictionary, Package, Type } from '@/libs/connection/m2r/messages/mavlink2rest'
Expand Down Expand Up @@ -53,7 +54,7 @@ export type ArduPilot = ArduPilotVehicle<any>
* Generic ArduPilot vehicle
*/
export abstract class ArduPilotVehicle<Modes> extends Vehicle.AbstractVehicle<Modes> {
_altitude = new Altitude({ msl: 0, rel: 0 })
_altitude = new Altitude({ msl: unit(0, 'm'), rel: 0 })
_attitude = new Attitude({ roll: 0, pitch: 0, yaw: 0 })
_communicationDropRate = 0
_communicationErrors = 0
Expand Down Expand Up @@ -345,7 +346,7 @@ export abstract class ArduPilotVehicle<Modes> extends Vehicle.AbstractVehicle<Mo
}
case MAVLinkType.AHRS2: {
const ahrsMessage = mavlink_message.message as Message.Ahrs2
this._altitude.msl = ahrsMessage.altitude
this._altitude.msl = unit(ahrsMessage.altitude, 'm')
this.onAltitude.emit()
break
}
Expand Down
4 changes: 3 additions & 1 deletion src/libs/vehicle/types.ts
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
import { Unit } from 'mathjs'

import type { Type } from '@/libs/connection/m2r/messages/mavlink2rest'
import { MavCmd, MavResult } from '@/libs/connection/m2r/messages/mavlink2rest-enum'
import { AlertLevel } from '@/types/alert'
Expand Down Expand Up @@ -143,7 +145,7 @@ export class Attitude {
* Altitude related data
*/
export class Altitude {
msl: number // Mean Sea Level, in meters
msl: Unit // Mean Sea Level altitude
rel: number // Relative altitude, in meters
/**
* Create object
Expand Down

0 comments on commit f69d057

Please sign in to comment.