Skip to content

Commit

Permalink
Add support for the s and t axes in the MAVLink MANUAL_CONTROL
Browse files Browse the repository at this point in the history
…protocol
  • Loading branch information
rafaellehmkuhl committed Nov 29, 2023
1 parent dda0192 commit 3b9bfb9
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 0 deletions.
10 changes: 10 additions & 0 deletions src/libs/joystick/protocols.ts
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@ export class MavlinkControllerState extends ProtocolControllerState {
y: number
z: number
r: number
s: number
t: number
buttons: number
buttons2: number
target: number
Expand Down Expand Up @@ -74,18 +76,24 @@ export class MavlinkControllerState extends ProtocolControllerState {
const yIndex = mapping.axesCorrespondencies.findIndex((v) => isMavlinkInput(v) && v.value === MAVLinkAxis.Y)
const zIndex = mapping.axesCorrespondencies.findIndex((v) => isMavlinkInput(v) && v.value === MAVLinkAxis.Z)
const rIndex = mapping.axesCorrespondencies.findIndex((v) => isMavlinkInput(v) && v.value === MAVLinkAxis.R)
const sIndex = mapping.axesCorrespondencies.findIndex((v) => isMavlinkInput(v) && v.value === MAVLinkAxis.S)
const tIndex = mapping.axesCorrespondencies.findIndex((v) => isMavlinkInput(v) && v.value === MAVLinkAxis.T)

const absLimits = mavlinkAxesLimits

const xLimits = [mapping.axesMins[xIndex] ?? absLimits[0], mapping.axesMaxs[xIndex] ?? absLimits[1]]
const yLimits = [mapping.axesMins[yIndex] ?? absLimits[0], mapping.axesMaxs[yIndex] ?? absLimits[1]]
const zLimits = [mapping.axesMins[zIndex] ?? absLimits[0], mapping.axesMaxs[zIndex] ?? absLimits[1]]
const rLimits = [mapping.axesMins[rIndex] ?? absLimits[0], mapping.axesMaxs[rIndex] ?? absLimits[1]]
const sLimits = [mapping.axesMins[sIndex] ?? absLimits[0], mapping.axesMaxs[sIndex] ?? absLimits[1]]
const tLimits = [mapping.axesMins[tIndex] ?? absLimits[0], mapping.axesMaxs[tIndex] ?? absLimits[1]]

this.x = xIndex === undefined ? 0 : round(scale(joystickState.axes[xIndex] ?? 0, -1, 1, xLimits[0], xLimits[1]), 0)
this.y = yIndex === undefined ? 0 : round(scale(joystickState.axes[yIndex] ?? 0, -1, 1, yLimits[0], yLimits[1]), 0)
this.z = zIndex === undefined ? 0 : round(scale(joystickState.axes[zIndex] ?? 0, -1, 1, zLimits[0], zLimits[1]), 0)
this.r = rIndex === undefined ? 0 : round(scale(joystickState.axes[rIndex] ?? 0, -1, 1, rLimits[0], rLimits[1]), 0)
this.s = sIndex === undefined ? 0 : round(scale(joystickState.axes[sIndex] ?? 0, -1, 1, sLimits[0], sLimits[1]), 0)
this.t = tIndex === undefined ? 0 : round(scale(joystickState.axes[tIndex] ?? 0, -1, 1, tLimits[0], tLimits[1]), 0)

this.buttons = buttons_int
this.buttons2 = buttons2_int
Expand Down Expand Up @@ -163,6 +171,8 @@ export enum MAVLinkAxis {
Y = 'y',
Z = 'z',
R = 'r',
S = 's',
T = 't',
}
const mavlinkAvailableAxes = Object.values(MAVLinkAxis)
export const mavlinkAvailableButtons = sequentialArray(32)
Expand Down
2 changes: 2 additions & 0 deletions src/libs/vehicle/ardupilot/ardupilot.ts
Original file line number Diff line number Diff line change
Expand Up @@ -503,6 +503,8 @@ export abstract class ArduPilotVehicle<Modes> extends Vehicle.AbstractVehicle<Mo
y: state.y,
z: state.z,
r: state.r,
s: state.s,
t: state.t,
buttons: state.buttons,
buttons2: state.buttons2,
target: 1,
Expand Down

0 comments on commit 3b9bfb9

Please sign in to comment.