|
5 | 5 | import { capitalize } from 'vue' |
6 | 6 |
|
7 | 7 | import { useInteractionDialog } from '@/composables/interactionDialog' |
| 8 | +import { getDataLakeVariableData } from '@/libs/actions/data-lake' |
8 | 9 | import { sendManualControl } from '@/libs/communication/mavlink' |
9 | 10 | import { modifierKeyActions, otherAvailableActions } from '@/libs/joystick/protocols/other' |
10 | | -import { round, scale } from '@/libs/utils' |
| 11 | +import { round } from '@/libs/utils' |
11 | 12 | import type { ArduPilot } from '@/libs/vehicle/ardupilot/ardupilot' |
12 | | -import { type JoystickProtocolActionsMapping, type JoystickState, type ProtocolAction, CockpitModifierKeyOption, JoystickAxis, JoystickButton, JoystickProtocol } from '@/types/joystick' |
| 13 | +import { type JoystickProtocolActionsMapping, type JoystickState, type ProtocolAction, CockpitModifierKeyOption, JoystickButton, JoystickProtocol } from '@/types/joystick' |
13 | 14 |
|
14 | 15 | /** |
15 | 16 | * Possible axes in the MAVLink `MANUAL_CONTROL` message protocol |
@@ -500,21 +501,13 @@ export class MavlinkManualControlManager { |
500 | 501 | } |
501 | 502 | } |
502 | 503 |
|
503 | | - // Calculate axes values |
504 | | - const xCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_x.id) |
505 | | - const yCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_y.id) |
506 | | - const zCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_z.id) |
507 | | - const rCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_r.id) |
508 | | - const sCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_s.id) |
509 | | - const tCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_t.id) |
510 | | - |
511 | | - // Populate MAVLink Manual Control state of axes and buttons |
512 | | - this.manualControlState.x = xCorrespondency === undefined ? 0 : round(scale(this.joystickState.axes[xCorrespondency[0] as unknown as JoystickAxis] ?? 0, -1, 1, xCorrespondency[1].min, xCorrespondency[1].max), 0) |
513 | | - this.manualControlState.y = yCorrespondency === undefined ? 0 : round(scale(this.joystickState.axes[yCorrespondency[0] as unknown as JoystickAxis] ?? 0, -1, 1, yCorrespondency[1].min, yCorrespondency[1].max), 0) |
514 | | - this.manualControlState.z = zCorrespondency === undefined ? 0 : round(scale(this.joystickState.axes[zCorrespondency[0] as unknown as JoystickAxis] ?? 0, -1, 1, zCorrespondency[1].min, zCorrespondency[1].max), 0) |
515 | | - this.manualControlState.r = rCorrespondency === undefined ? 0 : round(scale(this.joystickState.axes[rCorrespondency[0] as unknown as JoystickAxis] ?? 0, -1, 1, rCorrespondency[1].min, rCorrespondency[1].max), 0) |
516 | | - this.manualControlState.s = sCorrespondency === undefined ? 0 : round(scale(this.joystickState.axes[sCorrespondency[0] as unknown as JoystickAxis] ?? 0, -1, 1, sCorrespondency[1].min, sCorrespondency[1].max), 0) |
517 | | - this.manualControlState.t = tCorrespondency === undefined ? 0 : round(scale(this.joystickState.axes[tCorrespondency[0] as unknown as JoystickAxis] ?? 0, -1, 1, tCorrespondency[1].min, tCorrespondency[1].max), 0) |
| 504 | + // Read axis values from data lake output variables (scaling is handled by the data-lake protocol handler) |
| 505 | + this.manualControlState.x = round(Number(getDataLakeVariableData('joystick/outputs/axis-x') ?? 0), 0) |
| 506 | + this.manualControlState.y = round(Number(getDataLakeVariableData('joystick/outputs/axis-y') ?? 0), 0) |
| 507 | + this.manualControlState.z = round(Number(getDataLakeVariableData('joystick/outputs/axis-z') ?? 0), 0) |
| 508 | + this.manualControlState.r = round(Number(getDataLakeVariableData('joystick/outputs/axis-r') ?? 0), 0) |
| 509 | + this.manualControlState.s = round(Number(getDataLakeVariableData('joystick/outputs/axis-s') ?? 0), 0) |
| 510 | + this.manualControlState.t = round(Number(getDataLakeVariableData('joystick/outputs/axis-t') ?? 0), 0) |
518 | 511 | this.manualControlState.buttons = buttons_int |
519 | 512 | this.manualControlState.buttons2 = buttons2_int |
520 | 513 | } |
@@ -703,3 +696,31 @@ const migrateServoSubButtonsToActuators = (mappings: JoystickProtocolActionsMapp |
703 | 696 | export const migrateMavlinkManualControlButtons = (mappings: JoystickProtocolActionsMapping[]): JoystickProtocolActionsMapping[] => { |
704 | 697 | return migrateServoSubButtonsToActuators(mappings) |
705 | 698 | } |
| 699 | + |
| 700 | +const mavlinkAxisToDataLakeMap: Record<string, { id: string; name: string }> = { |
| 701 | + [MAVLinkAxisFunction.X]: { id: 'joystick/inputs/axis-x', name: 'Axis X' }, |
| 702 | + [MAVLinkAxisFunction.Y]: { id: 'joystick/inputs/axis-y', name: 'Axis Y' }, |
| 703 | + [MAVLinkAxisFunction.Z]: { id: 'joystick/inputs/axis-z', name: 'Axis Z' }, |
| 704 | + [MAVLinkAxisFunction.R]: { id: 'joystick/inputs/axis-r', name: 'Axis R' }, |
| 705 | + [MAVLinkAxisFunction.S]: { id: 'joystick/inputs/axis-s', name: 'Axis S' }, |
| 706 | + [MAVLinkAxisFunction.T]: { id: 'joystick/inputs/axis-t', name: 'Axis T' }, |
| 707 | +} |
| 708 | + |
| 709 | +export const migrateMavlinkManualControlAxes = (mappings: JoystickProtocolActionsMapping[]): JoystickProtocolActionsMapping[] => { |
| 710 | + const migratedMappings: JoystickProtocolActionsMapping[] = JSON.parse(JSON.stringify(mappings)) |
| 711 | + migratedMappings.forEach((mapping) => { |
| 712 | + Object.entries(mapping.axesCorrespondencies).forEach(([axisIndex, axisConfig]) => { |
| 713 | + if (axisConfig.action.protocol === JoystickProtocol.MAVLinkManualControl) { |
| 714 | + const replacement = mavlinkAxisToDataLakeMap[axisConfig.action.id] |
| 715 | + if (replacement) { |
| 716 | + mapping.axesCorrespondencies[axisIndex as unknown as number].action = { |
| 717 | + protocol: JoystickProtocol.DataLakeVariable, |
| 718 | + id: replacement.id, |
| 719 | + name: replacement.name, |
| 720 | + } |
| 721 | + } |
| 722 | + } |
| 723 | + }) |
| 724 | + }) |
| 725 | + return migratedMappings |
| 726 | +} |
0 commit comments