Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
150 changes: 115 additions & 35 deletions core/frontend/src/components/app/Alerter.vue
Original file line number Diff line number Diff line change
@@ -1,56 +1,127 @@
<template>
<v-snackbar
v-model="show"
:timeout="timeout"
>
{{ message }}

<template #action="{ attrs }">
<v-btn
:color="color"
text
v-bind="attrs"
@click="show = false"
<div class="alerter-stack">
<v-slide-y-reverse-transition
group
leave-absolute
>
<v-alert
v-for="alert in alerts"
:key="alert.id"
:value="true"
:type="alertType(alert.level)"
class="alerter-item"
dense
dismissible
elevation="6"
@input="dismiss(alert.id)"
>
Close
</v-btn>
</template>
</v-snackbar>
{{ alert.message }}
</v-alert>
</v-slide-y-reverse-transition>
</div>
</template>

<script lang="ts">
import Vue from 'vue'

import message_manager, { MessageLevel } from '@/libs/message-manager'

const MAX_VISIBLE = 5
const DRAIN_INTERVAL_MS = 1000

interface AlertEntry {
id: number
level: MessageLevel
message: string
}

let nextId = 0

export default Vue.extend({
name: 'ErrorMessage',
data() {
return {
level: undefined as MessageLevel|undefined,
message: '',
show: false,
alerts: [] as AlertEntry[],
queue: [] as AlertEntry[],
drainTimer: null as ReturnType<typeof setInterval> | null,
boundCallback: null as ((level: MessageLevel, msg: string) => void) | null,
}
},
mounted() {
this.boundCallback = (level: MessageLevel, message: string) => {
nextId += 1
const entry = { id: nextId, level, message }
if (this.alerts.length < MAX_VISIBLE) {
this.showAlert(entry)
} else {
this.queue.push(entry)
this.startDrain()
}
}
message_manager.addCallback(this.boundCallback)
},
beforeDestroy() {
if (this.boundCallback) {
message_manager.removeCallback(this.boundCallback)
this.boundCallback = null
}
this.stopDrain()
},
computed: {
color(): string {
switch (this.level) {
methods: {
showAlert(entry: AlertEntry) {
this.alerts.push(entry)
const timeout = this.getTimeout(entry.level)
if (timeout > 0) {
setTimeout(() => this.dismiss(entry.id), timeout)
}
},
dismiss(id: number) {
const idx = this.alerts.findIndex((a) => a.id === id)
if (idx !== -1) {
this.alerts.splice(idx, 1)
this.promoteFromQueue()
}
},
promoteFromQueue() {
while (this.queue.length > 0 && this.alerts.length < MAX_VISIBLE) {
this.showAlert(this.queue.shift()!)
}
if (this.queue.length === 0) {
this.stopDrain()
}
},
startDrain() {
if (this.drainTimer) return
this.drainTimer = setInterval(() => {
const evictIdx = this.alerts.findIndex((a) => this.getTimeout(a.level) > 0)
if (evictIdx !== -1) {
this.dismiss(this.alerts[evictIdx].id)
} else if (this.queue.length > 0 && this.alerts.length > 0) {
this.dismiss(this.alerts[0].id)
}
}, DRAIN_INTERVAL_MS)
},
stopDrain() {
if (this.drainTimer) {
clearInterval(this.drainTimer)
this.drainTimer = null
}
},
alertType(level: MessageLevel): string {
switch (level) {
case MessageLevel.Success:
return 'success'
case MessageLevel.Error:
case MessageLevel.Critical:
return 'error'
case MessageLevel.Info:
return 'info'
case MessageLevel.Warning:
return 'warning'
case MessageLevel.Critical:
return 'critical'
default:
return 'info'
}
},
timeout(): number {
switch (this.level) {
getTimeout(level: MessageLevel): number {
switch (level) {
case MessageLevel.Success:
case MessageLevel.Info:
return 5000
Expand All @@ -61,12 +132,21 @@ export default Vue.extend({
}
},
},
mounted() {
message_manager.addCallback((level: MessageLevel, message: string) => {
this.level = level
this.message = message
this.show = true
})
},
})
</script>

<style scoped>
.alerter-stack {
position: fixed;
bottom: 16px;
left: 50%;
transform: translateX(-50%);
z-index: 1000;
min-width: 344px;
max-width: 672px;
}

.alerter-item {
margin-bottom: 8px;
}
</style>
10 changes: 10 additions & 0 deletions core/frontend/src/libs/message-manager.ts
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,16 @@ class MessageManager {
this.callbacks.push(callback)
}

/**
* Remove a previously added callback
*/
removeCallback(callback:(level: MessageLevel, msg: string) => void): void {
const index = this.callbacks.indexOf(callback)
if (index !== -1) {
this.callbacks.splice(index, 1)
}
}

/**
* Emit a new message to be used in all callbacks
*/
Expand Down
18 changes: 14 additions & 4 deletions core/frontend/src/types/autopilot/parameter-fetcher.ts
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
import mavlink2rest from '@/libs/MAVLink2Rest'
import message_manager, { MessageLevel } from '@/libs/message-manager'
import settings from '@/libs/settings'
// eslint-disable-next-line import/no-cycle
import ardupilot_data from '@/store/autopilot'
import { AutopilotStore } from '@/store/autopilot'
Expand Down Expand Up @@ -33,6 +35,10 @@ export default class ParameterFetcher {
this.store = store
}

allParametersLoaded(): boolean {
return this.total_params_count !== null && this.loaded_params_count >= this.total_params_count
}

reset(): void {
this.loaded_params_count = 0
this.total_params_count = null
Expand All @@ -57,9 +63,7 @@ export default class ParameterFetcher {
}

requestParamsWatchdog(): void {
if (this.total_params_count !== null
&& this.loaded_params_count > 0
&& this.loaded_params_count >= this.total_params_count) {
if (this.loaded_params_count > 0 && this.allParametersLoaded()) {
return
}
if (autopilot.restarting) {
Expand Down Expand Up @@ -107,7 +111,13 @@ export default class ParameterFetcher {
// We need this due to mismatches between js 64-bit floats and REAL32 in MAVLink
const trimmed_value = Math.round(param_value * 10000) / 10000
if (param_index === 65535) {
this.parameter_table.updateParam(param_name, trimmed_value)
const change = this.parameter_table.updateParam(param_name, trimmed_value)
if (change && this.allParametersLoaded() && settings.is_dev_mode) {
message_manager.emitMessage(
MessageLevel.Info,
`Parameter ${param_name} changed: ${change.oldValue} → ${trimmed_value}`,
)
}
} else {
this.parameter_table.addParam(
{
Expand Down
12 changes: 9 additions & 3 deletions core/frontend/src/types/autopilot/parameter-table.ts
Original file line number Diff line number Diff line change
Expand Up @@ -190,15 +190,21 @@ export default class ParametersTable {
this.parametersDict[param.id] = param
}

updateParam(param_name: string, param_value: number): void {
updateParam(param_name: string, param_value: number): { oldValue: number } | null {
const index = Object.entries(this.parametersDict).find(([_key, value]) => value.name === param_name)
if (!index) {
// This is benign and will happen if we receive a parameter update before the parameters table
// is fully populated. We can safely ignore it.
console.info(`Unable to update param in store: ${param_name}. Parameter not yet loaded into ParametersTable.`)
return
return null
}
const paramKey = parseInt(index[0], 10)
const oldValue = this.parametersDict[paramKey].value
this.parametersDict[paramKey].value = param_value
if (oldValue !== param_value) {
return { oldValue }
}
this.parametersDict[parseInt(index[0], 10)].value = param_value
return null
}

parameters(): Parameter[] {
Expand Down
Loading