mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
Merge remote-tracking branch 'upstream/development' into blackbox-flash
This commit is contained in:
commit
7fb9f43b00
35 changed files with 1774 additions and 4748 deletions
36
js/boards.js
36
js/boards.js
|
@ -3,51 +3,43 @@
|
|||
var BOARD_DEFINITIONS = [
|
||||
{
|
||||
name: "CC3D",
|
||||
identifier: "CC3D",
|
||||
serialPortCount: 3
|
||||
identifier: "CC3D"
|
||||
}, {
|
||||
name: "ChebuzzF3",
|
||||
identifier: "CHF3",
|
||||
serialPortCount: 3
|
||||
identifier: "CHF3"
|
||||
}, {
|
||||
name: "CJMCU",
|
||||
identifier: "CJM1",
|
||||
serialPortCount: 2
|
||||
identifier: "CJM1"
|
||||
}, {
|
||||
name: "EUSTM32F103RB",
|
||||
identifier: "EUF1",
|
||||
serialPortCount: 4
|
||||
identifier: "EUF1"
|
||||
}, {
|
||||
name: "Naze/Flip32+",
|
||||
identifier: "AFNA",
|
||||
serialPortCount: 4
|
||||
identifier: "AFNA"
|
||||
}, {
|
||||
name: "Naze32Pro",
|
||||
identifier: "AFF3",
|
||||
serialPortCount: 3
|
||||
identifier: "AFF3"
|
||||
}, {
|
||||
name: "Olimexino",
|
||||
identifier: "OLI1",
|
||||
serialPortCount: 4
|
||||
identifier: "OLI1"
|
||||
}, {
|
||||
name: "Port103R",
|
||||
identifier: "103R",
|
||||
serialPortCount: 4
|
||||
identifier: "103R"
|
||||
}, {
|
||||
name: "Sparky",
|
||||
identifier: "SPKY",
|
||||
serialPortCount: 4
|
||||
identifier: "SPKY"
|
||||
}, {
|
||||
name: "STM32F3Discovery",
|
||||
identifier: "SDF3",
|
||||
serialPortCount: 3
|
||||
identifier: "SDF3"
|
||||
}, {
|
||||
name: "SP Racing F3",
|
||||
identifier: "SRF3"
|
||||
}
|
||||
];
|
||||
|
||||
var DEFAULT_BOARD_DEFINITION = {
|
||||
name: "Unknown",
|
||||
identifier: "????",
|
||||
serialPortCount: 1
|
||||
identifier: "????"
|
||||
};
|
||||
|
||||
var BOARD = {
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
'use strict';
|
||||
|
||||
var CONFIGURATOR = {
|
||||
'releaseDate': 1422552160231, // new Date().getTime() - 2015.01.29
|
||||
'releaseDate': 1422922675433, // new Date().getTime() - 2015.01.29
|
||||
'apiVersionAccepted': 1.2,
|
||||
'backupRestoreMinApiVersionAccepted': 1.5,
|
||||
'pidControllerChangeMinApiVersion': 1.5,
|
||||
|
@ -155,4 +155,4 @@ var DATAFLASH = {
|
|||
sectors: 0,
|
||||
totalSize: 0,
|
||||
usedSize: 0
|
||||
};
|
||||
};
|
||||
|
|
23
js/msp.js
23
js/msp.js
|
@ -488,9 +488,9 @@ var MSP = {
|
|||
BF_CONFIG.mixerConfiguration = data.getUint8(0);
|
||||
BF_CONFIG.features = data.getUint32(1, 1);
|
||||
BF_CONFIG.serialrx_type = data.getUint8(5);
|
||||
BF_CONFIG.board_align_roll = data.getInt16(6, 1);
|
||||
BF_CONFIG.board_align_pitch = data.getInt16(8, 1);
|
||||
BF_CONFIG.board_align_yaw = data.getInt16(10, 1);
|
||||
BF_CONFIG.board_align_roll = data.getInt16(6, 1); // -180 - 360
|
||||
BF_CONFIG.board_align_pitch = data.getInt16(8, 1); // -180 - 360
|
||||
BF_CONFIG.board_align_yaw = data.getInt16(10, 1); // -180 - 360
|
||||
BF_CONFIG.currentscale = data.getInt16(12, 1);
|
||||
BF_CONFIG.currentoffset = data.getUint16(14, 1);
|
||||
break;
|
||||
|
@ -559,8 +559,8 @@ var MSP = {
|
|||
case MSP_codes.MSP_CF_SERIAL_CONFIG:
|
||||
SERIAL_CONFIG.ports = [];
|
||||
var offset = 0;
|
||||
var serialPortCount = data.byteLength - (4 * 4);
|
||||
for (var i = 0; offset < serialPortCount; i++) {
|
||||
var serialPortCount = (data.byteLength - (4 * 4)) / 2;
|
||||
for (var i = 0; i < serialPortCount; i++) {
|
||||
var serialPort = {
|
||||
identifier: data.getUint8(offset++, 1),
|
||||
scenario: data.getUint8(offset++, 1)
|
||||
|
@ -622,7 +622,12 @@ var MSP = {
|
|||
break;
|
||||
case MSP_codes.MSP_CHANNEL_FORWARDING:
|
||||
for (var i = 0; i < 8; i ++) {
|
||||
SERVO_CONFIG[i].indexOfChannelToForward = data.getUint8(i);
|
||||
var channelIndex = data.getUint8(i);
|
||||
if (channelIndex < 255) {
|
||||
SERVO_CONFIG[i].indexOfChannelToForward;
|
||||
} else {
|
||||
SERVO_CONFIG[i].indexOfChannelToForward = undefined;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -931,7 +936,11 @@ MSP.crunch = function (code) {
|
|||
break;
|
||||
case MSP_codes.MSP_SET_CHANNEL_FORWARDING:
|
||||
for (var i = 0; i < SERVO_CONFIG.length; i++) {
|
||||
buffer.push(SERVO_CONFIG[i].indexOfChannelToForward);
|
||||
var out = SERVO_CONFIG[i].indexOfChannelToForward;
|
||||
if (out == undefined) {
|
||||
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
|
||||
}
|
||||
buffer.push(out);
|
||||
}
|
||||
break;
|
||||
case MSP_codes.MSP_SET_CF_SERIAL_CONFIG:
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue