23
23
<th class =" text-left subtitle-1 font-weight-bold" >
24
24
Motor Test
25
25
</th >
26
+ <th />
26
27
<th >
27
28
<v-switch
28
29
v-model =" desired_armed_state"
52
53
<td width =" 20%" >
53
54
{{ motor.name }}
54
55
</td >
56
+ <td width =" 10%" >
57
+ <parameterSwitch
58
+ v-if =" motor.reverse_parameter"
59
+ :parameter =" motor.reverse_parameter"
60
+ :on-value =" reverse_on_value"
61
+ :off-value =" reverse_off_value"
62
+ label =" Reversed"
63
+ />
64
+ </td >
55
65
<td width =" 80%" >
56
66
<v-slider
57
67
v-model =" motor_targets[motor.target]"
@@ -154,10 +164,14 @@ import { SERVO_FUNCTION } from '@/types/autopilot/parameter-sub-enums'
154
164
import { Dictionary } from ' @/types/common'
155
165
import mavlink_store_get from ' @/utils/mavlink'
156
166
167
+ import ParameterSwitch from ' ../common/ParameterSwitch.vue'
168
+
157
169
interface MotorTestTarget {
158
170
name: string
159
171
servo: number // target and servo differ in rover
160
172
target: number
173
+ direction: number
174
+ reverse_parameter? : Parameter
161
175
}
162
176
163
177
const rover_function_map = {
@@ -180,6 +194,7 @@ export default Vue.extend({
180
194
name: ' PwmSetup' ,
181
195
components: {
182
196
ParameterEditorDialog ,
197
+ ParameterSwitch ,
183
198
VehicleViewer ,
184
199
},
185
200
data() {
@@ -195,6 +210,9 @@ export default Vue.extend({
195
210
arming_timeout: undefined as number | undefined ,
196
211
has_focus: true ,
197
212
motors_zeroed: false ,
213
+ // These two change from firmware to firmware...
214
+ reverse_on_value: 1.0 ,
215
+ reverse_off_value: 0.0 ,
198
216
}
199
217
},
200
218
computed: {
@@ -221,11 +239,14 @@ export default Vue.extend({
221
239
).map ((parameter ) => {
222
240
const number = parseInt (/ \d + / g .exec (parameter .name )?.[0 ] ?? ' 0' , 10 )
223
241
const name = param_value_map .Submarine [parameter .name ] ?? ` Motor ${number } `
242
+ const direction_parameter = autopilot_data .parameterRegex (` MOT_${number }_DIRECTION ` )?.[0 ]
224
243
const target = number - 1
225
244
return {
226
245
name ,
227
246
servo: number ,
228
247
target ,
248
+ direction: direction_parameter .value ,
249
+ reverse_parameter: direction_parameter ,
229
250
}
230
251
})
231
252
},
@@ -235,6 +256,14 @@ export default Vue.extend({
235
256
}
236
257
return this .available_sub_motors
237
258
},
259
+ motor_direction(): {[key : number ]: number } {
260
+ const motorDict = {} as {[key : number ]: number }
261
+ const availableMotors = this .available_motors
262
+ for (const motor of availableMotors ) {
263
+ motorDict [motor .target ] = motor .direction
264
+ }
265
+ return motorDict
266
+ },
238
267
available_rover_motors(): MotorTestTarget [] {
239
268
return this .servo_function_parameters .filter (
240
269
(parameter ) => [
@@ -248,13 +277,25 @@ export default Vue.extend({
248
277
const name = printParam (parameter )
249
278
const servo = parseInt (/ \d + / g .exec (parameter .name )?.[0 ] ?? ' 0' , 10 )
250
279
const target = rover_function_map [parameter .value ] ?? 0
280
+ const reverse_parameter = autopilot_data .parameterRegex (` SERVO${servo }_REVERSED ` )?.[0 ]
251
281
return {
252
282
name ,
253
283
servo ,
254
284
target ,
285
+ direction: reverse_parameter .value ? - 1.0 : 1.0 ,
286
+ reverse_parameter ,
255
287
}
256
288
})
257
289
},
290
+ motor_target_with_reversion(): {[key : number ]: number } {
291
+ const targets = { ... this .motor_targets }
292
+ for (const motor_string of Object .keys (targets )) {
293
+ const motor = parseInt (motor_string , 10 )
294
+ const raw_value = targets [motor ] - 1500
295
+ targets [motor ] = 1500 + this .motor_direction [motor ] * raw_value
296
+ }
297
+ return targets
298
+ },
258
299
vehicle_id(): number {
259
300
return autopilot_data .system_id
260
301
},
@@ -327,13 +368,20 @@ export default Vue.extend({
327
368
// To reflect changed made from other sources like from GCSs
328
369
this .desired_armed_state = this .is_armed
329
370
},
371
+ is_rover() {
372
+ this .updateReversionValues ()
373
+ },
374
+ is_sub() {
375
+ this .updateReversionValues ()
376
+ },
330
377
},
331
378
mounted() {
332
379
this .motor_zeroer_interval = setInterval (this .zero_motors , 300 )
333
380
this .motor_writer_interval = setInterval (this .write_motors , 100 )
334
381
mavlink .setMessageRefreshRate ({ messageName: ' SERVO_OUTPUT_RAW' , refreshRate: 10 })
335
382
this .desired_armed_state = this .is_armed
336
383
this .installListeners ()
384
+ this .updateReversionValues ()
337
385
},
338
386
beforeDestroy() {
339
387
clearInterval (this .motor_zeroer_interval )
@@ -342,6 +390,16 @@ export default Vue.extend({
342
390
this .uninstallListeners ()
343
391
},
344
392
methods: {
393
+ updateReversionValues() {
394
+ if (this .is_rover ) {
395
+ this .reverse_on_value = 1.0
396
+ this .reverse_off_value = 0
397
+ return
398
+ }
399
+ // sub
400
+ this .reverse_on_value = - 1.0
401
+ this .reverse_off_value = 1.0
402
+ },
345
403
focusListener() {
346
404
this .has_focus = true
347
405
},
@@ -386,7 +444,7 @@ export default Vue.extend({
386
444
return
387
445
}
388
446
if (this .is_armed && this .desired_armed_state ) {
389
- for (const [motor, value] of Object .entries (this .motor_targets )) {
447
+ for (const [motor, value] of Object .entries (this .motor_target_with_reversion )) {
390
448
this .doMotorTest (parseInt (motor , 10 ), value )
391
449
}
392
450
}
0 commit comments