mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
initial strikes for backup and restore featureset
currently the backup part (file creation and latest data pull appears to be working just fine) restore part of the code is already able to pickup and read the file (without any version verifications (for now, will add some if necessary / needs more field testing) next step is to push the reconstructed values to the respective data arrays and objects and then uploading this new data to the flight controller
This commit is contained in:
parent
74b3fbb63f
commit
9ad8534f0c
7 changed files with 158 additions and 6 deletions
|
@ -204,6 +204,13 @@ a:hover {
|
|||
.tab-initial_setup .section a:hover {
|
||||
background-color: #424d84;
|
||||
}
|
||||
.tab-initial_setup .section a.backup {
|
||||
width: 75px;
|
||||
margin-right: 10px;
|
||||
}
|
||||
.tab-initial_setup .section a.restore {
|
||||
width: 75px;
|
||||
}
|
||||
.tab-initial_setup .section p {
|
||||
margin-left: 180px;
|
||||
|
||||
|
@ -216,7 +223,7 @@ a:hover {
|
|||
|
||||
margin-top: 10px;
|
||||
|
||||
height: 320px;
|
||||
height: 300px;
|
||||
width: 400px;
|
||||
|
||||
border: 1px solid silver;
|
||||
|
@ -226,7 +233,7 @@ a:hover {
|
|||
position: relative;
|
||||
display: block;
|
||||
|
||||
top: 285px;
|
||||
top: 265px;
|
||||
left: 10px;
|
||||
|
||||
width: 100px;
|
||||
|
@ -397,7 +404,7 @@ a:hover {
|
|||
.tab-initial_setup .compass-wrapper {
|
||||
float: left;
|
||||
|
||||
margin-top: 50px;
|
||||
margin-top: 20px;
|
||||
margin-left: 180px;
|
||||
|
||||
border: 1px solid silver;
|
||||
|
|
131
js/backup_restore.js
Normal file
131
js/backup_restore.js
Normal file
|
@ -0,0 +1,131 @@
|
|||
function configuration_backup() {
|
||||
// request configuration data
|
||||
send_message(MSP_codes.MSP_IDENT, MSP_codes.MSP_IDENT);
|
||||
send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS);
|
||||
send_message(MSP_codes.MSP_PID, MSP_codes.MSP_PID);
|
||||
send_message(MSP_codes.MSP_RC_TUNING, MSP_codes.MSP_RC_TUNING);
|
||||
send_message(MSP_codes.MSP_BOXNAMES, MSP_codes.MSP_BOXNAMES);
|
||||
send_message(MSP_codes.MSP_BOX, MSP_codes.MSP_BOX);
|
||||
send_message(MSP_codes.MSP_ACC_TRIM, MSP_codes.MSP_ACC_TRIM);
|
||||
|
||||
// applying 200ms delay (should be enough to pull all the data down)
|
||||
// we might increase this in case someone would be using very slow baudrate (ergo 9600 and lower)
|
||||
setTimeout(function() {
|
||||
var chosenFileEntry = null;
|
||||
|
||||
var accepts = [{
|
||||
extensions: ['txt']
|
||||
}];
|
||||
|
||||
// generate timestamp for the backup file
|
||||
var d = new Date();
|
||||
var now = d.getUTCFullYear() + '.' + d.getDate() + '.' + (d.getMonth() + 1) + '.' + d.getHours() + '.' + d.getMinutes();
|
||||
|
||||
// create or load the file
|
||||
chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: 'bf_mw_backup_' + now, accepts: accepts}, function(fileEntry) {
|
||||
if (!fileEntry) {
|
||||
console.log('No file selected');
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
chosenFileEntry = fileEntry;
|
||||
|
||||
// echo/console log path specified
|
||||
chrome.fileSystem.getDisplayPath(chosenFileEntry, function(path) {
|
||||
console.log('Backup file path: ' + path);
|
||||
});
|
||||
|
||||
// change file entry from read only to read/write
|
||||
chrome.fileSystem.getWritableEntry(chosenFileEntry, function(fileEntryWritable) {
|
||||
// check if file is writable
|
||||
chrome.fileSystem.isWritableEntry(fileEntryWritable, function(isWritable) {
|
||||
if (isWritable) {
|
||||
chosenFileEntry = fileEntryWritable;
|
||||
|
||||
// create config object that will be used to store all downloaded data
|
||||
var configuration = {
|
||||
PID: PIDs,
|
||||
AUX_val: AUX_CONFIG_values,
|
||||
RC: RC_tuning,
|
||||
AccelTrim: CONFIG.accelerometerTrims
|
||||
}
|
||||
|
||||
// crunch the config object
|
||||
var serialized_config_object = JSON.stringify(configuration);
|
||||
var blob = new Blob([serialized_config_object], {type: 'text/plain'}); // first parameter for Blob needs to be an array
|
||||
|
||||
chosenFileEntry.createWriter(function(writer) {
|
||||
writer.onerror = function (e) {
|
||||
console.error(e);
|
||||
};
|
||||
|
||||
writer.onwriteend = function() {
|
||||
console.log('Write SUCCESSFUL');
|
||||
};
|
||||
|
||||
writer.write(blob);
|
||||
}, function (e) {
|
||||
console.error(e);
|
||||
});
|
||||
} else {
|
||||
// Something went wrong or file is set to read only and cannot be changed
|
||||
console.log('File appears to be read only, sorry.');
|
||||
}
|
||||
});
|
||||
});
|
||||
});
|
||||
}, 200);
|
||||
}
|
||||
|
||||
function configuration_restore() {
|
||||
var chosenFileEntry = null;
|
||||
|
||||
var accepts = [{
|
||||
extensions: ['txt']
|
||||
}];
|
||||
|
||||
// load up the file
|
||||
chrome.fileSystem.chooseEntry({type: 'openFile', accepts: accepts}, function(fileEntry) {
|
||||
if (!fileEntry) {
|
||||
console.log('No file selected');
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
chosenFileEntry = fileEntry;
|
||||
|
||||
// echo/console log path specified
|
||||
chrome.fileSystem.getDisplayPath(chosenFileEntry, function(path) {
|
||||
console.log('Restore file path: ' + path);
|
||||
});
|
||||
|
||||
// read contents into variable
|
||||
chosenFileEntry.file(function(file) {
|
||||
var reader = new FileReader();
|
||||
|
||||
reader.onerror = function (e) {
|
||||
console.error(e);
|
||||
};
|
||||
|
||||
reader.onloadend = function(e) {
|
||||
console.log('Read SUCCESSFUL');
|
||||
|
||||
try { // check if string provided is a valid JSON
|
||||
var deserialized_configuration_object = JSON.parse(e.target.result);
|
||||
} catch (e) {
|
||||
// data provided != valid json object
|
||||
console.log('Data provided != valid JSON string. ABORTING !!!');
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
// replacing "old configuration" with configuration from backup file
|
||||
var configuration = deserialized_configuration_object;
|
||||
console.log(configuration);
|
||||
};
|
||||
|
||||
reader.readAsText(file);
|
||||
});
|
||||
});
|
||||
}
|
|
@ -63,5 +63,5 @@ $(document).ready(function() {
|
|||
});
|
||||
|
||||
// temporary
|
||||
//$('#content').load("./tabs/gps.html", tab_initialize_gps);
|
||||
//$('#content').load("./tabs/initial_setup.html", tab_initialize_initial_setup);
|
||||
});
|
|
@ -12,6 +12,7 @@
|
|||
<script type="text/javascript" src="./js/jquery-2.0.2.min.js"></script>
|
||||
<script type="text/javascript" src="./js/serial_backend.js"></script>
|
||||
<script type="text/javascript" src="./js/main.js"></script>
|
||||
<script type="text/javascript" src="./js/backup_restore.js"></script>
|
||||
|
||||
<!-- Various tabs are divided into separate files (for clarity) -->
|
||||
<script type="text/javascript" src="./tabs/initial_setup.js"></script>
|
||||
|
|
|
@ -12,7 +12,9 @@
|
|||
},
|
||||
|
||||
"permissions": [
|
||||
"serial"
|
||||
"serial",
|
||||
"fileSystem",
|
||||
"fileSystem.write"
|
||||
],
|
||||
|
||||
"icons": {
|
||||
|
|
|
@ -18,6 +18,13 @@
|
|||
Reset <span style="color: red">all</span> settings to <strong>default</strong>
|
||||
</p>
|
||||
</div>
|
||||
<div class="section">
|
||||
<a class="backup" href="#">Backup</a>
|
||||
<a class="restore" href="#">Restore</a>
|
||||
<p>
|
||||
<strong>Backup</strong> your configuration in case of accident.
|
||||
</p>
|
||||
</div>
|
||||
<div id="interactive_block">
|
||||
<a class="reset" href="#" title="Reset Z">Reset Z axis</a>
|
||||
<div id="perspective">
|
||||
|
|
|
@ -50,6 +50,10 @@ function tab_initialize_initial_setup() {
|
|||
console.log("YAW reset to 0");
|
||||
});
|
||||
|
||||
$('#content .backup').click(configuration_backup);
|
||||
|
||||
$('#content .restore').click(configuration_restore);
|
||||
|
||||
// enable data pulling
|
||||
timers.push(setInterval(data_poll, 50));
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue