Skip to content

Commit a4bd033

Browse files
authored
Start using node-mavlink bindings (#1158)
* Start using node-mavlink bindings * Address copilot review comments
1 parent 3dad249 commit a4bd033

6 files changed

Lines changed: 59 additions & 146 deletions

File tree

gcs/package.json

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,7 @@
5757
"mapbox-gl": "^3.0.1",
5858
"maplibre-gl": "^3.6.2",
5959
"moment": "^2.29.4",
60+
"node-mavlink": "^2.3.0",
6061
"octokit": "^4.0.2",
6162
"playwright": "^1.56.0",
6263
"prettier": "3.2.5",

gcs/src/components/dashboard/tabsSectionTabs/missionTabsSection.jsx

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -8,10 +8,8 @@
88
import { Button, Tabs } from "@mantine/core"
99

1010
// Mavlink
11-
import {
12-
getFlightModeMap,
13-
MISSION_STATES,
14-
} from "../../../helpers/mavlinkConstants"
11+
import { getFlightModeMap } from "../../../helpers/mavlinkConstants"
12+
import { mavlinkDef } from "../../../helpers/mavlinkDef"
1513

1614
import { useMemo } from "react"
1715
import { useDispatch, useSelector } from "react-redux"
@@ -63,7 +61,7 @@ const MissionInfo = () => {
6361
<div className="text-lg">
6462
<p>
6563
<span className="font-bold"> Mission State:</span>{" "}
66-
{MISSION_STATES[currentMission.mission_state]}
64+
{mavlinkDef.MissionState[currentMission.mission_state]}
6765
</p>
6866
<p>
6967
<span className="font-bold"> Waypoint: </span> {currentMission.seq}/
@@ -90,7 +88,7 @@ const AutoStartRestartMission = ({ aircraftType, currentFlightModeNumber }) => {
9088
const autoFlightModeNumber = useMemo(() => {
9189
const flightModeMap = getFlightModeMap(aircraftType)
9290
const key = Object.keys(flightModeMap).find(
93-
(key) => flightModeMap[key] === "Auto",
91+
(key) => flightModeMap[key] === "AUTO",
9492
)
9593
return key !== undefined ? parseInt(key) : null
9694
}, [aircraftType])

gcs/src/dashboard.jsx

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,6 @@ import { selectCurrentMission } from "./redux/slices/missionSlice"
4545
import { useSettings } from "./helpers/settings"
4646

4747
// Helper javascript files
48-
import { GPS_FIX_TYPES } from "./helpers/mavlinkConstants"
4948

5049
// Import components
5150
import ForceArmModal from "./components/dashboard/ForceArmModal"
@@ -71,6 +70,7 @@ import flightModeChangedSound from "./assets/sounds/flightmodechanged.mp3"
7170
import lowBatterySound from "./assets/sounds/lowbattery.mp3"
7271
import waypointReachedSound from "./assets/sounds/waypointreached.mp3"
7372
import { formatDurationSecondsToMMSS } from "./helpers/dataFormatters"
73+
import { GPS_FIX_TYPES } from "./helpers/mavlinkConstants.js"
7474

7575
export default function Dashboard() {
7676
const dispatch = useDispatch()
@@ -92,8 +92,6 @@ export default function Dashboard() {
9292
const gps2 = useSelector(selectGPS2RawInt)
9393
const hasSecondaryGps = useSelector(selectHasSecondaryGps)
9494

95-
const secondaryGpsFixLabel = GPS_FIX_TYPES[gps2.fixType]
96-
9795
// Telemetry panel sizing
9896
const [telemetryPanelSize, setTelemetryPanelSize] = useLocalStorage({
9997
key: "telemetryPanelSize",
@@ -269,7 +267,7 @@ export default function Dashboard() {
269267
{hasSecondaryGps && (
270268
<StatusSection
271269
icon={<IconRadar />}
272-
value={secondaryGpsFixLabel}
270+
value={GPS_FIX_TYPES[gps2.fixType]}
273271
tooltip="GPS2 fix type"
274272
/>
275273
)}

gcs/src/helpers/mavlinkConstants.js

Lines changed: 27 additions & 117 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,12 @@
1+
import { mavlinkDef } from "./mavlinkDef"
2+
3+
function enumToNumericLabelEntries(enumObj) {
4+
return Object.entries(enumObj)
5+
.filter(([key]) => !Number.isNaN(Number(key))) // keep "0","1",...
6+
.map(([key, name]) => [Number(key), name])
7+
.sort((a, b) => a[0] - b[0])
8+
}
9+
110
export const MAV_STATE = [
211
"UNINIT",
312
"BOOT",
@@ -10,71 +19,13 @@ export const MAV_STATE = [
1019
"FLIGHT TERMINATION",
1120
]
1221

13-
export const MAV_SEVERITY = [
14-
"EMERGENCY",
15-
"ALERT",
16-
"CRITICAL",
17-
"ERROR",
18-
"WARNING",
19-
"NOTICE",
20-
"INFO",
21-
"DEBUG",
22-
]
22+
export const PLANE_MODES_FLIGHT_MODE_MAP = Object.fromEntries(
23+
enumToNumericLabelEntries(mavlinkDef.PlaneMode),
24+
)
2325

24-
export const PLANE_MODES_FLIGHT_MODE_MAP = {
25-
0: "Manual",
26-
1: "CIRCLE",
27-
2: "STABILIZE",
28-
3: "TRAINING",
29-
4: "ACRO",
30-
5: "FBWA",
31-
6: "FBWB",
32-
7: "CRUISE",
33-
8: "AUTOTUNE",
34-
10: "Auto",
35-
11: "RTL",
36-
12: "Loiter",
37-
13: "TAKEOFF",
38-
14: "AVOID_ADSB",
39-
15: "Guided",
40-
17: "QSTABILIZE",
41-
18: "QHOVER",
42-
19: "QLOITER",
43-
20: "QLAND",
44-
21: "QRTL",
45-
22: "QAUTOTUNE",
46-
23: "QACRO",
47-
24: "THERMAL",
48-
25: "Loiter to QLand",
49-
}
50-
51-
export const COPTER_MODES_FLIGHT_MODE_MAP = {
52-
0: "Stabilize",
53-
1: "Acro",
54-
2: "AltHold",
55-
3: "Auto",
56-
4: "Guided",
57-
5: "Loiter",
58-
6: "RTL",
59-
7: "Circle",
60-
9: "Land",
61-
11: "Drift",
62-
13: "Sport",
63-
14: "Flip",
64-
15: "AutoTune",
65-
16: "PosHold",
66-
17: "Brake",
67-
18: "Throw",
68-
19: "Avoid_ADSB",
69-
20: "Guided_NoGPS",
70-
21: "Smart_RTL",
71-
22: "FlowHold",
72-
23: "Follow",
73-
24: "ZigZag",
74-
25: "SystemID",
75-
26: "Heli_Autorotate",
76-
27: "UNKNOWN",
77-
}
26+
export const COPTER_MODES_FLIGHT_MODE_MAP = Object.fromEntries(
27+
enumToNumericLabelEntries(mavlinkDef.CopterMode),
28+
)
7829

7930
export function getFlightModeMap(aircraftType) {
8031
if (aircraftType === "Plane") {
@@ -85,19 +36,15 @@ export function getFlightModeMap(aircraftType) {
8536
return {}
8637
}
8738

88-
export const GPS_FIX_TYPES = [
89-
"NO GPS",
90-
"NO FIX",
91-
"2D FIX",
92-
"3D FIX",
93-
"DGPS",
94-
"RTK FLOAT",
95-
"RTK FIXED",
96-
"STATIC",
97-
"PPP",
98-
]
39+
function formatGpsFixLabel(name) {
40+
return name
41+
.replace(/^GPS_FIX_TYPE_/, "") // remove prefix
42+
.replace(/_/g, " ") // underscores -> spaces
43+
}
9944

100-
export const MAV_AUTOPILOT_INVALID = 8
45+
export const GPS_FIX_TYPES = enumToNumericLabelEntries(
46+
mavlinkDef.GpsFixType,
47+
).map(([, name]) => formatGpsFixLabel(name))
10148

10249
export const FRAME_TYPE_MAP_QUAD = {
10350
0: {
@@ -314,15 +261,6 @@ export const MOTOR_LETTER_LABELS = [
314261
"L",
315262
]
316263

317-
export const MISSION_STATES = {
318-
0: "UNKNOWN",
319-
1: "NO MISSION",
320-
2: "NOT STARTED",
321-
3: "ACTIVE",
322-
4: "PAUSED",
323-
5: "COMPLETED",
324-
}
325-
326264
// List of mission item commands to not display on the map
327265
// due to lack of GPS coordinates
328266
export const FILTER_MISSION_ITEM_COMMANDS_LIST = {
@@ -460,24 +398,7 @@ export const FENCE_ITEM_COMMANDS_LIST = {
460398
5004: "MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION",
461399
}
462400

463-
export const MAV_FRAME_LIST = {
464-
0: "MAV_FRAME_GLOBAL",
465-
1: "MAV_FRAME_LOCAL_NED",
466-
2: "MAV_FRAME_MISSION",
467-
3: "MAV_FRAME_GLOBAL_RELATIVE_ALT",
468-
4: "MAV_FRAME_LOCAL_ENU",
469-
5: "MAV_FRAME_GLOBAL_INT",
470-
6: "MAV_FRAME_GLOBAL_RELATIVE_ALT_INT",
471-
7: "MAV_FRAME_LOCAL_OFFSET_NED",
472-
8: "MAV_FRAME_BODY_NED",
473-
9: "MAV_FRAME_BODY_OFFSET_NED",
474-
10: "MAV_FRAME_GLOBAL_TERRAIN_ALT",
475-
11: "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT",
476-
12: "MAV_FRAME_BODY_FRD",
477-
21: "MAV_FRAME_LOCAL_FRD",
478-
22: "MAV_FRAME_LOCAL_FLU",
479-
23: "MAV_FRAME_ENUM_END",
480-
}
401+
export const MAV_FRAME_LIST = mavlinkDef.MavFrame
481402

482403
function getPositionFrameValue(frameName) {
483404
return Object.keys(MAV_FRAME_LIST).find(
@@ -500,20 +421,9 @@ function getFrameDropdownData() {
500421

501422
export const MAV_FRAME_DROPDOWN_DATA = getFrameDropdownData()
502423

503-
export const EKF_STATUS_FLAGS = {
504-
1: "EKF_ATTITUDE",
505-
2: "EKF_VELOCITY_HORIZ",
506-
4: "EKF_VELOCITY_VERT",
507-
8: "EKF_POS_HORIZ_REL",
508-
16: "EKF_POS_HORIZ_ABS",
509-
32: "EKF_POS_VERT_ABS",
510-
64: "EKF_POS_VERT_AGL",
511-
128: "EKF_CONST_POS_MODE",
512-
256: "EKF_PRED_POS_HORIZ_REL",
513-
512: "EKF_PRED_POS_HORIZ_ABS",
514-
1024: "EKF_UNINITIALIZED",
515-
32768: "EKF_GPS_GLITCHING",
516-
}
424+
export const EKF_STATUS_FLAGS = Object.fromEntries(
425+
enumToNumericLabelEntries(mavlinkDef.EkfStatusFlags),
426+
)
517427

518428
export function getActiveEKFFlags(statusValue) {
519429
const activeFlags = []

gcs/src/helpers/mavlinkDef.js

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
import * as ardupilotmega from "mavlink-mappings/dist/lib/ardupilotmega"
2+
import * as common from "mavlink-mappings/dist/lib/common"
3+
import * as minimal from "mavlink-mappings/dist/lib/minimal"
4+
import * as standard from "mavlink-mappings/dist/lib/standard"
5+
import * as uavionix from "mavlink-mappings/dist/lib/uavionix"
6+
7+
export const mavlinkDef = {
8+
...minimal,
9+
...common,
10+
...standard,
11+
...ardupilotmega,
12+
...uavionix,
13+
}

gcs/src/redux/slices/droneInfoSlice.js

Lines changed: 12 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,7 @@ import {
77
getFlightModeMap,
88
MAV_STATE,
99
} from "../../helpers/mavlinkConstants"
10-
11-
const MAV_SYS_STATUS_PREARM_CHECK = 268435456
10+
import { mavlinkDef } from "../../helpers/mavlinkDef"
1211

1312
// TODO: Make this configurable in the future?
1413
const GPS_TRACK_MAX_LENGTH = 300
@@ -136,14 +135,14 @@ const droneInfoSlice = createSlice({
136135
},
137136
setHeartbeatData: (state, action) => {
138137
if (
139-
action.payload.base_mode & 128 &&
140-
!(state.heartbeatData.baseMode & 128)
138+
action.payload.base_mode & mavlinkDef.MavModeFlag["SAFETY_ARMED"] &&
139+
!(state.heartbeatData.baseMode & mavlinkDef.MavModeFlag["SAFETY_ARMED"])
141140
) {
142141
state.isArmed = true
143142
state.notificationSound = "armed"
144143
} else if (
145-
!(action.payload.base_mode & 128) &&
146-
state.heartbeatData.baseMode & 128
144+
!(action.payload.base_mode & mavlinkDef.MavModeFlag["SAFETY_ARMED"]) &&
145+
state.heartbeatData.baseMode & mavlinkDef.MavModeFlag["SAFETY_ARMED"]
147146
) {
148147
state.isArmed = false
149148
state.isFlying = false
@@ -213,13 +212,6 @@ const droneInfoSlice = createSlice({
213212
: [],
214213
},
215214
}
216-
217-
console.log("ESC REDUX", {
218-
timestamp: action.payload.timestamp,
219-
rpm: action.payload.rpm,
220-
current: action.payload.current,
221-
temperature: action.payload.temperature,
222-
})
223215
},
224216
setTelemetryData: (state, action) => {
225217
state.telemetryData = {
@@ -344,16 +336,16 @@ const droneInfoSlice = createSlice({
344336
// Check EKF flags to handle critical errors
345337
// https://github.com/ArduPilot/MissionPlanner/blob/4d441bd4b1dbc08adce4d8b26e078e93760da3a7/ExtLibs/ArduPilot/CurrentState.cs#L2674-L2736
346338
const activeFlags = getActiveEKFFlags(state.ekfStatusReportData.flags)
347-
if (!activeFlags.includes("EKF_ATTITUDE")) {
339+
if (!activeFlags.includes("ATTITUDE")) {
348340
// If we have no attitude solution
349341
state.ekfCalculatedStatus = 1
350-
} else if (!activeFlags.includes("EKF_VELOCITY_HORIZ")) {
342+
} else if (!activeFlags.includes("VELOCITY_HORIZ")) {
351343
// If we have GPS but no horizontal velocity solution
352344
const gpsStatus = state.gpsRawIntData.fixType
353345
if (gpsStatus > 0) {
354346
state.ekfCalculatedStatus = 1
355347
}
356-
} else if (activeFlags.includes("EKF_UNINITIALIZED")) {
348+
} else if (activeFlags.includes("UNINITIALIZED")) {
357349
// EKF not initialized at all
358350
state.ekfCalculatedStatus = 1
359351
}
@@ -396,10 +388,12 @@ const droneInfoSlice = createSlice({
396388
selectSystemStatus: (state) => MAV_STATE[state.heartbeatData.systemStatus],
397389
selectReadyToArm: (state) => {
398390
const isEnabled = !!(
399-
state.onboardControlSensorsEnabled & MAV_SYS_STATUS_PREARM_CHECK
391+
state.onboardControlSensorsEnabled &
392+
mavlinkDef.MavSysStatusSensor.PREARM_CHECK
400393
)
401394
const isHealthy = !!(
402-
state.onboardControlSensorsHealth & MAV_SYS_STATUS_PREARM_CHECK
395+
state.onboardControlSensorsHealth &
396+
mavlinkDef.MavSysStatusSensor.PREARM_CHECK
403397
)
404398

405399
// If pre-arm check is enabled, it must also be healthy
@@ -546,7 +540,6 @@ export const selectAircraftTypeString = createSelector(
546540
export const selectFlightModeString = createSelector(
547541
[droneInfoSlice.selectors.selectFlightMode, selectAircraftTypeString],
548542
(flightMode, aircraftType) => {
549-
//TODO: aircraftType should be in local storage apparently (for some reason?)
550543
const flightModeMap = getFlightModeMap(aircraftType)
551544
return flightModeMap[flightMode] || "UNKNOWN"
552545
},

0 commit comments

Comments
 (0)