mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-26 17:55:30 +03:00
Add support for 12 channels to the receiver tab.
If the incoming data from the FC has 8 channels then only 8 are displayed. The message size can be used to calculate the amount of channels, as per MultiWii protocol 2.3 and Cleanflight.
This commit is contained in:
parent
4fc1d3ef53
commit
49ec225d66
5 changed files with 100 additions and 26 deletions
|
@ -22,6 +22,7 @@ for (var i = 0; i < 10; i++) {
|
|||
}
|
||||
|
||||
var RC = {
|
||||
channelCount: 0,
|
||||
roll: 0,
|
||||
pitch: 0,
|
||||
yaw: 0,
|
||||
|
@ -29,7 +30,11 @@ var RC = {
|
|||
AUX1: 0,
|
||||
AUX2: 0,
|
||||
AUX3: 0,
|
||||
AUX4: 0
|
||||
AUX4: 0,
|
||||
AUX5: 0,
|
||||
AUX6: 0,
|
||||
AUX7: 0,
|
||||
AUX8: 0
|
||||
};
|
||||
|
||||
var RC_tuning = {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue