From e862291e57d5f66a4644769ede40de6df4c35104 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Wed, 18 Sep 2024 15:49:27 -0300 Subject: [PATCH] frontend: calibrations.ts: make it ts-friendly --- .../components/vehiclesetup/calibration.ts | 26 +++++++++++-------- 1 file changed, 15 insertions(+), 11 deletions(-) diff --git a/core/frontend/src/components/vehiclesetup/calibration.ts b/core/frontend/src/components/vehiclesetup/calibration.ts index 369b067c4f..9ee27a4fc6 100644 --- a/core/frontend/src/components/vehiclesetup/calibration.ts +++ b/core/frontend/src/components/vehiclesetup/calibration.ts @@ -57,6 +57,10 @@ class Calibrator { * @param {PreflightCalibration} type */ private static start(type: PreflightCalibration): void { + const getParamValue = (mapping: Partial>): number => { + return mapping[type] ?? 0; + }; + mavlink2rest.sendMessage({ header: { system_id: 255, @@ -65,30 +69,30 @@ class Calibrator { }, message: { type: MAVLinkType.COMMAND_LONG, - param1: { + param1: getParamValue({ [PreflightCalibration.GYROSCOPE]: 1, [PreflightCalibration.GYROSCOPE_TEMPERATURE]: 3, - }[type] || 0, + }), param2: type === PreflightCalibration.MAGNETOMETER ? 1 : 0, param3: type === PreflightCalibration.PRESSURE ? 1 : 0, - param4: { + param4: getParamValue({ [PreflightCalibration.RC]: 1, [PreflightCalibration.RC_TRIM]: 2, - }[type] || 0, - param5: { + }), + param5: getParamValue({ [PreflightCalibration.ACCELEROMETER]: 1, [PreflightCalibration.BOARD_LEVEL]: 2, [PreflightCalibration.ACCELEROMETER_TEMPERATURE]: 3, [PreflightCalibration.SIMPLE_ACCELEROMETER]: 4, - }[type] || 0, - param6: { + }), + param6: getParamValue({ [PreflightCalibration.COMPASS_MOTOR_INTERFERENCE]: 1, [PreflightCalibration.AIRPSEED]: 2, - }[type] || 0, - param7: { + }), + param7: getParamValue({ [PreflightCalibration.ESC]: 1, [PreflightCalibration.BAROMETER_TEMPERATURE]: 3, - }[type] || 0, + }), command: { type: MavCmd.MAV_CMD_PREFLIGHT_CALIBRATION, }, @@ -96,7 +100,7 @@ class Calibrator { target_component: 1, confirmation: 0, }, - }) + }); } /**