mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 22:35:23 +03:00
Fix auxiliary tab when using parallel PWM.
This commit is contained in:
parent
21c346d84f
commit
c1ab10c0c8
2 changed files with 8 additions and 4 deletions
6
changelog.html
Normal file → Executable file
6
changelog.html
Normal file → Executable file
|
@ -1,4 +1,8 @@
|
|||
<span>07.17.2014 - 0.47</span>
|
||||
<span>07.06.2014 - cleanflight</span>
|
||||
<p>
|
||||
- Fix auxiliary configuration tab when using parallel pwm.<br />
|
||||
</p>
|
||||
</p><span>07.17.2014 - 0.47</span>
|
||||
<p>
|
||||
- Bugfixes related to Chrome 36+ release<br />
|
||||
- Various optimizations and behavior improvements<br />
|
||||
|
|
6
tabs/auxiliary_configuration.js
Normal file → Executable file
6
tabs/auxiliary_configuration.js
Normal file → Executable file
|
@ -48,7 +48,7 @@ tabs.auxiliary_configuration.initialize = function(callback) {
|
|||
|
||||
var bitIndex = 0;
|
||||
var chunks = 1;
|
||||
if (bit_check(CONFIG.capability, 5)) {
|
||||
if (bit_check(CONFIG.capability, 5) && (RC.active_channels - 4) > 4) {
|
||||
chunks = 2;
|
||||
}
|
||||
var channelsPerChunk = 4;
|
||||
|
@ -76,7 +76,7 @@ tabs.auxiliary_configuration.initialize = function(callback) {
|
|||
|
||||
var boxCountFor4AuxChannels = 3 * 4;
|
||||
var boxCountPerLine = boxCountFor4AuxChannels;
|
||||
if (bit_check(CONFIG.capability, 5)) {
|
||||
if (bit_check(CONFIG.capability, 5) && (RC.active_channels - 4) > 4) {
|
||||
boxCountPerLine = boxCountFor4AuxChannels * 2;
|
||||
}
|
||||
|
||||
|
@ -107,7 +107,7 @@ tabs.auxiliary_configuration.initialize = function(callback) {
|
|||
AUX_val_buffer_out.push(lowByte(AUX_CONFIG_values[i] & 0xFFF));
|
||||
AUX_val_buffer_out.push(highByte(AUX_CONFIG_values[i] & 0xFFF));
|
||||
}
|
||||
if (bit_check(CONFIG.capability, 5)) {
|
||||
if (bit_check(CONFIG.capability, 5) && (RC.active_channels - 4) > 4) {
|
||||
for (var i = 0; i < AUX_CONFIG_values.length; i++) {
|
||||
AUX_val_buffer_out.push(lowByte((AUX_CONFIG_values[i] >> 16) & 0xFFF));
|
||||
AUX_val_buffer_out.push(highByte((AUX_CONFIG_values[i] >> 16) & 0xFFF));
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue