-
Notifications
You must be signed in to change notification settings - Fork 64
/
ParamSets.vue
233 lines (222 loc) · 6.91 KB
/
ParamSets.vue
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
<template>
<v-row>
<v-card class="ma-2 pa-2">
<v-card-title class="align-center">
Reset Parameters to Firmware Defaults
</v-card-title>
<v-card-text>
<p>
This will effectively wipe your "eeprom". You will lose all your parameters, vehicle setup, and calibrations.
Use this if you don't know which parameters you changed and need a clean start.
</p>
<v-btn :disabled="reset_successful" :loading="erasing" color="primary" @click="wipe">
Reset All Parameters
</v-btn>
<v-btn
v-if="reset_successful && !done"
color="warning"
:loading="rebooting"
@click="restartAutopilot"
>
Reboot Autopilot
</v-btn>
<v-alert
v-if="reset_successful"
dense
text
type="success"
>
Parameters reset <b>successful</b>. <span v-if="!done"> Please reboot the vehicle to apply changes. </span>
</v-alert>
</v-card-text>
<parameterloader
v-if="selected_paramset"
:parameters="selected_paramset"
@done="selected_paramset = {}"
/>
</v-card>
<v-card class="ma-2 pa-2">
<v-card-title class="align-center">
Load Recommended Parameter sets
</v-card-title>
<v-card-text>
<p>
These are the recommended parameter sets for your vehicle and firmware version. Curated by Blue Robotics
</p>
<v-btn
v-for="(paramSet, name) in filtered_param_sets"
:key="name"
color="primary"
@click="loadParams(name, paramSet)"
>
{{ name.split('/').pop() }}
</v-btn>
<p v-if="(Object.keys(filtered_param_sets).length === 0)">
No parameters available for this setup
</p>
</v-card-text>
<parameterloader
v-if="selected_paramset"
:parameters="selected_paramset"
@done="selected_paramset = {}"
/>
</v-card>
</v-row>
</template>
<script lang="ts">
import { SemVer } from 'semver'
import Vue from 'vue'
import * as AutopilotManager from '@/components/autopilot/AutopilotManagerUpdater'
import parameterloader from '@/components/parameter-editor/ParameterLoader.vue'
import mavlink2rest from '@/libs/MAVLink2Rest'
import { MavCmd } from '@/libs/MAVLink2Rest/mavlink2rest-ts/messages/mavlink2rest-enum'
import Notifier from '@/libs/notifier'
import autopilot_data from '@/store/autopilot'
import autopilot from '@/store/autopilot_manager'
import { Dictionary } from '@/types/common'
import { frontend_service } from '@/types/frontend_services'
const notifier = new Notifier(frontend_service)
const REPOSITORY_URL = 'https://docs.bluerobotics.com/Blueos-Parameter-Repository/params_v1.json'
export default Vue.extend({
name: 'ParamSets',
components: {
parameterloader,
},
data: () => ({
all_param_sets: {} as Dictionary<Dictionary<number>>,
selected_paramset: {} as Dictionary<number>,
selected_paramset_name: undefined as (undefined | string),
reset_successful: false,
rebooting: false,
done: false,
erasing: false,
}),
computed: {
board(): string | undefined {
return autopilot.current_board?.name
},
vehicle(): string | null {
return autopilot.firmware_vehicle_type
},
version(): SemVer | undefined {
return autopilot.firmware_info?.version
},
filtered_param_sets(): Dictionary<Dictionary<number>> | undefined {
const fw_patch = `${this.vehicle}/${this.version}/${this.board}`
const fw_minor = `${this.vehicle}/${this.version?.major}.${this.version?.minor}/${this.board}`
const fw_major = `${this.vehicle}/${this.version?.major}/${this.board}`
// returns a new dict where the keys start with the fullname
// e.g. "ArduSub/BlueROV2/4.0.3" -> "ArduSub/BlueROV2/4.0.3/BlueROV2"
let fw_params = {}
// try to find a paramset that matches the firmware version, starting from patch and walking up to major
for (const string of [fw_patch, fw_minor, fw_major]) {
fw_params = Object.fromEntries(
Object.entries(this.all_param_sets).filter(
([name]) => name.toLocaleLowerCase().includes(string.toLowerCase()),
),
)
if (Object.keys(fw_params).length > 0) {
break
}
}
return {
...fw_params,
}
},
},
mounted() {
this.loadParamSets()
},
methods: {
async loadParamSets() {
const response = await fetch(REPOSITORY_URL)
const paramSets = await response.json()
this.all_param_sets = paramSets
},
async loadParams(name: string, paramset: Dictionary<number>) {
this.selected_paramset_name = name
this.selected_paramset = paramset
},
async restartAutopilot(): Promise<void> {
this.rebooting = true
await AutopilotManager.restart()
autopilot_data.reset()
// reset to initial
this.done = true
this.rebooting = false
},
wipe() {
this.erasing = true
mavlink2rest.sendMessage({
header: {
system_id: 255,
component_id: 1,
sequence: 1,
},
message: {
type: 'COMMAND_LONG',
param1: 2, // PARAM_RESET_CONFIG_DEFAULT from MAV_CMD_PREFLIGHT_STORAGE
param2: 0,
param3: 0,
param4: 0,
param5: 0,
param6: 0,
param7: 0,
command: {
type: MavCmd.MAV_CMD_PREFLIGHT_STORAGE,
},
target_system: autopilot_data.system_id,
target_component: 1,
confirmation: 1,
},
})
let timeout = 0
const ack_listener = mavlink2rest.startListening('COMMAND_ACK').setCallback((message) => {
if (message.message.command.type === 'MAV_CMD_PREFLIGHT_STORAGE') {
if (message.message.result.type === 'MAV_RESULT_ACCEPTED') {
clearTimeout(timeout)
this.reset_successful = true
ack_listener.discard()
autopilot_data.setRebootRequired(true)
this.erasing = false
return
}
this.reset_successful = false
ack_listener.discard()
clearTimeout(timeout)
this.erasing = false
notifier.pushError('PARAM_RESET_FAIL', `Parameters Reset failed: ${message.message.result.type}`, true)
}
})
timeout = setTimeout(() => {
ack_listener.discard()
this.reset_successful = false
this.erasing = false
notifier.pushError('PARAM_RESET_TIMEOUT', 'Parameters Reset timed out', true)
}, 2000)
},
},
})
</script>
<style scoped>
button {
margin: 10px;
}
.virtual-table-row {
display: flex;
margin: 0;
margin-bottom: 15px;
border-bottom: 1px solid #eee;
}
.virtual-table-cell {
flex: 1;
padding: 5px;
height: 30px;
}
.virtual-table-cell .v-input {
margin-top: -6px;
}
.checkbox-label label {
font-weight: 700;
}
</style>