Skip to content

Commit bddd846

Browse files
Williangalvanipatrickelectric
authored andcommitted
Frontend: PwmSetup: fix motor test so it displays remapped ouputs on the correct motor row
1 parent 402cba9 commit bddd846

File tree

1 file changed

+14
-7
lines changed

1 file changed

+14
-7
lines changed

core/frontend/src/components/vehiclesetup/PwmSetup.vue

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,9 @@
5555
>
5656
<td width="20%">
5757
{{ motor.name }}
58+
<span v-if="motor.servo !== motor.motor">
59+
(Output {{ motor.servo }})
60+
</span>
5861
</td>
5962
<td width="10%">
6063
<parameterSwitch
@@ -175,6 +178,7 @@ import ParameterSwitch from '../common/ParameterSwitch.vue'
175178
176179
interface MotorTestTarget {
177180
name: string
181+
motor: number
178182
servo: number // target and servo differ in rover
179183
target: number
180184
direction: number
@@ -244,18 +248,20 @@ export default Vue.extend({
244248
return this.servo_function_parameters.filter(
245249
(parameter) => parameter.value >= SERVO_FUNCTION.MOTOR1 && parameter.value <= SERVO_FUNCTION.MOTOR8,
246250
).map((parameter) => {
247-
const number = parseInt(/\d+/g.exec(parameter.name)?.[0] ?? '0', 10)
248-
const name = param_value_map.Submarine[parameter.name] ?? `Motor ${number}`
249-
const direction_parameter = autopilot_data.parameterRegex(`MOT_${number}_DIRECTION`)?.[0]
250-
const target = number - 1
251+
const servo_number = parseInt(/\d+/g.exec(parameter.name)?.[0] ?? '0', 10)
252+
const motor_number = parseInt(/\d+/g.exec(printParam(parameter))?.[0] ?? '0', 10)
253+
const name = param_value_map.Submarine[parameter.name] ?? `Motor ${motor_number}`
254+
const direction_parameter = autopilot_data.parameterRegex(`MOT_${motor_number}_DIRECTION`)?.[0]
255+
const target = motor_number - 1
251256
return {
252257
name,
253-
servo: number,
258+
servo: servo_number,
259+
motor: motor_number,
254260
target,
255261
direction: direction_parameter.value,
256262
reverse_parameter: direction_parameter,
257263
}
258-
})
264+
}).sort((a, b) => a.motor - b.motor)
259265
},
260266
available_motors(): MotorTestTarget[] {
261267
if (this.is_rover) {
@@ -288,6 +294,7 @@ export default Vue.extend({
288294
return {
289295
name,
290296
servo,
297+
motor: servo,
291298
target,
292299
direction: reverse_parameter.value ? -1.0 : 1.0,
293300
reverse_parameter,
@@ -401,7 +408,7 @@ export default Vue.extend({
401408
if (this.is_rover) {
402409
this.highlight = [this.stringToUserFriendlyText(printParam(this.getParam(`SERVO${motor.servo}_FUNCTION`)))]
403410
} else {
404-
this.highlight = [`Motor${motor.servo}`]
411+
this.highlight = [`Motor${motor.motor}`]
405412
}
406413
},
407414
convert_servo_name(name: string) {

0 commit comments

Comments
 (0)