diff --git a/_locales/en/messages.json b/_locales/en/messages.json index 2f1fdd60..08e8541f 100644 --- a/_locales/en/messages.json +++ b/_locales/en/messages.json @@ -59,6 +59,9 @@ "tab9": { "message": "CLI" }, + "tab10": { + "message": "Logging" + }, "serialPortOpened": { "message": "Serial port successfully opened with ID: $1" @@ -114,7 +117,7 @@ }, "defaultWelcomeText": { - "message": "This application is a configuration utility for baseflight, a 32 bit fork of the popular open source RC flight control firmware project MultiWii.

Application supports hardware that run Baseflight exclusively (acro naze, naze, afromini)

Official Resellers
AbuseMark - International (Japan)
Multirotor Superstore - International (United States)

The firmware source code can be downloaded from here
The newest binary firmware image is available here
" + "message": "This application is a configuration utility for baseflight, a 32 bit fork of the popular open source RC flight control firmware project MultiWii.

Application supports hardware that run Baseflight exclusively (acro naze, naze, afromini)

Official Resellers & Backers
AbuseMark - International (Japan)
Multirotor Superstore - International (United States)

The firmware source code can be downloaded from here
The newest binary firmware image is available here
" }, "defaultChangelogHead": { "message": "Configurator - Changelog" @@ -205,11 +208,23 @@ "message": "Info" }, "initialSetupBattery": { - "message": "Battery:" + "message": "Battery voltage:" }, "initialSetupBatteryValue": { "message": "$1 V" }, + "initialSetupDrawn": { + "message": "Capacity drawn:" + }, + "initialSetupDrawing": { + "message": "Current draw:" + }, + "initialSetupBatteryMahValue": { + "message": "$1 mAh" + }, + "initialSetupBatteryAValue": { + "message": "$1 A" + }, "initialSetupRSSI": { "message": "RSSI:" }, @@ -435,6 +450,37 @@ "message": "Write your command here" }, + "loggingNote": { + "message": "Data will be logged in this tab only, leaving the tab will cancel logging and application will return to its normal \"configurator\" state.
You are free to select the global update period, data will be written into the log file every 1 second for performance reasons." + }, + "loggingSamplesSaved": { + "message": "Samples Saved:" + }, + "loggingLogSize": { + "message": "Log Size:" + }, + "loggingKB": { + "message": "$1 kB" + }, + "loggingButtonLogFile": { + "message": "Select Log File" + }, + "loggingStart": { + "message": "Start Logging" + }, + "loggingStop": { + "message": "Stop Logging" + }, + "loggingErrorLogFile": { + "message": "Please select log file" + }, + "loggingErrorOneProperty": { + "message": "Please select at least one property to log" + }, + "loggingAutomaticallyRetained": { + "message": "Automatically loaded previous log file: $1" + }, + "firmwareFlasherPath": { "message": "Path:" }, diff --git a/changelog.html b/changelog.html index d73671b6..91ed65cb 100644 --- a/changelog.html +++ b/changelog.html @@ -1,3 +1,13 @@ +06.01.2014 - 0.41 +

+ - Configurator reached 4000+ users on 05.29.2014
+ - Support for new current sensing code (latest firmware)
+

+05.27.2014 - 0.40 +

+ - Added Logging tab (log various MSP data into CSV file)
+ - Bugfix for CLI input area
+

05.08.2014 - 0.39

- UI enhancements for sensors tab
diff --git a/js/backup_restore.js b/js/backup_restore.js index 599eecbb..f0343f97 100644 --- a/js/backup_restore.js +++ b/js/backup_restore.js @@ -2,35 +2,35 @@ function configuration_backup() { // request configuration data (one by one) function get_ident_data() { - send_message(MSP_codes.MSP_IDENT, false, false, get_status_data); + MSP.send_message(MSP_codes.MSP_IDENT, false, false, get_status_data); } function get_status_data() { - send_message(MSP_codes.MSP_STATUS, false, false, get_pid_data); + MSP.send_message(MSP_codes.MSP_STATUS, false, false, get_pid_data); } function get_pid_data() { - send_message(MSP_codes.MSP_PID, false, false, get_rc_tuning_data); + MSP.send_message(MSP_codes.MSP_PID, false, false, get_rc_tuning_data); } function get_rc_tuning_data() { - send_message(MSP_codes.MSP_RC_TUNING, false, false, get_box_names_data); + MSP.send_message(MSP_codes.MSP_RC_TUNING, false, false, get_box_names_data); } function get_box_names_data() { - send_message(MSP_codes.MSP_BOXNAMES, false, false, get_box_data); + MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, get_box_data); } function get_box_data() { - send_message(MSP_codes.MSP_BOX, false, false, get_acc_trim_data); + MSP.send_message(MSP_codes.MSP_BOX, false, false, get_acc_trim_data); } function get_acc_trim_data() { - send_message(MSP_codes.MSP_ACC_TRIM, false, false, get_misc_data); + MSP.send_message(MSP_codes.MSP_ACC_TRIM, false, false, get_misc_data); } function get_misc_data() { - send_message(MSP_codes.MSP_MISC, false, false, backup); + MSP.send_message(MSP_codes.MSP_MISC, false, false, backup); } function backup() { @@ -222,7 +222,7 @@ function configuration_upload() { } // Send over the PID changes - send_message(MSP_codes.MSP_SET_PID, PID_buffer_out, false, rc_tuning); + MSP.send_message(MSP_codes.MSP_SET_PID, PID_buffer_out, false, rc_tuning); function rc_tuning() { // RC Tuning section @@ -236,7 +236,7 @@ function configuration_upload() { RC_tuning_buffer_out[6] = parseInt(RC_tuning.throttle_EXPO * 100); // Send over the RC_tuning changes - send_message(MSP_codes.MSP_SET_RC_TUNING, RC_tuning_buffer_out, false, aux); + MSP.send_message(MSP_codes.MSP_SET_RC_TUNING, RC_tuning_buffer_out, false, aux); } function aux() { @@ -250,7 +250,7 @@ function configuration_upload() { } // Send over the AUX changes - send_message(MSP_codes.MSP_SET_BOX, AUX_val_buffer_out, false, trim); + MSP.send_message(MSP_codes.MSP_SET_BOX, AUX_val_buffer_out, false, trim); } // Trim section @@ -262,7 +262,7 @@ function configuration_upload() { buffer_out[3] = highByte(CONFIG.accelerometerTrims[1]); // Send over the new trims - send_message(MSP_codes.MSP_SET_ACC_TRIM, buffer_out, false, misc); + MSP.send_message(MSP_codes.MSP_SET_ACC_TRIM, buffer_out, false, misc); } function misc() { @@ -293,9 +293,9 @@ function configuration_upload() { buffer_out[21] = 0; // vbatlevel_crit (unused) // Send ove the new MISC - send_message(MSP_codes.MSP_SET_MISC, buffer_out, false, function() { + MSP.send_message(MSP_codes.MSP_SET_MISC, buffer_out, false, function() { // Save changes to EEPROM - send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { + MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('eeprom_saved_ok')); }); }); diff --git a/js/data_storage.js b/js/data_storage.js index 1541a636..3af5498a 100644 --- a/js/data_storage.js +++ b/js/data_storage.js @@ -78,7 +78,7 @@ var GPS_DATA = { var ANALOG = { voltage: 0, - pMeterSum: 0, + mAhdrawn: 0, rssi: 0, amperage: 0 }; diff --git a/js/gui.js b/js/gui.js index 733ccafe..0933c3e6 100644 --- a/js/gui.js +++ b/js/gui.js @@ -249,7 +249,7 @@ GUI_control.prototype.tab_switch_cleanup = function(callback) { buffer_out.push(highByte(MISC.mincommand)); } - send_message(MSP_codes.MSP_SET_MOTOR, buffer_out, false, function() { + MSP.send_message(MSP_codes.MSP_SET_MOTOR, buffer_out, false, function() { if (callback) callback(); }); } else { diff --git a/js/msp.js b/js/msp.js index a38afe7a..fea1fdc6 100644 --- a/js/msp.js +++ b/js/msp.js @@ -239,9 +239,9 @@ MSP.process_data = function(code, message_buffer, message_length) { break; case MSP_codes.MSP_ANALOG: ANALOG.voltage = data.getUint8(0) / 10.0; - ANALOG.power = data.getUint16(1, 1); + ANALOG.mAhdrawn = data.getUint16(1, 1); ANALOG.rssi = data.getUint16(3, 1); // 0-1023 - ANALOG.amperage = data.getUint16(5, 1); + ANALOG.amperage = data.getUint16(5, 1) / 100; // A break; case MSP_codes.MSP_RC_TUNING: RC_tuning.RC_RATE = parseFloat((data.getUint8(0) / 100).toFixed(2)); @@ -386,16 +386,16 @@ MSP.process_data = function(code, message_buffer, message_length) { // With new flight software settings in place, we have to re-pull // latest values - send_message(MSP_codes.MSP_IDENT); - send_message(MSP_codes.MSP_STATUS); - send_message(MSP_codes.MSP_PID); - send_message(MSP_codes.MSP_RC_TUNING); - send_message(MSP_codes.MSP_BOXNAMES); - send_message(MSP_codes.MSP_BOX); + MSP.send_message(MSP_codes.MSP_IDENT); + MSP.send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSP_codes.MSP_PID); + MSP.send_message(MSP_codes.MSP_RC_TUNING); + MSP.send_message(MSP_codes.MSP_BOXNAMES); + MSP.send_message(MSP_codes.MSP_BOX); // baseflight specific - send_message(MSP_codes.MSP_UID); - send_message(MSP_codes.MSP_ACC_TRIM); + MSP.send_message(MSP_codes.MSP_UID); + MSP.send_message(MSP_codes.MSP_ACC_TRIM); break; case MSP_codes.MSP_SELECT_SETTING: console.log('Profile selected'); @@ -466,7 +466,7 @@ MSP.process_data = function(code, message_buffer, message_length) { } }; -function send_message(code, data, callback_sent, callback_msp) { +MSP.send_message = function(code, data, callback_sent, callback_msp) { var bufferOut; var bufView; diff --git a/js/serial_backend.js b/js/serial_backend.js index 1166f957..f03d96a0 100644 --- a/js/serial_backend.js +++ b/js/serial_backend.js @@ -137,9 +137,9 @@ function onOpen(openInfo) { }, 10000); // request configuration data - send_message(MSP_codes.MSP_UID, false, false, function() { + MSP.send_message(MSP_codes.MSP_UID, false, false, function() { GUI.log(chrome.i18n.getMessage('uniqueDeviceIdReceived', [CONFIG.uid[0].toString(16) + CONFIG.uid[1].toString(16) + CONFIG.uid[2].toString(16)])); - send_message(MSP_codes.MSP_IDENT, false, false, function() { + MSP.send_message(MSP_codes.MSP_IDENT, false, false, function() { GUI.timeout_remove('connecting'); // kill connecting timer GUI.log(chrome.i18n.getMessage('firmwareVersion', [CONFIG.version])); diff --git a/main.html b/main.html index cb398094..5d857a29 100644 --- a/main.html +++ b/main.html @@ -16,6 +16,7 @@ + @@ -44,6 +45,7 @@ + @@ -105,6 +107,7 @@

  • +
  • diff --git a/main.js b/main.js index 64b88e80..37af0a8a 100644 --- a/main.js +++ b/main.js @@ -102,6 +102,9 @@ $(document).ready(function() { case 'tab_cli': tab_initialize_cli(); break; + case 'tab_logging': + tab_initialize_logging(); + break; } }); } diff --git a/manifest.json b/manifest.json index 6c55b96c..450a3462 100644 --- a/manifest.json +++ b/manifest.json @@ -1,7 +1,7 @@ { "manifest_version": 2, "minimum_chrome_version": "33", - "version": "0.39", + "version": "0.41", "author": "Hydra", "name": "Cleanflight - Configurator", @@ -26,10 +26,11 @@ "storage", "fileSystem", "fileSystem.write", + "fileSystem.retainEntries", "notifications" ], "icons": { "128": "images/icon_128.png" } -} \ No newline at end of file +} diff --git a/tabs/auxiliary_configuration.js b/tabs/auxiliary_configuration.js index eddea536..c6be127f 100644 --- a/tabs/auxiliary_configuration.js +++ b/tabs/auxiliary_configuration.js @@ -2,10 +2,10 @@ function tab_initialize_auxiliary_configuration() { ga_tracker.sendAppView('Auxiliary Configuration'); GUI.active_tab = 'auxiliary_configuration'; - send_message(MSP_codes.MSP_BOXNAMES, false, false, get_box_data); + MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, get_box_data); function get_box_data() { - send_message(MSP_codes.MSP_BOX, false, false, load_html); + MSP.send_message(MSP_codes.MSP_BOX, false, false, load_html); } function load_html() { @@ -94,10 +94,10 @@ function tab_initialize_auxiliary_configuration() { AUX_val_buffer_out[needle++] = highByte(AUX_CONFIG_values[i]); } - send_message(MSP_codes.MSP_SET_BOX, AUX_val_buffer_out, false, save_to_eeprom); + MSP.send_message(MSP_codes.MSP_SET_BOX, AUX_val_buffer_out, false, save_to_eeprom); function save_to_eeprom() { - send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { + MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('auxiliaryEepromSaved')); var element = $('a.update'); @@ -112,7 +112,7 @@ function tab_initialize_auxiliary_configuration() { // data pulling functions used inside interval timer function get_rc_data() { - send_message(MSP_codes.MSP_RC, false, false, update_ui); + MSP.send_message(MSP_codes.MSP_RC, false, false, update_ui); } function update_ui() { @@ -139,7 +139,7 @@ function tab_initialize_auxiliary_configuration() { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function() { - send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSP_codes.MSP_STATUS); }, 250, true); } } \ No newline at end of file diff --git a/tabs/cli.css b/tabs/cli.css index 5f15e023..093e9ee4 100644 --- a/tabs/cli.css +++ b/tabs/cli.css @@ -29,7 +29,7 @@ margin-top: 8px; - height: 20px; + height: 22px; line-height: 20px; padding-left: 5px; diff --git a/tabs/cli.html b/tabs/cli.html index 1c6aa5ed..3c9c585e 100644 --- a/tabs/cli.html +++ b/tabs/cli.html @@ -5,5 +5,5 @@
    - + \ No newline at end of file diff --git a/tabs/cli.js b/tabs/cli.js index 8ba21c89..a58a1c80 100644 --- a/tabs/cli.js +++ b/tabs/cli.js @@ -43,18 +43,21 @@ function tab_initialize_cli() { serial.send(bufferOut, function(writeInfo) {}); var textarea = $('.tab-cli textarea'); + textarea.keypress(function(event) { if (event.which == 13) { // enter - var out_string = $('.tab-cli textarea').val(); + event.preventDefault(); // prevent the adding of new line + + var out_string = textarea.val(); var out_arr = out_string.split("\n"); cli_history.add(out_string.trim()); - var timeout_needle = 0; + var timeout_needle = 0; for (var i = 0; i < out_arr.length; i++) { send_slowly(out_arr, i, timeout_needle++); } - $('.tab-cli textarea').val(''); + textarea.val(''); } }); @@ -69,7 +72,7 @@ function tab_initialize_cli() { }); // give input element user focus - $('.tab-cli textarea').focus(); + textarea.focus(); }); } diff --git a/tabs/gps.js b/tabs/gps.js index c7b354b7..2a1a9725 100644 --- a/tabs/gps.js +++ b/tabs/gps.js @@ -2,7 +2,7 @@ function tab_initialize_gps () { ga_tracker.sendAppView('GPS Page'); GUI.active_tab = 'gps'; - send_message(MSP_codes.MSP_RAW_GPS, false, false, load_html); + MSP.send_message(MSP_codes.MSP_RAW_GPS, false, false, load_html); function load_html() { $('#content').load("./tabs/gps.html", process_html); @@ -13,16 +13,16 @@ function tab_initialize_gps () { localize(); function get_raw_gps_data() { - send_message(MSP_codes.MSP_RAW_GPS, false, false, get_gpsvinfo_data); + MSP.send_message(MSP_codes.MSP_RAW_GPS, false, false, get_gpsvinfo_data); } function get_gpsvinfo_data() { - send_message(MSP_codes.MSP_GPSSVINFO, false, false, update_ui); + MSP.send_message(MSP_codes.MSP_GPSSVINFO, false, false, update_ui); } function update_ui() { - var lat = GPS_DATA.lat / 100000000; - var lon = GPS_DATA.lon / 100000000; + var lat = GPS_DATA.lat / 10000000; + var lon = GPS_DATA.lon / 10000000; var url = 'https://maps.google.com/?q=' + lat + ',' + lon; $('.GPS_info td.fix').html((GPS_DATA.fix) ? chrome.i18n.getMessage('gpsFixTrue') : chrome.i18n.getMessage('gpsFixFalse')); @@ -50,7 +50,7 @@ function tab_initialize_gps () { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function() { - send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSP_codes.MSP_STATUS); }, 250, true); } } \ No newline at end of file diff --git a/tabs/initial_setup.css b/tabs/initial_setup.css index f54784c3..32509333 100644 --- a/tabs/initial_setup.css +++ b/tabs/initial_setup.css @@ -298,16 +298,16 @@ .tab-initial_setup .info dt { float: left; - width: 50px; + width: 100px; height: 20px; line-height: 20px; } .tab-initial_setup .info dd { - width: 40px; + width: 70px; height: 20px; line-height: 20px; - margin-left: 50px; + margin-left: 100px; } .tab-initial_setup .update { display: block; diff --git a/tabs/initial_setup.html b/tabs/initial_setup.html index 1fb60ee2..a38e6c2d 100644 --- a/tabs/initial_setup.html +++ b/tabs/initial_setup.html @@ -71,6 +71,17 @@
    +
    + +
    +
    +
    0 V
    +
    0 mAh
    +
    0 A
    +
    0 %
    +
    +
    +
    @@ -80,14 +91,5 @@
    -
    - -
    -
    -
    0 V
    -
    0 %
    -
    -
    -
    \ No newline at end of file diff --git a/tabs/initial_setup.js b/tabs/initial_setup.js index 0458e9bd..cb5ce0d8 100644 --- a/tabs/initial_setup.js +++ b/tabs/initial_setup.js @@ -2,14 +2,14 @@ function tab_initialize_initial_setup() { ga_tracker.sendAppView('Initial Setup'); GUI.active_tab = 'initial_setup'; - send_message(MSP_codes.MSP_ACC_TRIM, false, false, load_ident); + MSP.send_message(MSP_codes.MSP_ACC_TRIM, false, false, load_ident); function load_ident() { - send_message(MSP_codes.MSP_IDENT, false, false, load_misc_data); + MSP.send_message(MSP_codes.MSP_IDENT, false, false, load_misc_data); } function load_misc_data() { - send_message(MSP_codes.MSP_MISC, false, false, load_html); + MSP.send_message(MSP_codes.MSP_MISC, false, false, load_html); } function load_html() { @@ -114,7 +114,7 @@ function tab_initialize_initial_setup() { // During this period MCU won't be able to process any serial commands because its locked in a for/while loop // until this operation finishes, sending more commands through data_poll() will result in serial buffer overflow GUI.interval_pause('initial_setup_data_pull'); - send_message(MSP_codes.MSP_ACC_CALIBRATION, false, false, function() { + MSP.send_message(MSP_codes.MSP_ACC_CALIBRATION, false, false, function() { GUI.log(chrome.i18n.getMessage('initialSetupAccelCalibStarted')); }); @@ -134,7 +134,7 @@ function tab_initialize_initial_setup() { if (!self.hasClass('calibrating')) { self.addClass('calibrating'); - send_message(MSP_codes.MSP_MAG_CALIBRATION, false, false, function() { + MSP.send_message(MSP_codes.MSP_MAG_CALIBRATION, false, false, function() { GUI.log(chrome.i18n.getMessage('initialSetupMagCalibStarted')); }); @@ -146,7 +146,7 @@ function tab_initialize_initial_setup() { }); $('a.resetSettings').click(function() { - send_message(MSP_codes.MSP_RESET_CONF, false, false, function() { + MSP.send_message(MSP_codes.MSP_RESET_CONF, false, false, function() { GUI.log(chrome.i18n.getMessage('initialSetupSettingsRestored')); GUI.tab_switch_cleanup(function() { @@ -167,7 +167,7 @@ function tab_initialize_initial_setup() { buffer_out[3] = highByte(CONFIG.accelerometerTrims[1]); // Send over the new trims - send_message(MSP_codes.MSP_SET_ACC_TRIM, buffer_out); + MSP.send_message(MSP_codes.MSP_SET_ACC_TRIM, buffer_out); MISC.vbatmincellvoltage = parseFloat($('input[name="mincellvoltage"]').val()) * 10; MISC.vbatmaxcellvoltage = parseFloat($('input[name="maxcellvoltage"]').val()) * 10; @@ -206,10 +206,10 @@ function tab_initialize_initial_setup() { buffer_out[21] = 0; // vbatlevel_crit (unused) // Send over new misc - send_message(MSP_codes.MSP_SET_MISC, buffer_out, false, save_to_eeprom); + MSP.send_message(MSP_codes.MSP_SET_MISC, buffer_out, false, save_to_eeprom); function save_to_eeprom() { - send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { + MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('initialSetupEepromSaved')); var element = $('a.update'); @@ -234,16 +234,18 @@ function tab_initialize_initial_setup() { // data pulling functions used inside interval timer function get_analog_data() { - send_message(MSP_codes.MSP_ANALOG, false, false, get_attitude_data); + MSP.send_message(MSP_codes.MSP_ANALOG, false, false, get_attitude_data); } function get_attitude_data() { - send_message(MSP_codes.MSP_ATTITUDE, false, false, update_ui); + MSP.send_message(MSP_codes.MSP_ATTITUDE, false, false, update_ui); } function update_ui() { // Update voltage indicator $('.bat-voltage').text(chrome.i18n.getMessage('initialSetupBatteryValue', [ANALOG.voltage])); + $('.bat-mah-drawn').text(chrome.i18n.getMessage('initialSetupBatteryMahValue', [ANALOG.mAhdrawn])); + $('.bat-mah-drawing').text(chrome.i18n.getMessage('initialSetupBatteryAValue', [ANALOG.amperage.toFixed(2)])); $('.rssi').text(chrome.i18n.getMessage('initialSetupRSSIValue', [((ANALOG.rssi / 1023) * 100).toFixed(0)])); // Update cube @@ -258,7 +260,7 @@ function tab_initialize_initial_setup() { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function() { - send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSP_codes.MSP_STATUS); }, 250, true); } } \ No newline at end of file diff --git a/tabs/logging.css b/tabs/logging.css new file mode 100644 index 00000000..d393f8d6 --- /dev/null +++ b/tabs/logging.css @@ -0,0 +1,73 @@ +.tab-logging { +} + .tab-logging .note { + padding: 5px; + border: 1px dashed silver; + } + .tab-logging .properties { + margin-top: 10px; + } + .tab-logging .properties dt { + float: left; + width: 120px; + height: 20px; + line-height: 20px; + + font-weight: bold; + } + .tab-logging .properties dt input { + vertical-align: middle; + } + .tab-logging .properties dd { + display: block; + margin-left: 130px; + height: 20px; + line-height: 20px; + color: silver; + } + .tab-logging .speed { + margin-top: 5px; + width: 80px; + + border: 1px solid silver; + } + .tab-logging .info { + margin-top: 10px; + } + .tab-logging .info dt { + float: left; + width: 120px; + height: 20px; + line-height: 20px; + + font-weight: bold; + } + .tab-logging .info dd { + display: block; + margin-left: 130px; + height: 20px; + line-height: 20px; + } + .tab-logging .buttons { + margin-top: 10px; + } + .tab-logging .buttons a { + display: block; + float: left; + + margin-right: 10px; + + height: 28px; + line-height: 28px; + + padding: 0 15px 0 15px; + + text-align: center; + font-weight: bold; + + border: 1px solid silver; + background-color: #ececec; + } + .tab-logging .buttons a:hover { + background-color: #dedcdc; + } diff --git a/tabs/logging.html b/tabs/logging.html new file mode 100644 index 00000000..5b6c715b --- /dev/null +++ b/tabs/logging.html @@ -0,0 +1,38 @@ +
    +
    +
    +
    +
    +
    9 columns (accel[x, y, z], gyro[x, y, z], mag[x, y, z])
    +
    3 columns (x, y, z)
    +
    one column
    +
    7 columns
    +
    8 columns by default
    +
    8 columns by default
    +
    4 columns
    +
    +
    + +
    +
    +
    0
    +
    0 kB
    +
    +
    +
    + + +
    +
    \ No newline at end of file diff --git a/tabs/logging.js b/tabs/logging.js new file mode 100644 index 00000000..ea453700 --- /dev/null +++ b/tabs/logging.js @@ -0,0 +1,282 @@ +function tab_initialize_logging() { + ga_tracker.sendAppView('Logging'); + GUI.active_tab = 'logging'; + + var requested_properties = []; + + MSP.send_message(MSP_codes.MSP_RC, false, false, get_motor_data); + + function get_motor_data() { + MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html); + } + + function load_html() { + $('#content').load("./tabs/logging.html", process_html); + } + + function process_html() { + // translate to user-selected language + localize(); + + // UI hooks + $('a.log_file').click(prepare_file); + + $('a.logging').click(function() { + if (fileEntry != null) { + var clicks = $(this).data('clicks'); + + if (!clicks) { + // reset some variables before start + samples = 0; + log_buffer = []; + requested_properties = []; + + $('.properties input:checked').each(function() { + requested_properties.push($(this).prop('name')); + }); + + if (requested_properties.length) { + // print header for the + print_head(); + + function poll_data() { + // save current + crunch_data(); + + // request new + for (var i = 0; i < requested_properties.length; i++) { + MSP.send_message(MSP_codes[requested_properties[i]]); + + /* this approach could be used if we want to utilize request time compensation + if (i < requested_properties.length -1) { + MSP.send_message(requested_properties[i]); + } else { + MSP.send_message(requested_properties[i], false, false, poll_data); + } + */ + } + } + + GUI.interval_add('log_data_pull', poll_data, parseInt($('select.speed').val()), true); // refresh rate goes here + GUI.interval_add('flush_data', function() { + if (log_buffer.length) { // only execute when there is actual data to write + if (fileWriter.readyState == 0 || fileWriter.readyState == 2) { + append_to_file(log_buffer.join('\n')); + + $('.samples').text(samples += log_buffer.length); + $('.size').text(chrome.i18n.getMessage('loggingKB', [(fileWriter.length / 1024).toFixed(2)])); + + log_buffer = []; + } else { + console.log('IO having trouble keeping up with the data flow'); + } + } + }, 1000); + + $('.speed').prop('disabled', true); + $(this).text(chrome.i18n.getMessage('loggingStop')); + $(this).data("clicks", !clicks); + } else { + GUI.log(chrome.i18n.getMessage('loggingErrorOneProperty')); + } + } else { + GUI.interval_remove('log_data_pull'); + GUI.interval_remove('flush_data'); + + $('.speed').prop('disabled', false); + $(this).text(chrome.i18n.getMessage('loggingStart')); + $(this).data("clicks", !clicks); + } + } else { + GUI.log(chrome.i18n.getMessage('loggingErrorLogFile')); + } + }); + + chrome.storage.local.get('logging_file_entry', function(result) { + if (result.logging_file_entry) { + chrome.fileSystem.restoreEntry(result.logging_file_entry, function(entry) { + fileEntry = entry; + prepare_writer(true); + }); + } + }); + } + + var samples = 0; + var log_buffer = []; + function crunch_data() { + var sample = millitime(); + + for (var i = 0; i < requested_properties.length; i++) { + switch (requested_properties[i]) { + case 'MSP_RAW_IMU': + sample += ',' + SENSOR_DATA.gyroscope; + sample += ',' + SENSOR_DATA.accelerometer; + sample += ',' + SENSOR_DATA.magnetometer; + break; + case 'MSP_ATTITUDE': + sample += ',' + SENSOR_DATA.kinematicsX; + sample += ',' + SENSOR_DATA.kinematicsY; + sample += ',' + SENSOR_DATA.kinematicsZ; + break; + case 'MSP_ALTITUDE': + sample += ',' + SENSOR_DATA.altitude; + break; + case 'MSP_RAW_GPS': + sample += ',' + GPS_DATA.fix; + sample += ',' + GPS_DATA.numSat; + sample += ',' + (GPS_DATA.lat / 10000000); + sample += ',' + (GPS_DATA.lon / 10000000); + sample += ',' + GPS_DATA.alt; + sample += ',' + GPS_DATA.speed; + sample += ',' + GPS_DATA.ground_course; + break; + case 'MSP_RC': + for (var chan = 0; chan < RC.active_channels; chan++) { + sample += ',' + RC.channels[chan]; + } + break; + case 'MSP_MOTOR': + sample += ',' + MOTOR_DATA; + break; + case 'MSP_DEBUG': + sample += ',' + SENSOR_DATA.debug; + break; + } + } + + log_buffer.push(sample); + } + + function print_head() { + var head = "timestamp"; + + for (var i = 0; i < requested_properties.length; i++) { + switch (requested_properties[i]) { + case 'MSP_RAW_IMU': + head += ',' + 'gyroscopeX'; + head += ',' + 'gyroscopeY'; + head += ',' + 'gyroscopeZ'; + + head += ',' + 'accelerometerX'; + head += ',' + 'accelerometerY'; + head += ',' + 'accelerometerZ'; + + head += ',' + 'magnetometerX'; + head += ',' + 'magnetometerY'; + head += ',' + 'magnetometerZ'; + break; + case 'MSP_ATTITUDE': + head += ',' + 'kinematicsX'; + head += ',' + 'kinematicsY'; + head += ',' + 'kinematicsZ'; + break; + case 'MSP_ALTITUDE': + head += ',' + 'altitude'; + break; + case 'MSP_RAW_GPS': + head += ',' + 'gpsFix'; + head += ',' + 'gpsNumSat'; + head += ',' + 'gpsLat'; + head += ',' + 'gpsLon'; + head += ',' + 'gpsAlt'; + head += ',' + 'gpsSpeed'; + head += ',' + 'gpsGroundCourse'; + break; + case 'MSP_RC': + for (var chan = 0; chan < RC.active_channels; chan++) { + head += ',' + 'RC' + chan; + } + break; + case 'MSP_MOTOR': + for (var motor = 0; motor < MOTOR_DATA.length; motor++) { + head += ',' + 'Motor' + motor; + } + break; + case 'MSP_DEBUG': + for (var debug = 0; debug < SENSOR_DATA.debug.length; debug++) { + head += ',' + 'Debug' + debug; + } + break; + } + } + + log_buffer.push(head); + } + + // IO related methods + var fileEntry = null; + var fileWriter = null; + + function prepare_file() { + // create or load the file + chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: 'bf_data_log', accepts: [{extensions: ['csv']}]}, function(entry) { + if (!entry) { + console.log('No file selected'); + return; + } + + fileEntry = entry; + + // echo/console log path specified + chrome.fileSystem.getDisplayPath(fileEntry, function(path) { + console.log('Log file path: ' + path); + }); + + // change file entry from read only to read/write + chrome.fileSystem.getWritableEntry(fileEntry, function(fileEntryWritable) { + // check if file is writable + chrome.fileSystem.isWritableEntry(fileEntryWritable, function(isWritable) { + if (isWritable) { + fileEntry = fileEntryWritable; + + // save entry for next use + chrome.storage.local.set({'logging_file_entry': chrome.fileSystem.retainEntry(fileEntry)}); + + prepare_writer(); + } else { + console.log('File appears to be read only, sorry.'); + } + }); + }); + }); + } + + function prepare_writer(retaining) { + fileEntry.createWriter(function(writer) { + fileWriter = writer; + + fileWriter.onerror = function(e) { + console.error(e); + + // stop logging if the procedure was/is still running + if ($('a.logging').data('clicks')) $('a.logging').click(); + }; + + fileWriter.onwriteend = function() { + // console.log('Data written'); + }; + + if (retaining) { + chrome.fileSystem.getDisplayPath(fileEntry, function(path) { + GUI.log(chrome.i18n.getMessage('loggingAutomaticallyRetained', [path])); + }); + } + }, function(e) { + // File is not readable or does not exist! + console.error(e); + + if (retaining) { + fileEntry = null; + } + }); + } + + function append_to_file(data) { + if (fileWriter.position < fileWriter.length) { + fileWriter.seek(fileWriter.length); + } + + fileWriter.write(new Blob([data + '\n'], {type: 'text/plain'})); + } +} \ No newline at end of file diff --git a/tabs/motor_outputs.js b/tabs/motor_outputs.js index b09f7194..91eed6b3 100644 --- a/tabs/motor_outputs.js +++ b/tabs/motor_outputs.js @@ -2,10 +2,10 @@ function tab_initialize_motor_outputs() { ga_tracker.sendAppView('Motor Outputs Page'); GUI.active_tab = 'motor_outputs'; - send_message(MSP_codes.MSP_MISC, false, false, get_motor_data); + MSP.send_message(MSP_codes.MSP_MISC, false, false, get_motor_data); function get_motor_data() { - send_message(MSP_codes.MSP_MOTOR, false, false, load_html); + MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html); } function load_html() { @@ -48,7 +48,7 @@ function tab_initialize_motor_outputs() { buffer_out.push(highByte(val)); } - send_message(MSP_codes.MSP_SET_MOTOR, buffer_out); + MSP.send_message(MSP_codes.MSP_SET_MOTOR, buffer_out); }); $('div.sliders input.master').on('input', function() { @@ -80,11 +80,11 @@ function tab_initialize_motor_outputs() { // data pulling functions used inside interval timer function get_motor_data() { - send_message(MSP_codes.MSP_MOTOR, false, false, get_servo_data); + MSP.send_message(MSP_codes.MSP_MOTOR, false, false, get_servo_data); } function get_servo_data() { - send_message(MSP_codes.MSP_SERVO, false, false, update_ui); + MSP.send_message(MSP_codes.MSP_SERVO, false, false, update_ui); } function update_ui() { @@ -114,7 +114,7 @@ function tab_initialize_motor_outputs() { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function() { - send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSP_codes.MSP_STATUS); }, 250, true); } } \ No newline at end of file diff --git a/tabs/pid_tuning.js b/tabs/pid_tuning.js index a298b5de..0d0e9cab 100644 --- a/tabs/pid_tuning.js +++ b/tabs/pid_tuning.js @@ -3,18 +3,18 @@ function tab_initialize_pid_tuning() { GUI.active_tab = 'pid_tuning'; // requesting MSP_STATUS manually because it contains CONFIG.profile - send_message(MSP_codes.MSP_STATUS, false, false, get_pid_names); + MSP.send_message(MSP_codes.MSP_STATUS, false, false, get_pid_names); function get_pid_names() { - send_message(MSP_codes.MSP_PIDNAMES, false, false, get_pid_data); + MSP.send_message(MSP_codes.MSP_PIDNAMES, false, false, get_pid_data); } function get_pid_data() { - send_message(MSP_codes.MSP_PID, false, false, get_rc_tuning_data); + MSP.send_message(MSP_codes.MSP_PID, false, false, get_rc_tuning_data); } function get_rc_tuning_data() { - send_message(MSP_codes.MSP_RC_TUNING, false, false, load_html); + MSP.send_message(MSP_codes.MSP_RC_TUNING, false, false, load_html); } function load_html() { @@ -180,7 +180,7 @@ function tab_initialize_pid_tuning() { // UI Hooks $('input[name="profile"]').change(function() { var profile = parseInt($(this).val()); - send_message(MSP_codes.MSP_SELECT_SETTING, [profile - 1], false, function() { + MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [profile - 1], false, function() { GUI.log(chrome.i18n.getMessage('pidTuningLoadedProfile', [profile])); GUI.tab_switch_cleanup(tab_initialize_pid_tuning); @@ -276,7 +276,7 @@ function tab_initialize_pid_tuning() { } // Send over the PID changes - send_message(MSP_codes.MSP_SET_PID, PID_buffer_out, false, send_rc_tuning_changes); + MSP.send_message(MSP_codes.MSP_SET_PID, PID_buffer_out, false, send_rc_tuning_changes); function send_rc_tuning_changes() { // catch RC_tuning changes @@ -294,11 +294,11 @@ function tab_initialize_pid_tuning() { RC_tuning_buffer_out[6] = parseInt(RC_tuning.throttle_EXPO * 100); // Send over the RC_tuning changes - send_message(MSP_codes.MSP_SET_RC_TUNING, RC_tuning_buffer_out, false, save_to_eeprom); + MSP.send_message(MSP_codes.MSP_SET_RC_TUNING, RC_tuning_buffer_out, false, save_to_eeprom); } function save_to_eeprom() { - send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { + MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('pidTuningEepromSaved')); var element = $('a.update'); @@ -313,7 +313,7 @@ function tab_initialize_pid_tuning() { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function() { - send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSP_codes.MSP_STATUS); }, 250, true); } } \ No newline at end of file diff --git a/tabs/receiver.js b/tabs/receiver.js index f6ca73bf..0a7e7cd1 100644 --- a/tabs/receiver.js +++ b/tabs/receiver.js @@ -2,10 +2,10 @@ function tab_initialize_receiver() { ga_tracker.sendAppView('Receiver Page'); GUI.active_tab = 'receiver'; - send_message(MSP_codes.MSP_RC_TUNING, false, false, get_rc_data); + MSP.send_message(MSP_codes.MSP_RC_TUNING, false, false, get_rc_data); function get_rc_data() { - send_message(MSP_codes.MSP_RC, false, false, load_html); + MSP.send_message(MSP_codes.MSP_RC, false, false, load_html); } function load_html() { @@ -32,26 +32,21 @@ function tab_initialize_receiver() { }); // generate bars - var bar_names = [ - 'Roll', - 'Pitch', - 'Yaw', - 'Throttle', - 'AUX 1', - 'AUX 2', - 'AUX 3', - 'AUX 4', - 'AUX 5', - 'AUX 6', - 'AUX 7', - 'AUX 8' - ]; - + var bar_names = ['Roll', 'Pitch', 'Yaw', 'Throttle']; var bar_container = $('.tab-receiver .bars'); + var aux_index = 1; + for (var i = 0; i < RC.active_channels; i++) { + var name; + if (i < bar_names.length) { + name = bar_names[i]; + } else { + name = 'AUX ' + aux_index++; + } + bar_container.append('\ \ @@ -120,7 +115,7 @@ function tab_initialize_receiver() { }).change(); $('a.refresh').click(function() { - send_message(MSP_codes.MSP_RC_TUNING, false, false, function() { + MSP.send_message(MSP_codes.MSP_RC_TUNING, false, false, function() { GUI.log(chrome.i18n.getMessage('receiverDataRefreshed')); // fill in data from RC_tuning @@ -154,10 +149,10 @@ function tab_initialize_receiver() { RC_tuning_buffer_out[6] = parseInt(RC_tuning.throttle_EXPO * 100, 10); // Send over the RC_tuning changes - send_message(MSP_codes.MSP_SET_RC_TUNING, RC_tuning_buffer_out, false, save_to_eeprom); + MSP.send_message(MSP_codes.MSP_SET_RC_TUNING, RC_tuning_buffer_out, false, save_to_eeprom); function save_to_eeprom() { - send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { + MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('receiverEepromSaved')); var element = $('a.update'); @@ -177,7 +172,7 @@ function tab_initialize_receiver() { chrome.storage.local.set({'rx_refresh_rate': plot_update_rate}); function get_rc_data() { - send_message(MSP_codes.MSP_RC, false, false, update_ui); + MSP.send_message(MSP_codes.MSP_RC, false, false, update_ui); } // setup plot @@ -276,7 +271,7 @@ function tab_initialize_receiver() { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function() { - send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSP_codes.MSP_STATUS); }, 250, true); } } diff --git a/tabs/sensors.js b/tabs/sensors.js index 116383d2..1bca3963 100644 --- a/tabs/sensors.js +++ b/tabs/sensors.js @@ -333,19 +333,19 @@ function tab_initialize_sensors() { // data pulling timers if (checkboxes[0] || checkboxes[1] || checkboxes[2]) { GUI.interval_add('IMU_pull', function imu_data_pull() { - send_message(MSP_codes.MSP_RAW_IMU, false, false, update_imu_graphs); + MSP.send_message(MSP_codes.MSP_RAW_IMU, false, false, update_imu_graphs); }, fastest, true); } if (checkboxes[3]) { GUI.interval_add('altitude_pull', function altitude_data_pull() { - send_message(MSP_codes.MSP_ALTITUDE, false, false, update_altitude_graph); + MSP.send_message(MSP_codes.MSP_ALTITUDE, false, false, update_altitude_graph); }, rates.baro, true); } if (checkboxes[4]) { GUI.interval_add('debug_pull', function debug_data_pull() { - send_message(MSP_codes.MSP_DEBUG, false, false, update_debug_graphs); + MSP.send_message(MSP_codes.MSP_DEBUG, false, false, update_debug_graphs); }, rates.debug, true); } @@ -403,7 +403,7 @@ function tab_initialize_sensors() { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function() { - send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSP_codes.MSP_STATUS); }, 250, true); }); } diff --git a/tabs/servos.js b/tabs/servos.js index 64f38801..8d3320d6 100644 --- a/tabs/servos.js +++ b/tabs/servos.js @@ -9,14 +9,14 @@ function tab_initialize_servos() { ga_tracker.sendAppView('Servos'); GUI.active_tab = 'servos'; - send_message(MSP_codes.MSP_IDENT, false, false, get_servo_conf_data); + MSP.send_message(MSP_codes.MSP_IDENT, false, false, get_servo_conf_data); function get_servo_conf_data() { - send_message(MSP_codes.MSP_SERVO_CONF, false, false, get_boxnames_data); + MSP.send_message(MSP_codes.MSP_SERVO_CONF, false, false, get_boxnames_data); } function get_boxnames_data() { - send_message(MSP_codes.MSP_BOXNAMES, false, false, load_html); + MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, load_html); } function load_html() { @@ -175,11 +175,11 @@ function tab_initialize_servos() { buffer_out[needle++] = lowByte(SERVO_CONFIG[i].rate); } - send_message(MSP_codes.MSP_SET_SERVO_CONF, buffer_out); + MSP.send_message(MSP_codes.MSP_SET_SERVO_CONF, buffer_out); if (save_to_eeprom) { // Save changes to EEPROM - send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { + MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('servosEepromSave')); var element = $('a.update'); @@ -300,7 +300,7 @@ function tab_initialize_servos() { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function() { - send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSP_codes.MSP_STATUS); }, 250, true); } } \ No newline at end of file