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
30 changes: 14 additions & 16 deletions src/assets/joystick-profiles.ts
Original file line number Diff line number Diff line change
@@ -1,11 +1,9 @@
import { MavType } from '@/libs/connection/m2r/messages/mavlink2rest-enum'
import { JoystickModel } from '@/libs/joystick/manager'
import { availableCockpitActions } from '@/libs/joystick/protocols/cockpit-actions'
import {
availableMavlinkManualControlButtonFunctions,
mavlinkManualControlAxes,
} from '@/libs/joystick/protocols/mavlink-manual-control'
import { availableMavlinkManualControlButtonFunctions } from '@/libs/joystick/protocols/mavlink-manual-control'
import { modifierKeyActions, otherAvailableActions } from '@/libs/joystick/protocols/other'
import { joystickInputAxes } from '@/libs/joystick/protocols/predefined-resources'
import { getVehicleModeAction } from '@/libs/vehicle/ardupilot/common'
import { RoverMode } from '@/libs/vehicle/ardupilot/types/modes'
import { Type as VehicleType } from '@/libs/vehicle/vehicle'
Expand Down Expand Up @@ -33,10 +31,10 @@ export const cockpitStandardToProtocols: JoystickProtocolActionsMapping[] = [
name: 'ROV functions mapping',
hash: defaultRovMappingHash,
axesCorrespondencies: {
[JoystickAxis.A0]: { action: mavlinkManualControlAxes.axis_y, min: -1000, max: +1000 },
[JoystickAxis.A1]: { action: mavlinkManualControlAxes.axis_x, min: +1000, max: -1000 },
[JoystickAxis.A2]: { action: mavlinkManualControlAxes.axis_r, min: -1000, max: +1000 },
[JoystickAxis.A3]: { action: mavlinkManualControlAxes.axis_z, min: +1000, max: 0 },
[JoystickAxis.A0]: { action: joystickInputAxes.axis_y, min: -1000, max: +1000 },
[JoystickAxis.A1]: { action: joystickInputAxes.axis_x, min: +1000, max: -1000 },
[JoystickAxis.A2]: { action: joystickInputAxes.axis_r, min: -1000, max: +1000 },
[JoystickAxis.A3]: { action: joystickInputAxes.axis_z, min: +1000, max: 0 },
},
buttonsCorrespondencies: {
[CockpitModifierKeyOption.regular]: {
Expand Down Expand Up @@ -85,10 +83,10 @@ export const cockpitStandardToProtocols: JoystickProtocolActionsMapping[] = [
name: 'Boat functions mapping',
hash: defaultBoatMappingHash,
axesCorrespondencies: {
[JoystickAxis.A0]: { action: mavlinkManualControlAxes.axis_y, min: -1000, max: +1000 },
[JoystickAxis.A1]: { action: mavlinkManualControlAxes.axis_x, min: +1000, max: -1000 },
[JoystickAxis.A2]: { action: mavlinkManualControlAxes.axis_r, min: -1000, max: +1000 },
[JoystickAxis.A3]: { action: mavlinkManualControlAxes.axis_z, min: +1000, max: -1000 },
[JoystickAxis.A0]: { action: joystickInputAxes.axis_y, min: -1000, max: +1000 },
[JoystickAxis.A1]: { action: joystickInputAxes.axis_x, min: +1000, max: -1000 },
[JoystickAxis.A2]: { action: joystickInputAxes.axis_r, min: -1000, max: +1000 },
[JoystickAxis.A3]: { action: joystickInputAxes.axis_z, min: +1000, max: -1000 },
},
buttonsCorrespondencies: {
[CockpitModifierKeyOption.regular]: {
Expand Down Expand Up @@ -137,10 +135,10 @@ export const cockpitStandardToProtocols: JoystickProtocolActionsMapping[] = [
name: 'MAV functions mapping',
hash: defaultMavMappingHash,
axesCorrespondencies: {
[JoystickAxis.A0]: { action: mavlinkManualControlAxes.axis_r, min: -1000, max: +1000 },
[JoystickAxis.A1]: { action: mavlinkManualControlAxes.axis_z, min: +1000, max: 0 },
[JoystickAxis.A2]: { action: mavlinkManualControlAxes.axis_y, min: -1000, max: +1000 },
[JoystickAxis.A3]: { action: mavlinkManualControlAxes.axis_x, min: +1000, max: -1000 },
[JoystickAxis.A0]: { action: joystickInputAxes.axis_r, min: -1000, max: +1000 },
[JoystickAxis.A1]: { action: joystickInputAxes.axis_z, min: +1000, max: 0 },
[JoystickAxis.A2]: { action: joystickInputAxes.axis_y, min: -1000, max: +1000 },
[JoystickAxis.A3]: { action: joystickInputAxes.axis_x, min: +1000, max: -1000 },
},
buttonsCorrespondencies: {
[CockpitModifierKeyOption.regular]: {
Expand Down
10 changes: 3 additions & 7 deletions src/libs/joystick/protocols.ts
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,13 @@ import { availableCockpitActions } from './protocols/cockpit-actions'
import { availableDataLakeActions } from './protocols/data-lake'
import {
availableMavlinkManualControlButtonFunctions,
mavlinkManualControlAxes,
migrateMavlinkManualControlAxes,
migrateMavlinkManualControlButtons,
} from './protocols/mavlink-manual-control'
import { modifierKeyActions, otherAvailableActions } from './protocols/other'

export const allAvailableAxes = (): ProtocolAction[] => {
return [
...Object.values(mavlinkManualControlAxes),
...Object.values(availableDataLakeActions()),
otherAvailableActions.no_function,
]
return [...Object.values(availableDataLakeActions()), otherAvailableActions.no_function]
}

export const allAvailableButtons = (): ProtocolAction[] => {
Expand All @@ -30,5 +26,5 @@ export const allAvailableButtons = (): ProtocolAction[] => {
export const performJoystickMappingMigrations = (
mappings: JoystickProtocolActionsMapping[]
): JoystickProtocolActionsMapping[] => {
return migrateMavlinkManualControlButtons(mappings)
return migrateMavlinkManualControlAxes(migrateMavlinkManualControlButtons(mappings))
}
55 changes: 38 additions & 17 deletions src/libs/joystick/protocols/mavlink-manual-control.ts
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,12 @@
import { capitalize } from 'vue'

import { useInteractionDialog } from '@/composables/interactionDialog'
import { getDataLakeVariableData } from '@/libs/actions/data-lake'
import { sendManualControl } from '@/libs/communication/mavlink'
import { modifierKeyActions, otherAvailableActions } from '@/libs/joystick/protocols/other'
import { round, scale } from '@/libs/utils'
import { round } from '@/libs/utils'
import type { ArduPilot } from '@/libs/vehicle/ardupilot/ardupilot'
import { type JoystickProtocolActionsMapping, type JoystickState, type ProtocolAction, CockpitModifierKeyOption, JoystickAxis, JoystickButton, JoystickProtocol } from '@/types/joystick'
import { type JoystickProtocolActionsMapping, type JoystickState, type ProtocolAction, CockpitModifierKeyOption, JoystickButton, JoystickProtocol } from '@/types/joystick'

/**
* Possible axes in the MAVLink `MANUAL_CONTROL` message protocol
Expand Down Expand Up @@ -500,21 +501,13 @@ export class MavlinkManualControlManager {
}
}

// Calculate axes values
const xCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_x.id)
const yCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_y.id)
const zCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_z.id)
const rCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_r.id)
const sCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_s.id)
const tCorrespondency = Object.entries(this.currentActionsMapping.axesCorrespondencies).find((entry) => entry[1].action.protocol === JoystickProtocol.MAVLinkManualControl && entry[1].action.id === mavlinkManualControlAxes.axis_t.id)

// Populate MAVLink Manual Control state of axes and buttons
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)
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)
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)
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)
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)
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)
// Read axis values from data lake output variables (scaling is handled by the data-lake protocol handler)
this.manualControlState.x = round(Number(getDataLakeVariableData('joystick/outputs/axis-x') ?? 0), 0)
this.manualControlState.y = round(Number(getDataLakeVariableData('joystick/outputs/axis-y') ?? 0), 0)
this.manualControlState.z = round(Number(getDataLakeVariableData('joystick/outputs/axis-z') ?? 0), 0)
this.manualControlState.r = round(Number(getDataLakeVariableData('joystick/outputs/axis-r') ?? 0), 0)
this.manualControlState.s = round(Number(getDataLakeVariableData('joystick/outputs/axis-s') ?? 0), 0)
this.manualControlState.t = round(Number(getDataLakeVariableData('joystick/outputs/axis-t') ?? 0), 0)
this.manualControlState.buttons = buttons_int
this.manualControlState.buttons2 = buttons2_int
}
Expand Down Expand Up @@ -703,3 +696,31 @@ const migrateServoSubButtonsToActuators = (mappings: JoystickProtocolActionsMapp
export const migrateMavlinkManualControlButtons = (mappings: JoystickProtocolActionsMapping[]): JoystickProtocolActionsMapping[] => {
return migrateServoSubButtonsToActuators(mappings)
}

const mavlinkAxisToDataLakeMap: Record<string, { id: string; name: string }> = {
[MAVLinkAxisFunction.X]: { id: 'joystick/inputs/axis-x', name: 'Axis X' },
[MAVLinkAxisFunction.Y]: { id: 'joystick/inputs/axis-y', name: 'Axis Y' },
[MAVLinkAxisFunction.Z]: { id: 'joystick/inputs/axis-z', name: 'Axis Z' },
[MAVLinkAxisFunction.R]: { id: 'joystick/inputs/axis-r', name: 'Axis R' },
[MAVLinkAxisFunction.S]: { id: 'joystick/inputs/axis-s', name: 'Axis S' },
[MAVLinkAxisFunction.T]: { id: 'joystick/inputs/axis-t', name: 'Axis T' },
}

export const migrateMavlinkManualControlAxes = (mappings: JoystickProtocolActionsMapping[]): JoystickProtocolActionsMapping[] => {
const migratedMappings: JoystickProtocolActionsMapping[] = JSON.parse(JSON.stringify(mappings))
migratedMappings.forEach((mapping) => {
Object.entries(mapping.axesCorrespondencies).forEach(([axisIndex, axisConfig]) => {
if (axisConfig.action.protocol === JoystickProtocol.MAVLinkManualControl) {
const replacement = mavlinkAxisToDataLakeMap[axisConfig.action.id]
if (replacement) {
mapping.axesCorrespondencies[axisIndex as unknown as number].action = {
protocol: JoystickProtocol.DataLakeVariable,
id: replacement.id,
name: replacement.name,
}
}
}
})
})
return migratedMappings
}
61 changes: 61 additions & 0 deletions src/libs/joystick/protocols/predefined-resources.ts
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,42 @@ import { MavCmd, MAVLinkType } from '@/libs/connection/m2r/messages/mavlink2rest
import { getUnindentedString } from '@/libs/utils'
import { customActionTypes } from '@/types/cockpit-actions'

import { DataLakeVariableAction } from './data-lake'

export let mavlinkCameraZoomActionId: string | undefined = undefined
export let mavlinkCameraFocusActionId: string | undefined = undefined

const joystickAxisConfig = [
{ key: 'axis_x' },
{ key: 'axis_y' },
{ key: 'axis_z' },
{ key: 'axis_r' },
{ key: 'axis_s' },
{ key: 'axis_t' },
] as const

const axisInputId = (key: string): string => `joystick/inputs/${key.replace('_', '-')}`
const axisName = (key: string): string =>
key
.split('_')
.map((w) => w.charAt(0).toUpperCase() + w.slice(1))
.join(' ')

/**
* Pre-built data lake variable actions for joystick axis inputs, used in joystick profile mappings
*/
export const joystickInputAxes: Record<(typeof joystickAxisConfig)[number]['key'], DataLakeVariableAction> =
Object.fromEntries(
joystickAxisConfig.map((axis) => [
axis.key,
new DataLakeVariableAction({
id: axisInputId(axis.key),
name: axisName(axis.key),
type: 'number' as DataLakeVariableType,
}),
])
) as Record<(typeof joystickAxisConfig)[number]['key'], DataLakeVariableAction>

export const setupMavlinkCameraResources = (): void => {
const commonVariableConfig = { type: 'number' as DataLakeVariableType, allowUserToChangeValue: true }
// Initialize camera zoom variables
Expand Down Expand Up @@ -126,6 +159,34 @@ export const setupMavlinkCameraResources = (): void => {
}
}

export const setupJoystickAxesResources = (): void => {
const commonVariableConfig = { type: 'number' as DataLakeVariableType, allowUserToChangeValue: true }

for (const axis of joystickAxisConfig) {
const id = axisInputId(axis.key)
const name = axisName(axis.key)
const outputId = id.replace('/inputs/', '/outputs/')

createDataLakeVariable({ id, name, ...commonVariableConfig }, 0)

try {
const existing = getAllTransformingFunctions().find((f) => f.id === outputId)
if (!existing) {
createTransformingFunction(
outputId,
`${name} Output`,
'number',
`{{${id}}}`,
`Output value for MANUAL_CONTROL ${name}.`
)
}
} catch (error) {
console.error(`Error creating transforming function for ${name}:`, error)
}
}
}

export const setupPredefinedLakeAndActionResources = (): void => {
setupMavlinkCameraResources()
setupJoystickAxesResources()
}
Loading