Merge pull request #303 from ProDrone/safe_save_for_rxfail_values
MSP_SET_RXFAIL_CONFIG changed to allow more future RX channels10.3.x-maintenance
commit
4f4f8a5805
|
@ -676,7 +676,6 @@ function configuration_restore(callback) {
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||||
uniqueData.push(MSP_codes.MSP_SET_RX_CONFIG);
|
uniqueData.push(MSP_codes.MSP_SET_RX_CONFIG);
|
||||||
uniqueData.push(MSP_codes.MSP_SET_FAILSAFE_CONFIG);
|
uniqueData.push(MSP_codes.MSP_SET_FAILSAFE_CONFIG);
|
||||||
uniqueData.push(MSP_codes.MSP_SET_RXFAIL_CONFIG);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -701,7 +700,7 @@ function configuration_restore(callback) {
|
||||||
send_unique_data_item();
|
send_unique_data_item();
|
||||||
});
|
});
|
||||||
} else {
|
} else {
|
||||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, send_led_strip_config);
|
send_led_strip_config();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -714,7 +713,19 @@ function configuration_restore(callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function send_led_strip_config() {
|
function send_led_strip_config() {
|
||||||
MSP.sendLedStripConfig(reboot);
|
MSP.sendLedStripConfig(send_rxfail_config);
|
||||||
|
}
|
||||||
|
|
||||||
|
function send_rxfail_config() {
|
||||||
|
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||||
|
MSP.sendRxFailConfig(save_to_eeprom);
|
||||||
|
} else {
|
||||||
|
save_to_eeprom();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function save_to_eeprom() {
|
||||||
|
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||||
}
|
}
|
||||||
|
|
||||||
function reboot() {
|
function reboot() {
|
||||||
|
|
59
js/msp.js
59
js/msp.js
|
@ -800,12 +800,14 @@ var MSP = {
|
||||||
offset++;
|
offset++;
|
||||||
FAILSAFE_CONFIG.failsafe_throttle = data.getUint16(offset, 1);
|
FAILSAFE_CONFIG.failsafe_throttle = data.getUint16(offset, 1);
|
||||||
offset += 2;
|
offset += 2;
|
||||||
|
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||||
FAILSAFE_CONFIG.failsafe_kill_switch = data.getUint8(offset, 1);
|
FAILSAFE_CONFIG.failsafe_kill_switch = data.getUint8(offset, 1);
|
||||||
offset++;
|
offset++;
|
||||||
FAILSAFE_CONFIG.failsafe_throttle_low_delay = data.getUint16(offset, 1);
|
FAILSAFE_CONFIG.failsafe_throttle_low_delay = data.getUint16(offset, 1);
|
||||||
offset += 2;
|
offset += 2;
|
||||||
FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset, 1);
|
FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset, 1);
|
||||||
offset++;
|
offset++;
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_codes.MSP_RXFAIL_CONFIG:
|
case MSP_codes.MSP_RXFAIL_CONFIG:
|
||||||
|
@ -1178,17 +1180,11 @@ MSP.crunch = function (code) {
|
||||||
buffer.push(FAILSAFE_CONFIG.failsafe_off_delay);
|
buffer.push(FAILSAFE_CONFIG.failsafe_off_delay);
|
||||||
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle));
|
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle));
|
||||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle));
|
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle));
|
||||||
|
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||||
buffer.push(FAILSAFE_CONFIG.failsafe_kill_switch);
|
buffer.push(FAILSAFE_CONFIG.failsafe_kill_switch);
|
||||||
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||||
buffer.push(FAILSAFE_CONFIG.failsafe_procedure);
|
buffer.push(FAILSAFE_CONFIG.failsafe_procedure);
|
||||||
break;
|
|
||||||
|
|
||||||
case MSP_codes.MSP_SET_RXFAIL_CONFIG:
|
|
||||||
for (var i = 0; i < RXFAIL_CONFIG.length; i++) {
|
|
||||||
buffer.push(RXFAIL_CONFIG[i].mode);
|
|
||||||
buffer.push(lowByte(RXFAIL_CONFIG[i].value));
|
|
||||||
buffer.push(highByte(RXFAIL_CONFIG[i].value));
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -1312,9 +1308,9 @@ MSP.sendServoConfigurations = function(onCompleteCallback) {
|
||||||
|
|
||||||
if (SERVO_CONFIG.length == 0) {
|
if (SERVO_CONFIG.length == 0) {
|
||||||
onCompleteCallback();
|
onCompleteCallback();
|
||||||
}
|
} else {
|
||||||
|
|
||||||
nextFunction();
|
nextFunction();
|
||||||
|
}
|
||||||
|
|
||||||
function send_next_servo_configuration() {
|
function send_next_servo_configuration() {
|
||||||
|
|
||||||
|
@ -1402,10 +1398,9 @@ MSP.sendModeRanges = function(onCompleteCallback) {
|
||||||
|
|
||||||
if (MODE_RANGES.length == 0) {
|
if (MODE_RANGES.length == 0) {
|
||||||
onCompleteCallback();
|
onCompleteCallback();
|
||||||
}
|
} else {
|
||||||
|
|
||||||
send_next_mode_range();
|
send_next_mode_range();
|
||||||
|
}
|
||||||
|
|
||||||
function send_next_mode_range() {
|
function send_next_mode_range() {
|
||||||
|
|
||||||
|
@ -1435,10 +1430,9 @@ MSP.sendAdjustmentRanges = function(onCompleteCallback) {
|
||||||
|
|
||||||
if (ADJUSTMENT_RANGES.length == 0) {
|
if (ADJUSTMENT_RANGES.length == 0) {
|
||||||
onCompleteCallback();
|
onCompleteCallback();
|
||||||
}
|
} else {
|
||||||
|
|
||||||
send_next_adjustment_range();
|
send_next_adjustment_range();
|
||||||
|
}
|
||||||
|
|
||||||
function send_next_adjustment_range() {
|
function send_next_adjustment_range() {
|
||||||
|
|
||||||
|
@ -1471,9 +1465,9 @@ MSP.sendLedStripConfig = function(onCompleteCallback) {
|
||||||
|
|
||||||
if (LED_STRIP.length == 0) {
|
if (LED_STRIP.length == 0) {
|
||||||
onCompleteCallback();
|
onCompleteCallback();
|
||||||
}
|
} else {
|
||||||
|
|
||||||
send_next_led_strip_config();
|
send_next_led_strip_config();
|
||||||
|
}
|
||||||
|
|
||||||
function send_next_led_strip_config() {
|
function send_next_led_strip_config() {
|
||||||
|
|
||||||
|
@ -1540,3 +1534,34 @@ MSP.serialPortFunctionsToMask = function(functions) {
|
||||||
}
|
}
|
||||||
return mask;
|
return mask;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
MSP.sendRxFailConfig = function(onCompleteCallback) {
|
||||||
|
var nextFunction = send_next_rxfail_config;
|
||||||
|
|
||||||
|
var rxFailIndex = 0;
|
||||||
|
|
||||||
|
if (RXFAIL_CONFIG.length == 0) {
|
||||||
|
onCompleteCallback();
|
||||||
|
} else {
|
||||||
|
send_next_rxfail_config();
|
||||||
|
}
|
||||||
|
|
||||||
|
function send_next_rxfail_config() {
|
||||||
|
|
||||||
|
var rxFail = RXFAIL_CONFIG[rxFailIndex];
|
||||||
|
|
||||||
|
var buffer = [];
|
||||||
|
buffer.push(rxFailIndex);
|
||||||
|
buffer.push(rxFail.mode);
|
||||||
|
buffer.push(lowByte(rxFail.value));
|
||||||
|
buffer.push(highByte(rxFail.value));
|
||||||
|
|
||||||
|
// prepare for next iteration
|
||||||
|
rxFailIndex++;
|
||||||
|
if (rxFailIndex == RXFAIL_CONFIG.length) {
|
||||||
|
nextFunction = onCompleteCallback;
|
||||||
|
|
||||||
|
}
|
||||||
|
MSP.send_message(MSP_codes.MSP_SET_RXFAIL_CONFIG, buffer, false, nextFunction);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
|
@ -317,7 +317,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_rxfail_config() {
|
function save_rxfail_config() {
|
||||||
MSP.send_message(MSP_codes.MSP_SET_RXFAIL_CONFIG, MSP.crunch(MSP_codes.MSP_SET_RXFAIL_CONFIG), false, save_bf_config);
|
MSP.sendRxFailConfig(save_bf_config);
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_bf_config() {
|
function save_bf_config() {
|
||||||
|
|
Loading…
Reference in New Issue