mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-26 17:55:24 +03:00
Add support for using MSP build options (#3780)
* Add buildOptions from MSP * Fixup semver
This commit is contained in:
parent
322a198165
commit
939b88d897
5 changed files with 129 additions and 20 deletions
|
@ -7,6 +7,7 @@ export const API_VERSION_1_43 = '1.43.0';
|
||||||
export const API_VERSION_1_44 = '1.44.0';
|
export const API_VERSION_1_44 = '1.44.0';
|
||||||
export const API_VERSION_1_45 = '1.45.0';
|
export const API_VERSION_1_45 = '1.45.0';
|
||||||
export const API_VERSION_1_46 = '1.46.0';
|
export const API_VERSION_1_46 = '1.46.0';
|
||||||
|
export const API_VERSION_1_47 = '1.47.0';
|
||||||
|
|
||||||
const CONFIGURATOR = {
|
const CONFIGURATOR = {
|
||||||
// all versions are specified and compared using semantic versioning http://semver.org/
|
// all versions are specified and compared using semantic versioning http://semver.org/
|
||||||
|
|
69
src/js/fc.js
69
src/js/fc.js
|
@ -10,6 +10,7 @@ const INITIAL_CONFIG = {
|
||||||
buildInfo: '',
|
buildInfo: '',
|
||||||
buildKey: '',
|
buildKey: '',
|
||||||
buildOptions: [],
|
buildOptions: [],
|
||||||
|
gitRevision: '',
|
||||||
multiType: 0,
|
multiType: 0,
|
||||||
msp_version: 0, // not specified using semantic versioning
|
msp_version: 0, // not specified using semantic versioning
|
||||||
capability: 0,
|
capability: 0,
|
||||||
|
@ -67,6 +68,59 @@ const INITIAL_BATTERY_CONFIG = {
|
||||||
currentMeterSource: 0,
|
currentMeterSource: 0,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
const FIRMWARE_BUILD_OPTIONS = {
|
||||||
|
// Radio Protocols
|
||||||
|
USE_SERIALRX_CRSF: 4097,
|
||||||
|
USE_SERIALRX_FPORT: 4098,
|
||||||
|
USE_SERIALRX_GHST: 4099,
|
||||||
|
USE_SERIALRX_IBUS: 4100,
|
||||||
|
USE_SERIALRX_JETIEXBUS: 4101,
|
||||||
|
USE_RX_PPM: 4102,
|
||||||
|
USE_SERIALRX_SBUS: 4103,
|
||||||
|
USE_SERIALRX_SPEKTRUM: 4104,
|
||||||
|
USE_SERIALRX_SRXL2: 4105,
|
||||||
|
USE_SERIALRX_SUMD: 4106,
|
||||||
|
USE_SERIALRX_SUMH: 4107,
|
||||||
|
USE_SERIALRX_XBUS: 4108,
|
||||||
|
|
||||||
|
// Motor Protocols
|
||||||
|
USE_BRUSHED: 8230,
|
||||||
|
USE_DSHOT: 8231,
|
||||||
|
USE_MULTISHOT: 8232,
|
||||||
|
USE_ONESHOT: 8233,
|
||||||
|
USE_PROSHOT: 8234,
|
||||||
|
USE_PWM_OUTPUT: 8235,
|
||||||
|
|
||||||
|
// Telemetry Protocols
|
||||||
|
USE_TELEMETRY_FRSKY_HUB: 12301,
|
||||||
|
USE_TELEMETRY_HOTT: 12302,
|
||||||
|
USE_TELEMETRY_IBUS_EXTENDED:12303,
|
||||||
|
USE_TELEMETRY_LTM: 12304,
|
||||||
|
USE_TELEMETRY_MAVLINK: 12305,
|
||||||
|
USE_TELEMETRY_SMARTPORT: 12306,
|
||||||
|
USE_TELEMETRY_SRXL: 12307,
|
||||||
|
|
||||||
|
// General Options
|
||||||
|
USE_ACRO_TRAINER: 16404,
|
||||||
|
USE_AKK_SMARTAUDIO: 16405,
|
||||||
|
USE_BATTERY_CONTINUE: 16406,
|
||||||
|
USE_CAMERA_CONTROL: 16407,
|
||||||
|
USE_DASHBOARD: 16408,
|
||||||
|
USE_EMFAT_TOOLS: 16409,
|
||||||
|
USE_ESCSERIAL_SIMONK: 16410,
|
||||||
|
USE_FRSKYOSD: 16411,
|
||||||
|
USE_GPS: 16412,
|
||||||
|
USE_LED_STRIP: 16413,
|
||||||
|
USE_LED_STRIP_64: 16414,
|
||||||
|
USE_MAG: 16415,
|
||||||
|
USE_OSD_SD: 16416,
|
||||||
|
USE_OSD_HD: 16417,
|
||||||
|
USE_PINIO: 16418,
|
||||||
|
USE_RACE_PRO: 16419,
|
||||||
|
USE_SERVOS: 16420,
|
||||||
|
USE_VTX: 16421,
|
||||||
|
};
|
||||||
|
|
||||||
const FC = {
|
const FC = {
|
||||||
|
|
||||||
// define all the global variables that are uses to hold FC state
|
// define all the global variables that are uses to hold FC state
|
||||||
|
@ -832,6 +886,21 @@ const FC = {
|
||||||
MOTOR_PROTOCOL_DISABLED: 1,
|
MOTOR_PROTOCOL_DISABLED: 1,
|
||||||
},
|
},
|
||||||
|
|
||||||
|
processBuildOptions() {
|
||||||
|
const buildOptions = [];
|
||||||
|
|
||||||
|
for (const [key, value] of Object.entries(FIRMWARE_BUILD_OPTIONS)) {
|
||||||
|
for (const option of this.CONFIG.buildOptions) {
|
||||||
|
if (option === value) {
|
||||||
|
buildOptions.push(key);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
this.CONFIG.buildOptions = buildOptions;
|
||||||
|
},
|
||||||
|
|
||||||
boardHasVcp() {
|
boardHasVcp() {
|
||||||
return bit_check(this.CONFIG.targetCapabilities, this.TARGET_CAPABILITIES_FLAGS.HAS_VCP);
|
return bit_check(this.CONFIG.targetCapabilities, this.TARGET_CAPABILITIES_FLAGS.HAS_VCP);
|
||||||
},
|
},
|
||||||
|
|
|
@ -8,7 +8,7 @@ import semver from 'semver';
|
||||||
import vtxDeviceStatusFactory from "../utils/VtxDeviceStatus/VtxDeviceStatusFactory";
|
import vtxDeviceStatusFactory from "../utils/VtxDeviceStatus/VtxDeviceStatusFactory";
|
||||||
import MSP from "../msp";
|
import MSP from "../msp";
|
||||||
import MSPCodes from "./MSPCodes";
|
import MSPCodes from "./MSPCodes";
|
||||||
import { API_VERSION_1_42, API_VERSION_1_43, API_VERSION_1_44, API_VERSION_1_45, API_VERSION_1_46 } from '../data_storage';
|
import { API_VERSION_1_42, API_VERSION_1_43, API_VERSION_1_44, API_VERSION_1_45, API_VERSION_1_46, API_VERSION_1_47 } from '../data_storage';
|
||||||
import EscProtocols from "../utils/EscProtocols";
|
import EscProtocols from "../utils/EscProtocols";
|
||||||
import huffmanDecodeBuf from "../huffman";
|
import huffmanDecodeBuf from "../huffman";
|
||||||
import { defaultHuffmanTree, defaultHuffmanLenIndex } from "../default_huffman_tree";
|
import { defaultHuffmanTree, defaultHuffmanLenIndex } from "../default_huffman_tree";
|
||||||
|
@ -771,7 +771,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
FC.CONFIG.flightControllerVersion = `${data.readU8()}.${data.readU8()}.${data.readU8()}`;
|
FC.CONFIG.flightControllerVersion = `${data.readU8()}.${data.readU8()}.${data.readU8()}`;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_BUILD_INFO:
|
case MSPCodes.MSP_BUILD_INFO: {
|
||||||
const dateLength = 11;
|
const dateLength = 11;
|
||||||
buff = [];
|
buff = [];
|
||||||
|
|
||||||
|
@ -785,7 +785,26 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
buff.push(data.readU8());
|
buff.push(data.readU8());
|
||||||
}
|
}
|
||||||
FC.CONFIG.buildInfo = String.fromCharCode.apply(null, buff);
|
FC.CONFIG.buildInfo = String.fromCharCode.apply(null, buff);
|
||||||
|
|
||||||
|
const gitRevisionLength = 7;
|
||||||
|
buff = [];
|
||||||
|
for (let i = 0; i < gitRevisionLength; i++) {
|
||||||
|
buff.push(data.readU8());
|
||||||
|
}
|
||||||
|
|
||||||
|
FC.CONFIG.gitRevision = String.fromCharCode.apply(null, buff);
|
||||||
|
console.log("Fw git rev:", FC.CONFIG.gitRevision);
|
||||||
|
|
||||||
|
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_47)) {
|
||||||
|
let option = data.readU16();
|
||||||
|
while (option) {
|
||||||
|
FC.CONFIG.buildOptions.push(option);
|
||||||
|
option = data.readU16();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
case MSPCodes.MSP_BOARD_INFO:
|
case MSPCodes.MSP_BOARD_INFO:
|
||||||
FC.CONFIG.boardIdentifier = '';
|
FC.CONFIG.boardIdentifier = '';
|
||||||
|
|
|
@ -10,7 +10,7 @@ import MSP from "./msp";
|
||||||
import MSPCodes from "./msp/MSPCodes";
|
import MSPCodes from "./msp/MSPCodes";
|
||||||
import PortUsage from "./port_usage";
|
import PortUsage from "./port_usage";
|
||||||
import PortHandler from "./port_handler";
|
import PortHandler from "./port_handler";
|
||||||
import CONFIGURATOR, { API_VERSION_1_45, API_VERSION_1_46 } from "./data_storage";
|
import CONFIGURATOR, { API_VERSION_1_45, API_VERSION_1_46, API_VERSION_1_47 } from "./data_storage";
|
||||||
import UI_PHONES from "./phones_ui";
|
import UI_PHONES from "./phones_ui";
|
||||||
import { bit_check } from './bit.js';
|
import { bit_check } from './bit.js';
|
||||||
import { sensor_status, have_sensor } from "./sensor_helpers";
|
import { sensor_status, have_sensor } from "./sensor_helpers";
|
||||||
|
@ -352,6 +352,11 @@ function onOpen(openInfo) {
|
||||||
|
|
||||||
gui_log(i18n.getMessage('buildInfoReceived', [FC.CONFIG.buildInfo]));
|
gui_log(i18n.getMessage('buildInfoReceived', [FC.CONFIG.buildInfo]));
|
||||||
|
|
||||||
|
// retrieve build options from the flight controller
|
||||||
|
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_47)) {
|
||||||
|
FC.processBuildOptions();
|
||||||
|
}
|
||||||
|
|
||||||
MSP.send_message(MSPCodes.MSP_BOARD_INFO, false, false, processBoardInfo);
|
MSP.send_message(MSPCodes.MSP_BOARD_INFO, false, false, processBoardInfo);
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
|
@ -534,7 +539,12 @@ function checkReportProblems() {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
async function processBuildConfiguration() {
|
async function processBuildOptions() {
|
||||||
|
const supported = semver.satisfies(FC.CONFIG.apiVersion, `${API_VERSION_1_45} - ${API_VERSION_1_46}`);
|
||||||
|
|
||||||
|
// firmware 1_45 or higher is required to support cloud build options
|
||||||
|
// firmware 1_46 or higher retrieves build options from the flight controller
|
||||||
|
if (supported && FC.CONFIG.buildKey.length === 32 && navigator.onLine) {
|
||||||
const buildApi = new BuildApi();
|
const buildApi = new BuildApi();
|
||||||
|
|
||||||
function onLoadCloudBuild(options) {
|
function onLoadCloudBuild(options) {
|
||||||
|
@ -542,16 +552,24 @@ async function processBuildConfiguration() {
|
||||||
processCraftName();
|
processCraftName();
|
||||||
}
|
}
|
||||||
|
|
||||||
await MSP.promise(MSPCodes.MSP2_GET_TEXT, mspHelper.crunch(MSPCodes.MSP2_GET_TEXT, MSPCodes.BUILD_KEY));
|
|
||||||
|
|
||||||
if (FC.CONFIG.buildKey.length === 32 && navigator.onLine) {
|
|
||||||
gui_log(i18n.getMessage('buildKey', FC.CONFIG.buildKey));
|
|
||||||
buildApi.requestBuildOptions(FC.CONFIG.buildKey, onLoadCloudBuild, processCraftName);
|
buildApi.requestBuildOptions(FC.CONFIG.buildKey, onLoadCloudBuild, processCraftName);
|
||||||
} else {
|
} else {
|
||||||
processCraftName();
|
processCraftName();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
async function processBuildConfiguration() {
|
||||||
|
const supported = semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_45);
|
||||||
|
|
||||||
|
if (supported) {
|
||||||
|
// get build key from firmware
|
||||||
|
await MSP.promise(MSPCodes.MSP2_GET_TEXT, mspHelper.crunch(MSPCodes.MSP2_GET_TEXT, MSPCodes.BUILD_KEY));
|
||||||
|
gui_log(i18n.getMessage('buildKey', FC.CONFIG.buildKey));
|
||||||
|
}
|
||||||
|
|
||||||
|
processBuildOptions();
|
||||||
|
}
|
||||||
|
|
||||||
async function processUid() {
|
async function processUid() {
|
||||||
await MSP.promise(MSPCodes.MSP_UID);
|
await MSP.promise(MSPCodes.MSP_UID);
|
||||||
|
|
||||||
|
@ -559,11 +577,7 @@ async function processUid() {
|
||||||
|
|
||||||
gui_log(i18n.getMessage('uniqueDeviceIdReceived', FC.CONFIG.deviceIdentifier));
|
gui_log(i18n.getMessage('uniqueDeviceIdReceived', FC.CONFIG.deviceIdentifier));
|
||||||
|
|
||||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_45)) {
|
|
||||||
processBuildConfiguration();
|
processBuildConfiguration();
|
||||||
} else {
|
|
||||||
processCraftName();
|
|
||||||
}
|
|
||||||
|
|
||||||
tracking.sendEvent(tracking.EVENT_CATEGORIES.FLIGHT_CONTROLLER, 'Connected', {
|
tracking.sendEvent(tracking.EVENT_CATEGORIES.FLIGHT_CONTROLLER, 'Connected', {
|
||||||
deviceIdentifier: CryptoES.SHA1(FC.CONFIG.deviceIdentifier),
|
deviceIdentifier: CryptoES.SHA1(FC.CONFIG.deviceIdentifier),
|
||||||
|
|
|
@ -12,7 +12,7 @@ import FC from '../fc';
|
||||||
import MSP from '../msp';
|
import MSP from '../msp';
|
||||||
import MSPCodes from '../msp/MSPCodes';
|
import MSPCodes from '../msp/MSPCodes';
|
||||||
import PortHandler, { usbDevices } from '../port_handler';
|
import PortHandler, { usbDevices } from '../port_handler';
|
||||||
import { API_VERSION_1_39, API_VERSION_1_45 } from '../data_storage';
|
import { API_VERSION_1_39, API_VERSION_1_45, API_VERSION_1_47 } from '../data_storage';
|
||||||
import serial from '../serial';
|
import serial from '../serial';
|
||||||
import STM32DFU from '../protocols/stm32usbdfu';
|
import STM32DFU from '../protocols/stm32usbdfu';
|
||||||
import { gui_log } from '../gui_log';
|
import { gui_log } from '../gui_log';
|
||||||
|
@ -1302,7 +1302,13 @@ firmware_flasher.verifyBoard = function() {
|
||||||
}
|
}
|
||||||
|
|
||||||
function getBoardInfo() {
|
function getBoardInfo() {
|
||||||
MSP.send_message(MSPCodes.MSP_BOARD_INFO, false, false, onFinish);
|
MSP.send_message(MSPCodes.MSP_BOARD_INFO, false, false, function() {
|
||||||
|
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_47)) {
|
||||||
|
FC.processBuildOptions();
|
||||||
|
self.cloudBuildOptions = FC.CONFIG.buildOptions;
|
||||||
|
}
|
||||||
|
onFinish();
|
||||||
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
function getCloudBuildOptions(options) {
|
function getCloudBuildOptions(options) {
|
||||||
|
@ -1319,7 +1325,7 @@ firmware_flasher.verifyBoard = function() {
|
||||||
// store FC.CONFIG.buildKey as the object gets destroyed after disconnect
|
// store FC.CONFIG.buildKey as the object gets destroyed after disconnect
|
||||||
self.cloudBuildKey = FC.CONFIG.buildKey;
|
self.cloudBuildKey = FC.CONFIG.buildKey;
|
||||||
|
|
||||||
if (self.validateBuildKey()) {
|
if (self.validateBuildKey() && semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_47)) {
|
||||||
self.buildApi.requestBuildOptions(self.cloudBuildKey, getCloudBuildOptions, getBoardInfo);
|
self.buildApi.requestBuildOptions(self.cloudBuildKey, getCloudBuildOptions, getBoardInfo);
|
||||||
} else {
|
} else {
|
||||||
getBoardInfo();
|
getBoardInfo();
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue