@betaflight/api
Version:
A high-level API to read data from betaflight flight controllers
334 lines • 14.4 kB
JavaScript
;
var __importDefault = (this && this.__importDefault) || function (mod) {
return (mod && mod.__esModule) ? mod : { "default": mod };
};
Object.defineProperty(exports, "__esModule", { value: true });
exports.targetCapabilities = exports.blackboxDevices = exports.gpsBaudRates = exports.gpsSbasTypes = exports.gpsProtocols = exports.channelLetters = exports.rcSmoothingDerivativeTypes = exports.rcSmoothingInputTypes = exports.rcSmoothingTypes = exports.rcSmoothingChannels = exports.rcInterpolations = exports.spiRxProtocols = exports.serialRxProviders = exports.MIXER_LIST = exports.mcuGroupFromId = exports.MCU_GROUPS = exports.escProtocols = exports.beeperBits = exports.sensorBits = exports.disarmFlagBits = exports.availableFeatures = void 0;
const semver_1 = __importDefault(require("semver"));
const types_1 = require("./types");
const utils_1 = require("./utils");
const BASE_FEATURE_BITS = {
0: types_1.Features.RX_PPM,
2: types_1.Features.INFLIGHT_ACC_CAL,
3: types_1.Features.RX_SERIAL,
4: types_1.Features.MOTOR_STOP,
5: types_1.Features.SERVO_TILT,
6: types_1.Features.SOFTSERIAL,
7: types_1.Features.GPS,
9: types_1.Features.SONAR,
10: types_1.Features.TELEMETRY,
12: types_1.Features["3D"],
13: types_1.Features.RX_PARALLEL_PWM,
14: types_1.Features.RX_MSP,
15: types_1.Features.RSSI_ADC,
16: types_1.Features.LED_STRIP,
17: types_1.Features.DISPLAY,
};
const availableFeatures = (apiVersion) => {
const featureBits = { ...BASE_FEATURE_BITS };
if (!semver_1.default.gte(apiVersion, "1.33.0")) {
featureBits[19] = types_1.Features.BLACKBOX;
}
if (semver_1.default.gte(apiVersion, "1.12.0")) {
featureBits[20] = types_1.Features.CHANNEL_FORWARDING;
}
if (semver_1.default.gte(apiVersion, "1.15.0") && !semver_1.default.gte(apiVersion, "1.36.0")) {
featureBits[8] = types_1.Features.FAILSAFE;
}
if (semver_1.default.gte(apiVersion, "1.16.0")) {
featureBits[21] = types_1.Features.TRANSPONDER;
}
if (semver_1.default.gte(apiVersion, "1.16.0")) {
featureBits[22] = types_1.Features.AIRMODE;
}
if (semver_1.default.gte(apiVersion, "1.16.0")) {
if (semver_1.default.lt(apiVersion, "1.20.0")) {
featureBits[23] = types_1.Features.SUPEREXPO_RATES;
}
else if (!semver_1.default.gte(apiVersion, "1.33.0")) {
featureBits[23] = types_1.Features.SDCARD;
}
}
if (semver_1.default.gte(apiVersion, "1.20.0")) {
featureBits[18] = types_1.Features.OSD;
if (!semver_1.default.gte(apiVersion, "1.35.0")) {
featureBits[24] = types_1.Features.VTX;
}
}
if (semver_1.default.gte(apiVersion, "1.31.0")) {
featureBits[25] = types_1.Features.RX_SPI;
featureBits[27] = types_1.Features.ESC_SENSOR;
}
if (semver_1.default.gte(apiVersion, "1.36.0")) {
featureBits[28] = types_1.Features.ANTI_GRAVITY;
featureBits[29] = types_1.Features.DYNAMIC_FILTER;
}
if (!semver_1.default.gte(apiVersion, "1.36.0")) {
featureBits[1] = types_1.Features.VBAT;
featureBits[11] = types_1.Features.VCURRENT_METER;
}
return featureBits;
};
exports.availableFeatures = availableFeatures;
const disarmFlagBits = (apiVersion) => [
types_1.DisarmFlags.NO_GYRO,
types_1.DisarmFlags.FAILSAFE,
types_1.DisarmFlags.RX_FAILSAFE,
types_1.DisarmFlags.BAD_RX_RECOVERY,
types_1.DisarmFlags.BOXFAILSAFE,
types_1.DisarmFlags.THROTTLE,
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.38.0"), types_1.DisarmFlags.RUNAWAY_TAKEOFF),
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.42.0"), types_1.DisarmFlags.CRASH),
types_1.DisarmFlags.ANGLE,
types_1.DisarmFlags.BOOT_GRACE_TIME,
types_1.DisarmFlags.NOPREARM,
types_1.DisarmFlags.LOAD,
types_1.DisarmFlags.CALIBRATING,
types_1.DisarmFlags.CLI,
types_1.DisarmFlags.CMS_MENU,
...(0, utils_1.includeIf)(semver_1.default.lt(apiVersion, "1.41.0"), types_1.DisarmFlags.OSD_MENU),
types_1.DisarmFlags.BST,
types_1.DisarmFlags.MSP,
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.39.0"), [
types_1.DisarmFlags.PARALYZE,
types_1.DisarmFlags.GPS,
]),
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.41.0"), [
types_1.DisarmFlags.RESC,
types_1.DisarmFlags.RPMFILTER,
]),
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.42.0"), [
types_1.DisarmFlags.REBOOT_REQD,
types_1.DisarmFlags.DSHOT_BBANG,
]),
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.43.0"), [types_1.DisarmFlags.NO_ACC_CAL]),
types_1.DisarmFlags.ARM_SWITCH,
];
exports.disarmFlagBits = disarmFlagBits;
const sensorBits = () => [
types_1.Sensors.ACCELEROMETER,
types_1.Sensors.BAROMETER,
types_1.Sensors.MAGNETOMETER,
types_1.Sensors.GPS,
types_1.Sensors.SONAR,
types_1.Sensors.GYRO,
];
exports.sensorBits = sensorBits;
const beeperBits = (apiVersion) => [
types_1.Beepers.GYRO_CALIBRATED,
types_1.Beepers.RX_LOST,
types_1.Beepers.RX_LOST_LANDING,
types_1.Beepers.DISARMING,
types_1.Beepers.ARMING,
types_1.Beepers.ARMING_GPS_FIX,
types_1.Beepers.BAT_CRIT_LOW,
types_1.Beepers.BAT_LOW,
types_1.Beepers.GPS_STATUS,
types_1.Beepers.RX_SET,
types_1.Beepers.ACC_CALIBRATION,
types_1.Beepers.ACC_CALIBRATION_FAIL,
types_1.Beepers.READY_BEEP,
types_1.Beepers.MULTI_BEEPS,
types_1.Beepers.DISARM_REPEAT,
types_1.Beepers.ARMED,
types_1.Beepers.SYSTEM_INIT,
types_1.Beepers.USB,
types_1.Beepers.BLACKBOX_ERASE,
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.37.0"), [
types_1.Beepers.CRASH_FLIP,
types_1.Beepers.CAM_CONNECTION_OPEN,
types_1.Beepers.CAM_CONNECTION_CLOSE,
]),
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.39.0"), [
types_1.Beepers.RC_SMOOTHING_INIT_FAIL,
]),
];
exports.beeperBits = beeperBits;
const escProtocols = (version) => [
types_1.EscProtocols.PWM,
types_1.EscProtocols.ONESHOT125,
types_1.EscProtocols.ONESHOT42,
types_1.EscProtocols.MULTISHOT,
...(0, utils_1.includeIf)(semver_1.default.gte(version, "1.20.0"), [types_1.EscProtocols.BRUSHED]),
...(0, utils_1.includeIf)(semver_1.default.gte(version, "1.31.0"), [
types_1.EscProtocols.DSHOT150,
types_1.EscProtocols.DSHOT300,
types_1.EscProtocols.DSHOT600,
]),
...(0, utils_1.includeIf)(semver_1.default.gte(version, "1.31.0") && semver_1.default.lt(version, "1.42.0"), [
types_1.EscProtocols.DSHOT1200,
]),
...(0, utils_1.includeIf)(semver_1.default.gte(version, "1.36.0"), [types_1.EscProtocols.PROSHOT1000]),
...(0, utils_1.includeIf)(semver_1.default.gte(version, "1.43.0"), [types_1.EscProtocols.DISABLED]),
];
exports.escProtocols = escProtocols;
exports.MCU_GROUPS = {
F7: [types_1.McuTypes.F722, types_1.McuTypes.F745, types_1.McuTypes.F746, types_1.McuTypes.F765],
F3: [types_1.McuTypes.F303],
F4: [types_1.McuTypes.F411, types_1.McuTypes.F446],
H7: [
types_1.McuTypes.H723_725,
types_1.McuTypes.H743_REV_UNKNOWN,
types_1.McuTypes.H743_REV_V,
types_1.McuTypes.H743_REV_X,
types_1.McuTypes.H743_REV_Y,
types_1.McuTypes.H750,
types_1.McuTypes.H7A3,
],
F1: [types_1.McuTypes.F103],
};
const mcuGroupFromId = (mcuTypeId) => Object.keys(exports.MCU_GROUPS).find((key) => exports.MCU_GROUPS[key].includes(mcuTypeId));
exports.mcuGroupFromId = mcuGroupFromId;
exports.MIXER_LIST = [
{ name: "Tricopter", id: 3, model: "tricopter", image: "tri" },
{ name: "Quad +", id: 2, model: "quad_x", image: "quad_p" },
{ name: "Quad X", id: 0, model: "quad_x", image: "quad_x" },
{ name: "Bicopter", id: 16, model: "custom", image: "bicopter" },
{ name: "Gimbal", id: 4, model: "custom", image: "custom" },
{ name: "Y6", id: 20, model: "y6", image: "y6" },
{ name: "Hex +", id: 5, model: "hex_plus", image: "hex_p" },
{ name: "Flying Wing", id: 10, model: "custom", image: "flying_wing" },
{ name: "Y4", id: 19, model: "y4", image: "y4" },
{ name: "Hex X", id: 6, model: "hex_x", image: "hex_x" },
{ name: "Octo X8", id: 21, model: "custom", image: "octo_x8" },
{ name: "Octo Flat +", id: 8, model: "custom", image: "octo_flat_p" },
{ name: "Octo Flat X", id: 9, model: "custom", image: "octo_flat_x" },
{ name: "Airplane", id: 11, model: "custom", image: "airplane" },
{ name: "Heli 120", id: 12, model: "custom", image: "custom" },
{ name: "Heli 90", id: 13, model: "custom", image: "custom" },
{ name: "V-tail Quad", id: 17, model: "quad_vtail", image: "vtail_quad" },
{ name: "Hex H", id: 7, model: "custom", image: "custom" },
{ name: "PPM to SERVO", id: 22, model: "custom", image: "custom" },
{ name: "Dualcopter", id: 15, model: "custom", image: "custom" },
{ name: "Singlecopter", id: 14, model: "custom", image: "custom" },
{ name: "A-tail Quad", id: 18, model: "quad_atail", image: "atail_quad" },
{ name: "Custom", id: 23, model: "custom", image: "custom" },
{ name: "Custom Airplane", id: 24, model: "custom", image: "custom" },
{ name: "Custom Tricopter", id: 25, model: "custom", image: "custom" },
{ name: "Quad X 1234", id: 1, model: "quad_x", image: "quad_x_1234" },
];
const serialRxProviders = (apiVersion) => [
types_1.SerialRxProviders.SPEKTRUM1024,
types_1.SerialRxProviders.SPEKTRUM2048,
types_1.SerialRxProviders.SBUS,
types_1.SerialRxProviders.SUMD,
types_1.SerialRxProviders.SUMH,
types_1.SerialRxProviders.XBUS_MODE_B,
types_1.SerialRxProviders.XBUS_MODE_B_RJ01,
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.15.0"), types_1.SerialRxProviders.IBUS),
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.31.0"), [
types_1.SerialRxProviders.JETIEXBUS,
types_1.SerialRxProviders.CRSF,
]),
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.24.0"), types_1.SerialRxProviders.SPEKTRUM2048_SRXL),
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.35.0"), types_1.SerialRxProviders.TARGET_CUSTOM),
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.37.0"), types_1.SerialRxProviders.FRSKY_FPORT),
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.42.0"), types_1.SerialRxProviders.SPEKTRUM_SRXL2),
];
exports.serialRxProviders = serialRxProviders;
const spiRxProtocols = (apiVersion) => [
types_1.SpiRxProtocols.NRF24_V202_250K,
types_1.SpiRxProtocols.NRF24_V202_1M,
types_1.SpiRxProtocols.NRF24_SYMA_X,
types_1.SpiRxProtocols.NRF24_SYMA_X5C,
types_1.SpiRxProtocols.NRF24_CX10,
types_1.SpiRxProtocols.CX10A,
types_1.SpiRxProtocols.NRF24_H8_3D,
types_1.SpiRxProtocols.NRF24_INAV,
types_1.SpiRxProtocols.FRSKY_D,
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.37.0"), [
types_1.SpiRxProtocols.FRSKY_X,
types_1.SpiRxProtocols.A7105_FLYSKY,
types_1.SpiRxProtocols.A7105_FLYSKY_2A,
types_1.SpiRxProtocols.NRF24_KN,
]),
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.41.0"), [
types_1.SpiRxProtocols.SFHSS,
types_1.SpiRxProtocols.SPEKTRUM,
types_1.SpiRxProtocols.FRSKY_X_LBT,
]),
];
exports.spiRxProtocols = spiRxProtocols;
const rcInterpolations = () => [
types_1.RcInterpolations.AUTO,
types_1.RcInterpolations.DEFAULT,
types_1.RcInterpolations.MANUAL,
types_1.RcInterpolations.OFF,
];
exports.rcInterpolations = rcInterpolations;
const rcSmoothingChannels = () => [
types_1.RcSmoothingChannels.RP,
types_1.RcSmoothingChannels.RPY,
types_1.RcSmoothingChannels.RPYT,
types_1.RcSmoothingChannels.T,
types_1.RcSmoothingChannels.RPT,
];
exports.rcSmoothingChannels = rcSmoothingChannels;
const rcSmoothingTypes = () => [
types_1.RcSmoothingTypes.INTERPOLATION,
types_1.RcSmoothingTypes.FILTER,
];
exports.rcSmoothingTypes = rcSmoothingTypes;
const rcSmoothingInputTypes = () => [
types_1.RcSmoothingInputTypes.PT1,
types_1.RcSmoothingInputTypes.BIQUAD,
];
exports.rcSmoothingInputTypes = rcSmoothingInputTypes;
const rcSmoothingDerivativeTypes = (apiVersion) => [
types_1.RcSmoothingDerivativeTypes.OFF,
types_1.RcSmoothingDerivativeTypes.PT1,
types_1.RcSmoothingDerivativeTypes.BIQUAD,
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.43.0"), types_1.RcSmoothingDerivativeTypes.AUTO),
];
exports.rcSmoothingDerivativeTypes = rcSmoothingDerivativeTypes;
const channelLetters = () => [
"A",
"E",
"R",
"T",
"1",
"2",
"3",
"4",
];
exports.channelLetters = channelLetters;
const gpsProtocols = (apiVersion) => [
types_1.GpsProtocols.NMEA,
types_1.GpsProtocols.UBLOX,
...(0, utils_1.includeIf)(semver_1.default.gte(apiVersion, "1.41.0"), types_1.GpsProtocols.MSP),
];
exports.gpsProtocols = gpsProtocols;
const gpsSbasTypes = () => [
types_1.GpsSbasTypes.AUTO,
types_1.GpsSbasTypes.EGNOS,
types_1.GpsSbasTypes.WAAS,
types_1.GpsSbasTypes.MSAS,
types_1.GpsSbasTypes.GAGAN,
];
exports.gpsSbasTypes = gpsSbasTypes;
const gpsBaudRates = () => [
types_1.GpsBaudRates.BAUD_115200,
types_1.GpsBaudRates.BAUD_57600,
types_1.GpsBaudRates.BAUD_38400,
types_1.GpsBaudRates.BAUD_19200,
types_1.GpsBaudRates.BAUD_9600,
];
exports.gpsBaudRates = gpsBaudRates;
const blackboxDevices = (api) => [
semver_1.default.gte(api, "1.33.0") ? types_1.BlackboxDevices.NONE : types_1.BlackboxDevices.SERIAL,
types_1.BlackboxDevices.FLASH,
types_1.BlackboxDevices.SDCARD,
types_1.BlackboxDevices.SERIAL,
];
exports.blackboxDevices = blackboxDevices;
const targetCapabilities = () => [
types_1.TargetCapabilities.HAS_VCP,
types_1.TargetCapabilities.HAS_SOFTSERIAL,
types_1.TargetCapabilities.IS_UNIFIED,
types_1.TargetCapabilities.HAS_FLASH_BOOTLOADER,
types_1.TargetCapabilities.SUPPORTS_CUSTOM_DEFAULTS,
types_1.TargetCapabilities.HAS_CUSTOM_DEFAULTS,
types_1.TargetCapabilities.SUPPORTS_RX_BIND,
];
exports.targetCapabilities = targetCapabilities;
//# sourceMappingURL=features.js.map