1
0
Fork 0
mirror of https://github.com/betaflight/betaflight-configurator.git synced 2025-07-24 16:55:24 +03:00

Merge branch 'master' of https://github.com/NightHawk32/cleanflight-configurator into NightHawk32-master

This commit is contained in:
Dominic Clifton 2015-11-16 21:44:11 +00:00
commit e801cd260a
6 changed files with 126 additions and 10 deletions

View file

@ -27,7 +27,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
}
function load_misc() {
MSP.send_message(MSP_codes.MSP_MISC, false, false, load_acc_trim);
MSP.send_message(MSP_codes.MSP_MISC, false, false, load_3d);
}
function load_3d() {
MSP.send_message(MSP_codes.MSP_3D, false, false, load_acc_trim);
}
function load_acc_trim() {
@ -313,6 +317,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('input[name="currentoffset"]').val(BF_CONFIG.currentoffset);
$('input[name="multiwiicurrentoutput"]').prop('checked', MISC.multiwiicurrentoutput);
//fill 3D
$('input[name="3ddeadbandlow"]').val(_3D.deadband3d_low);
$('input[name="3ddeadbandhigh"]').val(_3D.deadband3d_high);
$('input[name="3dneutral"]').val(_3D.neutral3d);
$('input[name="3ddeadbandthrottle"]').val(_3D.deadband3d_throttle);
// UI hooks
$('input[name="looptime"]').change(function() {
@ -389,6 +398,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
BF_CONFIG.currentoffset = parseInt($('input[name="currentoffset"]').val());
MISC.multiwiicurrentoutput = ~~$('input[name="multiwiicurrentoutput"]').is(':checked'); // ~~ boolean to decimal conversion
_3D.deadband3d_low = parseInt($('input[name="3ddeadbandlow"]').val());
_3D.deadband3d_high = parseInt($('input[name="3ddeadbandhigh"]').val());
_3D.neutral3d = parseInt($('input[name="3dneutral"]').val());
_3D.deadband3d_throttle = ($('input[name="3ddeadbandthrottle"]').val());
function save_serial_config() {
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
MSP.send_message(MSP_codes.MSP_SET_CF_SERIAL_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CF_SERIAL_CONFIG), false, save_misc);
@ -398,7 +412,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
}
function save_misc() {
MSP.send_message(MSP_codes.MSP_SET_MISC, MSP.crunch(MSP_codes.MSP_SET_MISC), false, save_acc_trim);
MSP.send_message(MSP_codes.MSP_SET_MISC, MSP.crunch(MSP_codes.MSP_SET_MISC), false, save_3d);
}
function save_3d() {
MSP.send_message(MSP_codes.MSP_SET_3D, MSP.crunch(MSP_codes.MSP_SET_3D), false, save_acc_trim);
}
function save_acc_trim() {