diff --git a/tabs/auxiliary_configuration.js b/tabs/auxiliary_configuration.js index 540e7331..38d9e171 100644 --- a/tabs/auxiliary_configuration.js +++ b/tabs/auxiliary_configuration.js @@ -2,125 +2,140 @@ function tab_initialize_auxiliary_configuration() { ga_tracker.sendAppView('Auxiliary Configuration'); GUI.active_tab = 'auxiliary_configuration'; - send_message(MSP_codes.MSP_BOXNAMES, MSP_codes.MSP_BOXNAMES, false, function() { - send_message(MSP_codes.MSP_BOX, MSP_codes.MSP_BOX, false, function() { - $('#content').load("./tabs/auxiliary_configuration.html", function() { - // generate table from the supplied AUX names and AUX data - for (var i = 0; i < AUX_CONFIG.length; i++) { - $('.boxes > tbody:last').append( - '' + - '' + AUX_CONFIG[i] + '' + - box_check(AUX_CONFIG_values[i], 0) + - box_check(AUX_CONFIG_values[i], 1) + - box_check(AUX_CONFIG_values[i], 2) + + send_message(MSP_codes.MSP_BOXNAMES, MSP_codes.MSP_BOXNAMES, false, get_box_data); - box_check(AUX_CONFIG_values[i], 3) + - box_check(AUX_CONFIG_values[i], 4) + - box_check(AUX_CONFIG_values[i], 5) + + function get_box_data() { + send_message(MSP_codes.MSP_BOX, MSP_codes.MSP_BOX, false, load_html); + } - box_check(AUX_CONFIG_values[i], 6) + - box_check(AUX_CONFIG_values[i], 7) + - box_check(AUX_CONFIG_values[i], 8) + + function load_html() { + $('#content').load("./tabs/auxiliary_configuration.html", process_html); + } - box_check(AUX_CONFIG_values[i], 9) + - box_check(AUX_CONFIG_values[i], 10) + - box_check(AUX_CONFIG_values[i], 11) + - '' - ); + function process_html() { + function box_check(num, pos) { + if (bit_check(num, pos)) { // 1 + return ''; + } else { // 0 + return ''; + } + } + + // val = channel value + // aux_num = position of corresponding aux channel in the html table + function box_highlight(val, aux_num) { + var tr = $('table.boxes tr'); + var pos = 0; // < 1300 + + if (val > 1300 && val < 1700) { + pos = 1; + } else if (val > 1700) { + pos = 2; + } + + $(':nth-child(' + aux_num + '), :nth-child(' + (aux_num + 1) + '), :nth-child(' + (aux_num + 2) + ')', tr).css('background-color', 'transparent'); + $('td:nth-child(' + (aux_num + pos) + ')', tr).css('background-color', 'orange'); + } + + // generate table from the supplied AUX names and AUX data + for (var i = 0; i < AUX_CONFIG.length; i++) { + $('.boxes > tbody:last').append( + '' + + '' + AUX_CONFIG[i] + '' + + box_check(AUX_CONFIG_values[i], 0) + + box_check(AUX_CONFIG_values[i], 1) + + box_check(AUX_CONFIG_values[i], 2) + + + box_check(AUX_CONFIG_values[i], 3) + + box_check(AUX_CONFIG_values[i], 4) + + box_check(AUX_CONFIG_values[i], 5) + + + box_check(AUX_CONFIG_values[i], 6) + + box_check(AUX_CONFIG_values[i], 7) + + box_check(AUX_CONFIG_values[i], 8) + + + box_check(AUX_CONFIG_values[i], 9) + + box_check(AUX_CONFIG_values[i], 10) + + box_check(AUX_CONFIG_values[i], 11) + + '' + ); + } + + // UI Hooks + $('a.update').click(function() { + // catch the input changes + var main_needle = 0; + var needle = 0; + $('.boxes input').each(function() { + if ($(this).is(':checked')) { + AUX_CONFIG_values[main_needle] = bit_set(AUX_CONFIG_values[main_needle], needle); + } else { + AUX_CONFIG_values[main_needle] = bit_clear(AUX_CONFIG_values[main_needle], needle); } - // UI Hooks - $('a.update').click(function() { - // catch the input changes - var main_needle = 0; - var needle = 0; - $('.boxes input').each(function() { - if ($(this).is(':checked')) { - AUX_CONFIG_values[main_needle] = bit_set(AUX_CONFIG_values[main_needle], needle); - } else { - AUX_CONFIG_values[main_needle] = bit_clear(AUX_CONFIG_values[main_needle], needle); - } + needle++; - needle++; + if (needle >= 12) { // 4 aux * 3 checkboxes = 12 bits per line + main_needle++; - if (needle >= 12) { // 4 aux * 3 checkboxes = 12 bits per line - main_needle++; - - needle = 0; - } - }); - - // send over the data - var AUX_val_buffer_out = new Array(); - - var needle = 0; - for (var i = 0; i < AUX_CONFIG_values.length; i++) { - AUX_val_buffer_out[needle++] = lowByte(AUX_CONFIG_values[i]); - AUX_val_buffer_out[needle++] = highByte(AUX_CONFIG_values[i]); - } - - send_message(MSP_codes.MSP_SET_BOX, AUX_val_buffer_out); - - // Save changes to EEPROM - send_message(MSP_codes.MSP_EEPROM_WRITE, MSP_codes.MSP_EEPROM_WRITE, false, function() { - GUI.log('EEPROM saved'); - - var element = $('a.update'); - element.addClass('success'); - - GUI.timeout_add('success_highlight', function() { - element.removeClass('success'); - }, 2000); - }); - }); - - // enable data pulling - GUI.interval_add('aux_data_poll', function() { - send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS); - send_message(MSP_codes.MSP_RC, MSP_codes.MSP_RC, false, function() { - for (var i = 0; i < AUX_CONFIG.length; i++) { - if (bit_check(CONFIG.mode, i)) { - $('td.name').eq(i).addClass('on').removeClass('off'); - } else { - $('td.name').eq(i).removeClass('on').removeClass('off'); - - if (AUX_CONFIG_values[i] > 0) { - $('td.name').eq(i).addClass('off'); - } - } - } - - box_highlight(RC.AUX1, 2); - box_highlight(RC.AUX2, 5); - box_highlight(RC.AUX3, 8); - box_highlight(RC.AUX4, 11); - }); - }, 50, true); + needle = 0; + } }); + + // send over the data + var AUX_val_buffer_out = new Array(); + + var needle = 0; + for (var i = 0; i < AUX_CONFIG_values.length; i++) { + AUX_val_buffer_out[needle++] = lowByte(AUX_CONFIG_values[i]); + 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); + + function save_to_eeprom() { + send_message(MSP_codes.MSP_EEPROM_WRITE, MSP_codes.MSP_EEPROM_WRITE, false, function() { + GUI.log('EEPROM saved'); + + var element = $('a.update'); + element.addClass('success'); + + GUI.timeout_add('success_highlight', function() { + element.removeClass('success'); + }, 2000); + }); + } }); - }); -} -function box_check(num, pos) { - if (bit_check(num, pos)) { // 1 - return ''; - } else { // 0 - return ''; + // data pulling functions used inside interval timer + function get_status_data() { + send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS, false, get_rc_data); + } + + function get_rc_data() { + send_message(MSP_codes.MSP_RC, MSP_codes.MSP_RC, false, update_ui); + } + + function update_ui() { + for (var i = 0; i < AUX_CONFIG.length; i++) { + if (bit_check(CONFIG.mode, i)) { + $('td.name').eq(i).addClass('on').removeClass('off'); + } else { + $('td.name').eq(i).removeClass('on').removeClass('off'); + + if (AUX_CONFIG_values[i] > 0) { + $('td.name').eq(i).addClass('off'); + } + } + } + + box_highlight(RC.AUX1, 2); + box_highlight(RC.AUX2, 5); + box_highlight(RC.AUX3, 8); + box_highlight(RC.AUX4, 11); + } + + // enable data pulling + GUI.interval_add('aux_data_poll', get_status_data, 50, true); } -} - -// val = channel value -// aux_num = position of corresponding aux channel in the html table -function box_highlight(val, aux_num) { - var tr = $('table.boxes tr'); - var pos = 0; // < 1300 - - if (val > 1300 && val < 1700) { - pos = 1; - } else if (val > 1700) { - pos = 2; - } - - $(':nth-child(' + aux_num + '), :nth-child(' + (aux_num + 1) + '), :nth-child(' + (aux_num + 2) + ')', tr).css('background-color', 'transparent'); - $('td:nth-child(' + (aux_num + pos) + ')', tr).css('background-color', 'orange'); } \ No newline at end of file diff --git a/tabs/default.js b/tabs/default.js index c7466fba..521874a8 100644 --- a/tabs/default.js +++ b/tabs/default.js @@ -6,8 +6,6 @@ function tab_initialize_default() { $('div.changelog.configurator .wrapper').load('./changelog.html'); // UI Hooks - $('a.firmware_flasher').click(function() { - tab_initialize_firmware_flasher(); - }); + $('a.firmware_flasher').click(tab_initialize_firmware_flasher); }); } \ No newline at end of file diff --git a/tabs/gps.html b/tabs/gps.html index da1374bf..cbe2ebf9 100644 --- a/tabs/gps.html +++ b/tabs/gps.html @@ -4,19 +4,19 @@ - + - + - + - + @@ -24,7 +24,7 @@ - +
Altitude:00 m
Latitude:00.0000 deg
Longitude:00.0000 deg
Speed:00 cm/s
Sats:
Dist to Home:00 m
diff --git a/tabs/gps.js b/tabs/gps.js index 848c1b24..c6c4f41d 100644 --- a/tabs/gps.js +++ b/tabs/gps.js @@ -2,33 +2,46 @@ function tab_initialize_gps () { ga_tracker.sendAppView('GPS Page'); GUI.active_tab = 'gps'; - send_message(MSP_codes.MSP_RAW_GPS, MSP_codes.MSP_RAW_GPS, false, function() { - $('#content').load("./tabs/gps.html", function() { - // enable data pulling - GUI.interval_add('gps_pull', function() { - // Update GPS data - $('.GPS_info td.alt').html(GPS_DATA.alt + ' m'); - $('.GPS_info td.lat').html((GPS_DATA.lat / 10000000).toFixed(4) + ' deg'); - $('.GPS_info td.lon').html((GPS_DATA.lon / 10000000).toFixed(4) + ' deg'); - $('.GPS_info td.speed').html(GPS_DATA.speed + ' cm/s'); - $('.GPS_info td.sats').html(GPS_DATA.numSat); - $('.GPS_info td.distToHome').html(GPS_DATA.distanceToHome + ' m'); + send_message(MSP_codes.MSP_RAW_GPS, MSP_codes.MSP_RAW_GPS, false, load_html); - // Update GPS Signal Strengths - var e_ss_table = $('div.GPS_signal_strength table tr:not(.titles)'); + function load_html() { + $('#content').load("./tabs/gps.html", process_html); + } - for (var i = 0; i < GPS_DATA.chn.length; i++) { - var row = e_ss_table.eq(i); + function process_html() { + function get_status_data() { + send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS, false, get_raw_gps_data); + } - $('td', row).eq(0).html(GPS_DATA.svid[i]); - $('td', row).eq(1).html(GPS_DATA.quality[i]); - $('td', row).eq(2).find('progress').val(GPS_DATA.cno[i]); - } + function get_raw_gps_data() { + send_message(MSP_codes.MSP_RAW_GPS, MSP_codes.MSP_RAW_GPS, false, get_gpsvinfo_data); + } - send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS); - send_message(MSP_codes.MSP_RAW_GPS, MSP_codes.MSP_RAW_GPS); - send_message(MSP_codes.MSP_GPSSVINFO, MSP_codes.MSP_GPSSVINFO); - }, 75, true); - }); - }); + function get_gpsvinfo_data() { + send_message(MSP_codes.MSP_GPSSVINFO, MSP_codes.MSP_GPSSVINFO, false, update_ui); + } + + function update_ui() { + $('.GPS_info td.alt').html(GPS_DATA.alt + ' m'); + $('.GPS_info td.lat').html((GPS_DATA.lat / 10000000).toFixed(4) + ' deg'); + $('.GPS_info td.lon').html((GPS_DATA.lon / 10000000).toFixed(4) + ' deg'); + $('.GPS_info td.speed').html(GPS_DATA.speed + ' cm/s'); + $('.GPS_info td.sats').html(GPS_DATA.numSat); + $('.GPS_info td.distToHome').html(GPS_DATA.distanceToHome + ' m'); + + // Update GPS Signal Strengths + var e_ss_table = $('div.GPS_signal_strength table tr:not(.titles)'); + + for (var i = 0; i < GPS_DATA.chn.length; i++) { + var row = e_ss_table.eq(i); + + $('td', row).eq(0).html(GPS_DATA.svid[i]); + $('td', row).eq(1).html(GPS_DATA.quality[i]); + $('td', row).eq(2).find('progress').val(GPS_DATA.cno[i]); + } + } + + // enable data pulling + GUI.interval_add('gps_pull', get_status_data, 75, true); + } } \ No newline at end of file diff --git a/tabs/initial_setup.js b/tabs/initial_setup.js index 8d5f4cc7..108383f4 100644 --- a/tabs/initial_setup.js +++ b/tabs/initial_setup.js @@ -2,245 +2,260 @@ function tab_initialize_initial_setup() { ga_tracker.sendAppView('Initial Setup'); GUI.active_tab = 'initial_setup'; - send_message(MSP_codes.MSP_ACC_TRIM, MSP_codes.MSP_ACC_TRIM, false, function() { - send_message(MSP_codes.MSP_MISC, MSP_codes.MSP_MISC, false, function() { - $('#content').load("./tabs/initial_setup.html", function() { - var yaw_fix = 0.0; + send_message(MSP_codes.MSP_ACC_TRIM, MSP_codes.MSP_ACC_TRIM, false, load_misc_data); - // Fill in misc stuff - $('input[name="mincellvoltage"]').val(MISC.vbatmincellvoltage); - $('input[name="maxcellvoltage"]').val(MISC.vbatmaxcellvoltage); - $('input[name="voltagescale"]').val(MISC.vbatscale); + function load_misc_data() { + send_message(MSP_codes.MSP_MISC, MSP_codes.MSP_MISC, false, load_html); + } - $('input[name="minthrottle"]').val(MISC.minthrottle); - $('input[name="maxthrottle"]').val(MISC.maxthrottle); - $('input[name="failsafe_throttle"]').val(MISC.failsafe_throttle); - $('input[name="mincommand"]').val(MISC.mincommand); + function load_html() { + $('#content').load("./tabs/initial_setup.html", process_html); + } - $('input[name="mag_declination"]').val(MISC.mag_declination / 10); + function process_html() { + var yaw_fix = 0.0; - // Fill in the accel trimms from CONFIG object - $('input[name="pitch"]').val(CONFIG.accelerometerTrims[0]); - $('input[name="roll"]').val(CONFIG.accelerometerTrims[1]); + // Fill in misc stuff + $('input[name="mincellvoltage"]').val(MISC.vbatmincellvoltage); + $('input[name="maxcellvoltage"]').val(MISC.vbatmaxcellvoltage); + $('input[name="voltagescale"]').val(MISC.vbatscale); - // Display multiType - var str = ''; - switch (CONFIG.multiType) { - case 1: // TRI - str = 'TRI'; - break; - case 2: // QUAD + - str = 'Quad +'; - break; - case 3: // QUAD X - str = 'Quad X'; - break; - case 4: // BI - str = 'BI'; - break; - case 5: // GIMBAL - str = 'Gimbal'; - break; - case 6: // Y6 - str = 'Y6'; - break; - case 7: // HEX 6 - str = 'HEX 6'; - break; - case 8: // FLYING_WING - str = 'Flying Wing'; - break; - case 9: // Y4 - str = 'Y4'; - break; - case 10: // HEX6 X - str = 'HEX6 X'; - break; - case 11: // OCTO X8 - case 12: - case 13: - str = 'OCTO X8'; - break; - case 14: // AIRPLANE - str = 'Airplane'; - break; - case 15: // Heli 120 - str = 'Heli 120'; - break; - case 16: // Heli 90 - str = 'Heli 90'; - break; - case 17: // Vtail - str = 'Vtail'; - break; - case 18: // HEX6 H - str = 'HEX6 H'; - break; - case 19: // PPM to SERVO - str = 'PPM to SERVO'; - break; - case 20: // Dualcopter - str = 'Dualcopter'; - break; - case 21: // - str = 'Singlecopter'; - break; - } + $('input[name="minthrottle"]').val(MISC.minthrottle); + $('input[name="maxthrottle"]').val(MISC.maxthrottle); + $('input[name="failsafe_throttle"]').val(MISC.failsafe_throttle); + $('input[name="mincommand"]').val(MISC.mincommand); - $('span.model').html('Model: ' + str); + $('input[name="mag_declination"]').val(MISC.mag_declination / 10); - // UI Hooks - $('a.calibrateAccel').click(function() { - var self = $(this); + // Fill in the accel trimms from CONFIG object + $('input[name="pitch"]').val(CONFIG.accelerometerTrims[0]); + $('input[name="roll"]').val(CONFIG.accelerometerTrims[1]); - if (!self.hasClass('calibrating')) { - self.addClass('calibrating'); + // Display multiType + var str = ''; + switch (CONFIG.multiType) { + case 1: // TRI + str = 'TRI'; + break; + case 2: // QUAD + + str = 'Quad +'; + break; + case 3: // QUAD X + str = 'Quad X'; + break; + case 4: // BI + str = 'BI'; + break; + case 5: // GIMBAL + str = 'Gimbal'; + break; + case 6: // Y6 + str = 'Y6'; + break; + case 7: // HEX 6 + str = 'HEX 6'; + break; + case 8: // FLYING_WING + str = 'Flying Wing'; + break; + case 9: // Y4 + str = 'Y4'; + break; + case 10: // HEX6 X + str = 'HEX6 X'; + break; + case 11: // OCTO X8 + case 12: + case 13: + str = 'OCTO X8'; + break; + case 14: // AIRPLANE + str = 'Airplane'; + break; + case 15: // Heli 120 + str = 'Heli 120'; + break; + case 16: // Heli 90 + str = 'Heli 90'; + break; + case 17: // Vtail + str = 'Vtail'; + break; + case 18: // HEX6 H + str = 'HEX6 H'; + break; + case 19: // PPM to SERVO + str = 'PPM to SERVO'; + break; + case 20: // Dualcopter + str = 'Dualcopter'; + break; + case 21: // + str = 'Singlecopter'; + break; + } - // 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, MSP_codes.MSP_ACC_CALIBRATION, false, function() { - GUI.log('Accelerometer calibration started'); - }); + $('span.model').html('Model: ' + str); - GUI.timeout_add('button_reset', function() { - GUI.interval_resume('initial_setup_data_pull'); + // UI Hooks + $('a.calibrateAccel').click(function() { + var self = $(this); - GUI.log('Accelerometer calibration finished'); + if (!self.hasClass('calibrating')) { + self.addClass('calibrating'); - self.removeClass('calibrating'); - }, 2000); - } + // 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, MSP_codes.MSP_ACC_CALIBRATION, false, function() { + GUI.log('Accelerometer calibration started'); }); - $('a.calibrateMag').click(function() { - var self = $(this); + GUI.timeout_add('button_reset', function() { + GUI.interval_resume('initial_setup_data_pull'); - if (!self.hasClass('calibrating')) { - self.addClass('calibrating'); + GUI.log('Accelerometer calibration finished'); - send_message(MSP_codes.MSP_MAG_CALIBRATION, MSP_codes.MSP_MAG_CALIBRATION, false, function() { - GUI.log('Magnetometer calibration started'); - }); + self.removeClass('calibrating'); + }, 2000); + } + }); - GUI.timeout_add('button_reset', function() { - GUI.log('Magnetometer calibration finished'); - self.removeClass('calibrating'); - }, 30000); - } + $('a.calibrateMag').click(function() { + var self = $(this); + + if (!self.hasClass('calibrating')) { + self.addClass('calibrating'); + + send_message(MSP_codes.MSP_MAG_CALIBRATION, MSP_codes.MSP_MAG_CALIBRATION, false, function() { + GUI.log('Magnetometer calibration started'); }); - $('a.resetSettings').click(function() { - send_message(MSP_codes.MSP_RESET_CONF, MSP_codes.MSP_RESET_CONF, false, function() { - GUI.log('Settings restored to default'); + GUI.timeout_add('button_reset', function() { + GUI.log('Magnetometer calibration finished'); + self.removeClass('calibrating'); + }, 30000); + } + }); - GUI.tab_switch_cleanup(function() { - tab_initialize_initial_setup(); - }); - }); + $('a.resetSettings').click(function() { + send_message(MSP_codes.MSP_RESET_CONF, MSP_codes.MSP_RESET_CONF, false, function() { + GUI.log('Settings restored to default'); + + GUI.tab_switch_cleanup(function() { + tab_initialize_initial_setup(); }); - - - $('a.update').click(function() { - CONFIG.accelerometerTrims[0] = parseInt($('input[name="pitch"]').val()); - CONFIG.accelerometerTrims[1] = parseInt($('input[name="roll"]').val()); - - var buffer_out = new Array(); - buffer_out[0] = lowByte(CONFIG.accelerometerTrims[0]); - buffer_out[1] = highByte(CONFIG.accelerometerTrims[0]); - buffer_out[2] = lowByte(CONFIG.accelerometerTrims[1]); - buffer_out[3] = highByte(CONFIG.accelerometerTrims[1]); - - // Send over the new trims - 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; - MISC.vbatscale = parseInt($('input[name="voltagescale"]').val()); - - MISC.minthrottle = parseInt($('input[name="minthrottle"]').val()); - MISC.maxthrottle = parseInt($('input[name="maxthrottle"]').val()); - MISC.failsafe_throttle = parseInt($('input[name="failsafe_throttle"]').val()); - MISC.mincommand = parseInt($('input[name="mincommand"]').val()); - - MISC.mag_declination = parseFloat($('input[name="mag_declination"]').val()) * 10; - - // we also have to fill the unsupported bytes - var buffer_out = new Array(); - buffer_out[0] = 0; // powerfailmeter - buffer_out[1] = 0; - buffer_out[2] = lowByte(MISC.minthrottle); - buffer_out[3] = highByte(MISC.minthrottle); - buffer_out[4] = lowByte(MISC.maxthrottle); - buffer_out[5] = highByte(MISC.maxthrottle); - buffer_out[6] = lowByte(MISC.mincommand); - buffer_out[7] = highByte(MISC.mincommand); - buffer_out[8] = lowByte(MISC.failsafe_throttle); - buffer_out[9] = highByte(MISC.failsafe_throttle); - buffer_out[10] = 0; - buffer_out[11] = 0; - buffer_out[12] = 0; - buffer_out[13] = 0; - buffer_out[14] = 0; - buffer_out[15] = 0; - buffer_out[16] = lowByte(MISC.mag_declination); - buffer_out[17] = highByte(MISC.mag_declination); - buffer_out[18] = MISC.vbatscale; - buffer_out[19] = MISC.vbatmincellvoltage; - buffer_out[20] = MISC.vbatmaxcellvoltage; - buffer_out[21] = 0; // vbatlevel_crit (unused) - - // Send over new misc - send_message(MSP_codes.MSP_SET_MISC, buffer_out); - - // Save changes to EEPROM - send_message(MSP_codes.MSP_EEPROM_WRITE, MSP_codes.MSP_EEPROM_WRITE, false, function() { - GUI.log('EEPROM saved'); - - var element = $('a.update'); - element.addClass('success'); - - GUI.timeout_add('success_highlight', function() { - element.removeClass('success'); - }, 2000); - }); - }); - - // reset yaw button hook - $('div#interactive_block > a.reset').click(function() { - yaw_fix = SENSOR_DATA.kinematicsZ * - 1.0; - console.log("YAW reset to 0"); - }); - - $('#content .backup').click(configuration_backup); - - $('#content .restore').click(configuration_restore); - - GUI.interval_add('initial_setup_data_pull', function() { - // Update voltage indicator - $('.bat-voltage').html(ANALOG.voltage + ' V'); - - // Request new data, if transmission fails it doesn't matter as new transmission will be requested after 50ms - send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS, false, function() { // cycle time, active sensors, etc... - send_message(MSP_codes.MSP_ANALOG, MSP_codes.MSP_ANALOG, false, function() { // battery voltage - send_message(MSP_codes.MSP_ATTITUDE, MSP_codes.MSP_ATTITUDE, false, function() { // kinematics - // Update cube - var cube = $('div#cube'); - - cube.css('-webkit-transform', 'rotateY(' + ((SENSOR_DATA.kinematicsZ * -1.0) - yaw_fix) + 'deg)'); - $('#cubePITCH', cube).css('-webkit-transform', 'rotateX(' + SENSOR_DATA.kinematicsY + 'deg)'); - $('#cubeROLL', cube).css('-webkit-transform', 'rotateZ(' + SENSOR_DATA.kinematicsX + 'deg)'); - - /* - // Update Compass - $('div#compass .pointer').css('-webkit-transform', 'rotate(' + (SENSOR_DATA.kinematicsZ) + 'deg)'); - $('div#compass .value').html(SENSOR_DATA.kinematicsZ + '°'); - */ - }); - }); - }); - }, 50, true); }); }); - }); + + + $('a.update').click(function() { + CONFIG.accelerometerTrims[0] = parseInt($('input[name="pitch"]').val()); + CONFIG.accelerometerTrims[1] = parseInt($('input[name="roll"]').val()); + + var buffer_out = new Array(); + buffer_out[0] = lowByte(CONFIG.accelerometerTrims[0]); + buffer_out[1] = highByte(CONFIG.accelerometerTrims[0]); + buffer_out[2] = lowByte(CONFIG.accelerometerTrims[1]); + buffer_out[3] = highByte(CONFIG.accelerometerTrims[1]); + + // Send over the new trims + 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; + MISC.vbatscale = parseInt($('input[name="voltagescale"]').val()); + + MISC.minthrottle = parseInt($('input[name="minthrottle"]').val()); + MISC.maxthrottle = parseInt($('input[name="maxthrottle"]').val()); + MISC.failsafe_throttle = parseInt($('input[name="failsafe_throttle"]').val()); + MISC.mincommand = parseInt($('input[name="mincommand"]').val()); + + MISC.mag_declination = parseFloat($('input[name="mag_declination"]').val()) * 10; + + // we also have to fill the unsupported bytes + var buffer_out = new Array(); + buffer_out[0] = 0; // powerfailmeter + buffer_out[1] = 0; + buffer_out[2] = lowByte(MISC.minthrottle); + buffer_out[3] = highByte(MISC.minthrottle); + buffer_out[4] = lowByte(MISC.maxthrottle); + buffer_out[5] = highByte(MISC.maxthrottle); + buffer_out[6] = lowByte(MISC.mincommand); + buffer_out[7] = highByte(MISC.mincommand); + buffer_out[8] = lowByte(MISC.failsafe_throttle); + buffer_out[9] = highByte(MISC.failsafe_throttle); + buffer_out[10] = 0; + buffer_out[11] = 0; + buffer_out[12] = 0; + buffer_out[13] = 0; + buffer_out[14] = 0; + buffer_out[15] = 0; + buffer_out[16] = lowByte(MISC.mag_declination); + buffer_out[17] = highByte(MISC.mag_declination); + buffer_out[18] = MISC.vbatscale; + buffer_out[19] = MISC.vbatmincellvoltage; + buffer_out[20] = MISC.vbatmaxcellvoltage; + buffer_out[21] = 0; // vbatlevel_crit (unused) + + // Send over new misc + send_message(MSP_codes.MSP_SET_MISC, buffer_out, false, save_to_eeprom); + + function save_to_eeprom() { + send_message(MSP_codes.MSP_EEPROM_WRITE, MSP_codes.MSP_EEPROM_WRITE, false, function() { + GUI.log('EEPROM saved'); + + var element = $('a.update'); + element.addClass('success'); + + GUI.timeout_add('success_highlight', function() { + element.removeClass('success'); + }, 2000); + }); + } + }); + + // reset yaw button hook + $('div#interactive_block > a.reset').click(function() { + yaw_fix = SENSOR_DATA.kinematicsZ * - 1.0; + console.log("YAW reset to 0"); + }); + + $('#content .backup').click(configuration_backup); + + $('#content .restore').click(configuration_restore); + + // data pulling functions used inside interval timer + function get_status_data() { + send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS, false, get_analog_data); + } + + function get_analog_data() { + send_message(MSP_codes.MSP_ANALOG, MSP_codes.MSP_ANALOG, false, get_attitude_data); + } + + function get_attitude_data() { + send_message(MSP_codes.MSP_ATTITUDE, MSP_codes.MSP_ATTITUDE, false, update_ui); + } + + function update_ui() { + // Update voltage indicator + $('.bat-voltage').html(ANALOG.voltage + ' V'); + + // Update cube + var cube = $('div#cube'); + + cube.css('-webkit-transform', 'rotateY(' + ((SENSOR_DATA.kinematicsZ * -1.0) - yaw_fix) + 'deg)'); + $('#cubePITCH', cube).css('-webkit-transform', 'rotateX(' + SENSOR_DATA.kinematicsY + 'deg)'); + $('#cubeROLL', cube).css('-webkit-transform', 'rotateZ(' + SENSOR_DATA.kinematicsX + 'deg)'); + + /* + // Update Compass + $('div#compass .pointer').css('-webkit-transform', 'rotate(' + (SENSOR_DATA.kinematicsZ) + 'deg)'); + $('div#compass .value').html(SENSOR_DATA.kinematicsZ + '°'); + */ + } + + GUI.interval_add('initial_setup_data_pull', get_status_data, 50, true); + } } \ No newline at end of file diff --git a/tabs/motor_outputs.js b/tabs/motor_outputs.js index 3d62be41..bb492c3b 100644 --- a/tabs/motor_outputs.js +++ b/tabs/motor_outputs.js @@ -2,103 +2,115 @@ function tab_initialize_motor_outputs() { ga_tracker.sendAppView('Motor Outputs Page'); GUI.active_tab = 'motor_outputs'; - send_message(MSP_codes.MSP_MISC, MSP_codes.MSP_MISC, false, function() { - send_message(MSP_codes.MSP_MOTOR, MSP_codes.MSP_MOTOR, false, function() { - $('#content').load("./tabs/motor_outputs.html", function() { - // if CAP_DYNBALANCE is true - if (bit_check(CONFIG.capability, 2)) { - $('div.motor_testing').show(); - } + send_message(MSP_codes.MSP_MISC, MSP_codes.MSP_MISC, false, get_motor_data); - var number_of_valid_outputs = (MOTOR_DATA.indexOf(0) > -1) ? MOTOR_DATA.indexOf(0) : 8; + function get_motor_data() { + send_message(MSP_codes.MSP_MOTOR, MSP_codes.MSP_MOTOR, false, load_html); + } - $('input.min').val(MISC.mincommand); - $('input.max').val(MISC.maxthrottle); + function load_html() { + $('#content').load("./tabs/motor_outputs.html", process_html); + } + + function process_html() { + // if CAP_DYNBALANCE is true + if (bit_check(CONFIG.capability, 2)) { + $('div.motor_testing').show(); + } + + var number_of_valid_outputs = (MOTOR_DATA.indexOf(0) > -1) ? MOTOR_DATA.indexOf(0) : 8; + + $('input.min').val(MISC.mincommand); + $('input.max').val(MISC.maxthrottle); - $('div.sliders input').prop('min', MISC.mincommand); - $('div.sliders input').prop('max', MISC.maxthrottle); - $('div.sliders input').val(MISC.mincommand); - $('div.values li:not(:last)').html(MISC.mincommand); + $('div.sliders input').prop('min', MISC.mincommand); + $('div.sliders input').prop('max', MISC.maxthrottle); + $('div.sliders input').val(MISC.mincommand); + $('div.values li:not(:last)').html(MISC.mincommand); - // UI hooks - $('div.sliders input:not(.master)').change(function() { - var index = $(this).index(); + // UI hooks + $('div.sliders input:not(.master)').change(function() { + var index = $(this).index(); - $('div.values li').eq(index).html($(this).val()); + $('div.values li').eq(index).html($(this).val()); - // send data to mcu - var buffer_out = []; + // send data to mcu + var buffer_out = []; - for (var i = 0; i < 8; i++) { - var val = parseInt($('div.sliders input').eq(i).val()); + for (var i = 0; i < 8; i++) { + var val = parseInt($('div.sliders input').eq(i).val()); - buffer_out.push(lowByte(val)); - buffer_out.push(highByte(val)); - } + buffer_out.push(lowByte(val)); + buffer_out.push(highByte(val)); + } - send_message(MSP_codes.MSP_SET_MOTOR, buffer_out); - }); - - $('div.sliders input.master').change(function() { - var val = $(this).val(); - - $('div.sliders input:not(:disabled, :last)').val(val); - $('div.values li:not(:last)').slice(0, number_of_valid_outputs).html(val); - $('div.sliders input:not(:last):first').change(); - }); - - $('div.notice input[type="checkbox"]').change(function() { - if ($(this).is(':checked')) { - $('div.sliders input').slice(0, number_of_valid_outputs).prop('disabled', false); - - // unlock master slider - $('div.sliders input:last').prop('disabled', false); - } else { - // disable sliders / min max - $('div.sliders input').prop('disabled', true); - - // change all values to default - $('div.sliders input').val(1000); - $('div.values li:not(:last)').html(1000); - - // trigger change event so values are sent to mcu - $('div.sliders input').change(); - } - }); - - // enable Motor data pulling - GUI.interval_add('motor_poll', function() { - // Request New data - send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS, false, function() { - send_message(MSP_codes.MSP_MOTOR, MSP_codes.MSP_MOTOR, false, function() { - send_message(MSP_codes.MSP_SERVO, MSP_codes.MSP_SERVO, false, function() { - // Update UI - - var block_height = $('div.m-block:first').height(); - - for (var i = 0; i < MOTOR_DATA.length; i++) { - var data = MOTOR_DATA[i] - 1000; - var margin_top = block_height - (data * (block_height / 1000)); - var height = (data * (block_height / 1000)); - var color = parseInt(data * 0.256); - - $('.motor-' + i + ' .indicator').css({'margin-top' : margin_top + 'px', 'height' : height + 'px', 'background-color' : 'rgb(' + color + ',0,0)'}); - } - - for (var i = 0; i < SERVO_DATA.length; i++) { - var data = SERVO_DATA[i] - 1000; - var margin_top = block_height - (data * (block_height / 1000)); - var height = (data * (block_height / 1000)); - var color = parseInt(data * 0.256); - - $('.servo-' + i + ' .indicator').css({'margin-top' : margin_top + 'px', 'height' : height + 'px', 'background-color' : 'rgb(' + color + ',0,0)'}); - } - }); - }); - }); - }, 50, true); - }); + send_message(MSP_codes.MSP_SET_MOTOR, buffer_out); }); - }); + + $('div.sliders input.master').change(function() { + var val = $(this).val(); + + $('div.sliders input:not(:disabled, :last)').val(val); + $('div.values li:not(:last)').slice(0, number_of_valid_outputs).html(val); + $('div.sliders input:not(:last):first').change(); + }); + + $('div.notice input[type="checkbox"]').change(function() { + if ($(this).is(':checked')) { + $('div.sliders input').slice(0, number_of_valid_outputs).prop('disabled', false); + + // unlock master slider + $('div.sliders input:last').prop('disabled', false); + } else { + // disable sliders / min max + $('div.sliders input').prop('disabled', true); + + // change all values to default + $('div.sliders input').val(1000); + $('div.values li:not(:last)').html(1000); + + // trigger change event so values are sent to mcu + $('div.sliders input').change(); + } + }); + + // data pulling functions used inside interval timer + function get_status_data() { + send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS, false, get_motor_data); + } + + function get_motor_data() { + send_message(MSP_codes.MSP_MOTOR, MSP_codes.MSP_MOTOR, false, get_servo_data); + } + + function get_servo_data() { + send_message(MSP_codes.MSP_SERVO, MSP_codes.MSP_SERVO, false, update_ui); + } + + function update_ui() { + var block_height = $('div.m-block:first').height(); + + for (var i = 0; i < MOTOR_DATA.length; i++) { + var data = MOTOR_DATA[i] - 1000; + var margin_top = block_height - (data * (block_height / 1000)); + var height = (data * (block_height / 1000)); + var color = parseInt(data * 0.256); + + $('.motor-' + i + ' .indicator').css({'margin-top' : margin_top + 'px', 'height' : height + 'px', 'background-color' : 'rgb(' + color + ',0,0)'}); + } + + for (var i = 0; i < SERVO_DATA.length; i++) { + var data = SERVO_DATA[i] - 1000; + var margin_top = block_height - (data * (block_height / 1000)); + var height = (data * (block_height / 1000)); + var color = parseInt(data * 0.256); + + $('.servo-' + i + ' .indicator').css({'margin-top' : margin_top + 'px', 'height' : height + 'px', 'background-color' : 'rgb(' + color + ',0,0)'}); + } + } + + // enable Motor data pulling + GUI.interval_add('motor_poll', get_status_data, 50, true); + } } \ No newline at end of file diff --git a/tabs/pid_tuning.js b/tabs/pid_tuning.js index 01330d8d..ce2e5b80 100644 --- a/tabs/pid_tuning.js +++ b/tabs/pid_tuning.js @@ -2,286 +2,295 @@ function tab_initialize_pid_tuning() { ga_tracker.sendAppView('PID Tuning'); GUI.active_tab = 'pid_tuning'; - send_message(MSP_codes.MSP_PID, MSP_codes.MSP_PID, false, function() { - send_message(MSP_codes.MSP_RC_TUNING, MSP_codes.MSP_RC_TUNING, false, function() { - $('#content').load("./tabs/pid_tuning.html", function() { - // Fill in the data from PIDs array - var i = 0; - $('.pid_tuning .ROLL input').each(function() { - switch (i) { - case 0: - $(this).val(PIDs[0][i++].toFixed(1)); - break; - case 1: - $(this).val(PIDs[0][i++].toFixed(3)); - break; - case 2: - $(this).val(PIDs[0][i++].toFixed(0)); - break; - } + send_message(MSP_codes.MSP_PID, MSP_codes.MSP_PID, false, get_rc_tuning_data); + + function get_rc_tuning_data() { + send_message(MSP_codes.MSP_RC_TUNING, MSP_codes.MSP_RC_TUNING, false, load_html); + } + + function load_html() { + $('#content').load("./tabs/pid_tuning.html", process_html); + } + + function process_html() { + // Fill in the data from PIDs array + var i = 0; + $('.pid_tuning .ROLL input').each(function() { + switch (i) { + case 0: + $(this).val(PIDs[0][i++].toFixed(1)); + break; + case 1: + $(this).val(PIDs[0][i++].toFixed(3)); + break; + case 2: + $(this).val(PIDs[0][i++].toFixed(0)); + break; + } + }); + + i = 0; + $('.pid_tuning .PITCH input').each(function() { + switch (i) { + case 0: + $(this).val(PIDs[1][i++].toFixed(1)); + break; + case 1: + $(this).val(PIDs[1][i++].toFixed(3)); + break; + case 2: + $(this).val(PIDs[1][i++].toFixed(0)); + break; + } + }); + + i = 0; + $('.pid_tuning .YAW input').each(function() { + switch (i) { + case 0: + $(this).val(PIDs[2][i++].toFixed(1)); + break; + case 1: + $(this).val(PIDs[2][i++].toFixed(3)); + break; + case 2: + $(this).val(PIDs[2][i++].toFixed(0)); + break; + } + }); + + i = 0; + $('.pid_tuning .ALT input').each(function() { + switch (i) { + case 0: + $(this).val(PIDs[3][i++].toFixed(1)); + break; + case 1: + $(this).val(PIDs[3][i++].toFixed(3)); + break; + case 2: + $(this).val(PIDs[3][i++].toFixed(0)); + break; + } + }); + + i = 0; + $('.pid_tuning .Pos input').each(function() { + $(this).val(PIDs[4][i++].toFixed(2)); + }); + + i = 0; + $('.pid_tuning .PosR input').each(function() { + switch (i) { + case 0: + $(this).val(PIDs[5][i++].toFixed(1)); + break; + case 1: + $(this).val(PIDs[5][i++].toFixed(2)); + break; + case 2: + $(this).val(PIDs[5][i++].toFixed(3)); + break; + } + }); + + i = 0; + $('.pid_tuning .NavR input').each(function() { + switch (i) { + case 0: + $(this).val(PIDs[6][i++].toFixed(1)); + break; + case 1: + $(this).val(PIDs[6][i++].toFixed(2)); + break; + case 2: + $(this).val(PIDs[6][i++].toFixed(3)); + break; + } + }); + + i = 0; + $('.pid_tuning .LEVEL input').each(function() { + switch (i) { + case 0: + $(this).val(PIDs[7][i++].toFixed(1)); + break; + case 1: + $(this).val(PIDs[7][i++].toFixed(2)); + break; + case 2: + $(this).val(PIDs[7][i++].toFixed(0)); + break; + } + }); + + i = 0; + $('.pid_tuning .MAG input').each(function() { + $(this).val(PIDs[8][i++].toFixed(1)); + }); + + i = 0; + $('.pid_tuning .Vario input').each(function() { + switch (i) { + case 0: + $(this).val(PIDs[9][i++].toFixed(1)); + break; + case 1: + $(this).val(PIDs[9][i++].toFixed(3)); + break; + case 2: + $(this).val(PIDs[9][i++].toFixed(0)); + break; + } + }); + + // Fill in data from RC_tuning object + $('.rate-tpa input[name="roll-pitch"]').val(RC_tuning.roll_pitch_rate.toFixed(2)); + $('.rate-tpa input[name="yaw"]').val(RC_tuning.yaw_rate.toFixed(2)); + $('.rate-tpa input[name="tpa"]').val(RC_tuning.dynamic_THR_PID.toFixed(2)); + + // Fill in currently selected profile + $('input[name="profile"]').val(CONFIG.profile + 1); // +1 because the range is 0-2 + + // UI Hooks + $('input[name="profile"]').change(function() { + var profile = parseInt($(this).val()); + send_message(MSP_codes.MSP_SELECT_SETTING, [profile - 1], false, function() { + GUI.log('Loaded Profile: ' + profile + ''); + + GUI.tab_switch_cleanup(function() { + tab_initialize_pid_tuning(); }); - - i = 0; - $('.pid_tuning .PITCH input').each(function() { - switch (i) { - case 0: - $(this).val(PIDs[1][i++].toFixed(1)); - break; - case 1: - $(this).val(PIDs[1][i++].toFixed(3)); - break; - case 2: - $(this).val(PIDs[1][i++].toFixed(0)); - break; - } - }); - - i = 0; - $('.pid_tuning .YAW input').each(function() { - switch (i) { - case 0: - $(this).val(PIDs[2][i++].toFixed(1)); - break; - case 1: - $(this).val(PIDs[2][i++].toFixed(3)); - break; - case 2: - $(this).val(PIDs[2][i++].toFixed(0)); - break; - } - }); - - i = 0; - $('.pid_tuning .ALT input').each(function() { - switch (i) { - case 0: - $(this).val(PIDs[3][i++].toFixed(1)); - break; - case 1: - $(this).val(PIDs[3][i++].toFixed(3)); - break; - case 2: - $(this).val(PIDs[3][i++].toFixed(0)); - break; - } - }); - - i = 0; - $('.pid_tuning .Pos input').each(function() { - $(this).val(PIDs[4][i++].toFixed(2)); - }); - - i = 0; - $('.pid_tuning .PosR input').each(function() { - switch (i) { - case 0: - $(this).val(PIDs[5][i++].toFixed(1)); - break; - case 1: - $(this).val(PIDs[5][i++].toFixed(2)); - break; - case 2: - $(this).val(PIDs[5][i++].toFixed(3)); - break; - } - }); - - i = 0; - $('.pid_tuning .NavR input').each(function() { - switch (i) { - case 0: - $(this).val(PIDs[6][i++].toFixed(1)); - break; - case 1: - $(this).val(PIDs[6][i++].toFixed(2)); - break; - case 2: - $(this).val(PIDs[6][i++].toFixed(3)); - break; - } - }); - - i = 0; - $('.pid_tuning .LEVEL input').each(function() { - switch (i) { - case 0: - $(this).val(PIDs[7][i++].toFixed(1)); - break; - case 1: - $(this).val(PIDs[7][i++].toFixed(2)); - break; - case 2: - $(this).val(PIDs[7][i++].toFixed(0)); - break; - } - }); - - i = 0; - $('.pid_tuning .MAG input').each(function() { - $(this).val(PIDs[8][i++].toFixed(1)); - }); - - i = 0; - $('.pid_tuning .Vario input').each(function() { - switch (i) { - case 0: - $(this).val(PIDs[9][i++].toFixed(1)); - break; - case 1: - $(this).val(PIDs[9][i++].toFixed(3)); - break; - case 2: - $(this).val(PIDs[9][i++].toFixed(0)); - break; - } - }); - - // Fill in data from RC_tuning object - $('.rate-tpa input[name="roll-pitch"]').val(RC_tuning.roll_pitch_rate.toFixed(2)); - $('.rate-tpa input[name="yaw"]').val(RC_tuning.yaw_rate.toFixed(2)); - $('.rate-tpa input[name="tpa"]').val(RC_tuning.dynamic_THR_PID.toFixed(2)); - - // Fill in currently selected profile - $('input[name="profile"]').val(CONFIG.profile + 1); // +1 because the range is 0-2 - - // UI Hooks - $('input[name="profile"]').change(function() { - var profile = parseInt($(this).val()); - send_message(MSP_codes.MSP_SELECT_SETTING, [profile - 1], false, function() { - GUI.log('Loaded Profile: ' + profile + ''); - - GUI.tab_switch_cleanup(function() { - tab_initialize_pid_tuning(); - }); - }); - }); - - $('a.refresh').click(function() { - GUI.tab_switch_cleanup(function() { - GUI.log('PID data refreshed'); - - tab_initialize_pid_tuning(); - }); - }); - - $('a.update').click(function() { - // Catch all the changes and stuff the inside PIDs array - var i = 0; - $('table.pid_tuning tr.ROLL input').each(function() { - PIDs[0][i++] = parseFloat($(this).val()); - }); - - i = 0; - $('table.pid_tuning tr.PITCH input').each(function() { - PIDs[1][i++] = parseFloat($(this).val()); - }); - - i = 0; - $('table.pid_tuning tr.YAW input').each(function() { - PIDs[2][i++] = parseFloat($(this).val()); - }); - - i = 0; - $('table.pid_tuning tr.ALT input').each(function() { - PIDs[3][i++] = parseFloat($(this).val()); - }); - - i = 0; - $('table.pid_tuning tr.Vario input').each(function() { - PIDs[9][i++] = parseFloat($(this).val()); - }); - - i = 0; - $('table.pid_tuning tr.Pos input').each(function() { - PIDs[4][i++] = parseFloat($(this).val()); - }); - - i = 0; - $('table.pid_tuning tr.PosR input').each(function() { - PIDs[5][i++] = parseFloat($(this).val()); - }); - - i = 0; - $('table.pid_tuning tr.NavR input').each(function() { - PIDs[6][i++] = parseFloat($(this).val()); - }); - - i = 0; - $('table.pid_tuning tr.LEVEL input').each(function() { - PIDs[7][i++] = parseFloat($(this).val()); - }); - - i = 0; - $('table.pid_tuning tr.MAG input').each(function() { - PIDs[8][i++] = parseFloat($(this).val()); - }); - - var PID_buffer_out = new Array(); - for (var i = 0, needle = 0; i < PIDs.length; i++, needle += 3) { - switch (i) { - case 0: - case 1: - case 2: - case 3: - case 7: - case 8: - case 9: - PID_buffer_out[needle] = parseInt(PIDs[i][0] * 10); - PID_buffer_out[needle + 1] = parseInt(PIDs[i][1] * 1000); - PID_buffer_out[needle + 2] = parseInt(PIDs[i][2]); - break; - case 4: - PID_buffer_out[needle] = parseInt(PIDs[i][0] * 100); - PID_buffer_out[needle + 1] = parseInt(PIDs[i][1] * 100); - PID_buffer_out[needle + 2] = parseInt(PIDs[i][2]); - break; - case 5: - case 6: - PID_buffer_out[needle] = parseInt(PIDs[i][0] * 10); - PID_buffer_out[needle + 1] = parseInt(PIDs[i][1] * 100); - PID_buffer_out[needle + 2] = parseInt(PIDs[i][2] * 1000); - break; - } - } - - // Send over the PID changes - send_message(MSP_codes.MSP_SET_PID, PID_buffer_out); - - // catch RC_tuning changes - RC_tuning.roll_pitch_rate = parseFloat($('.rate-tpa input[name="roll-pitch"]').val()); - RC_tuning.yaw_rate = parseFloat($('.rate-tpa input[name="yaw"]').val()); - RC_tuning.dynamic_THR_PID = parseFloat($('.rate-tpa input[name="tpa"]').val()); - - var RC_tuning_buffer_out = new Array(); - RC_tuning_buffer_out[0] = parseInt(RC_tuning.RC_RATE * 100); - RC_tuning_buffer_out[1] = parseInt(RC_tuning.RC_EXPO * 100); - RC_tuning_buffer_out[2] = parseInt(RC_tuning.roll_pitch_rate * 100); - RC_tuning_buffer_out[3] = parseInt(RC_tuning.yaw_rate * 100); - RC_tuning_buffer_out[4] = parseInt(RC_tuning.dynamic_THR_PID * 100); - RC_tuning_buffer_out[5] = parseInt(RC_tuning.throttle_MID * 100); - 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); - - // Save changes to EEPROM - send_message(MSP_codes.MSP_EEPROM_WRITE, MSP_codes.MSP_EEPROM_WRITE, false, function() { - GUI.log('EEPROM saved'); - - var element = $('a.update'); - element.addClass('success'); - - GUI.timeout_add('success_highlight', function() { - element.removeClass('success'); - }, 2000); - }); - }); - - // enable data pulling - GUI.interval_add('pid_data_poll', function() { - send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS); - }, 50); }); }); - }); + + $('a.refresh').click(function() { + GUI.tab_switch_cleanup(function() { + GUI.log('PID data refreshed'); + + tab_initialize_pid_tuning(); + }); + }); + + $('a.update').click(function() { + // Catch all the changes and stuff the inside PIDs array + var i = 0; + $('table.pid_tuning tr.ROLL input').each(function() { + PIDs[0][i++] = parseFloat($(this).val()); + }); + + i = 0; + $('table.pid_tuning tr.PITCH input').each(function() { + PIDs[1][i++] = parseFloat($(this).val()); + }); + + i = 0; + $('table.pid_tuning tr.YAW input').each(function() { + PIDs[2][i++] = parseFloat($(this).val()); + }); + + i = 0; + $('table.pid_tuning tr.ALT input').each(function() { + PIDs[3][i++] = parseFloat($(this).val()); + }); + + i = 0; + $('table.pid_tuning tr.Vario input').each(function() { + PIDs[9][i++] = parseFloat($(this).val()); + }); + + i = 0; + $('table.pid_tuning tr.Pos input').each(function() { + PIDs[4][i++] = parseFloat($(this).val()); + }); + + i = 0; + $('table.pid_tuning tr.PosR input').each(function() { + PIDs[5][i++] = parseFloat($(this).val()); + }); + + i = 0; + $('table.pid_tuning tr.NavR input').each(function() { + PIDs[6][i++] = parseFloat($(this).val()); + }); + + i = 0; + $('table.pid_tuning tr.LEVEL input').each(function() { + PIDs[7][i++] = parseFloat($(this).val()); + }); + + i = 0; + $('table.pid_tuning tr.MAG input').each(function() { + PIDs[8][i++] = parseFloat($(this).val()); + }); + + var PID_buffer_out = new Array(); + for (var i = 0, needle = 0; i < PIDs.length; i++, needle += 3) { + switch (i) { + case 0: + case 1: + case 2: + case 3: + case 7: + case 8: + case 9: + PID_buffer_out[needle] = parseInt(PIDs[i][0] * 10); + PID_buffer_out[needle + 1] = parseInt(PIDs[i][1] * 1000); + PID_buffer_out[needle + 2] = parseInt(PIDs[i][2]); + break; + case 4: + PID_buffer_out[needle] = parseInt(PIDs[i][0] * 100); + PID_buffer_out[needle + 1] = parseInt(PIDs[i][1] * 100); + PID_buffer_out[needle + 2] = parseInt(PIDs[i][2]); + break; + case 5: + case 6: + PID_buffer_out[needle] = parseInt(PIDs[i][0] * 10); + PID_buffer_out[needle + 1] = parseInt(PIDs[i][1] * 100); + PID_buffer_out[needle + 2] = parseInt(PIDs[i][2] * 1000); + break; + } + } + + // Send over the PID changes + send_message(MSP_codes.MSP_SET_PID, PID_buffer_out, false, send_rc_tuning_changes); + + function send_rc_tuning_changes() { + // catch RC_tuning changes + RC_tuning.roll_pitch_rate = parseFloat($('.rate-tpa input[name="roll-pitch"]').val()); + RC_tuning.yaw_rate = parseFloat($('.rate-tpa input[name="yaw"]').val()); + RC_tuning.dynamic_THR_PID = parseFloat($('.rate-tpa input[name="tpa"]').val()); + + var RC_tuning_buffer_out = new Array(); + RC_tuning_buffer_out[0] = parseInt(RC_tuning.RC_RATE * 100); + RC_tuning_buffer_out[1] = parseInt(RC_tuning.RC_EXPO * 100); + RC_tuning_buffer_out[2] = parseInt(RC_tuning.roll_pitch_rate * 100); + RC_tuning_buffer_out[3] = parseInt(RC_tuning.yaw_rate * 100); + RC_tuning_buffer_out[4] = parseInt(RC_tuning.dynamic_THR_PID * 100); + RC_tuning_buffer_out[5] = parseInt(RC_tuning.throttle_MID * 100); + 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); + } + + function save_to_eeprom() { + send_message(MSP_codes.MSP_EEPROM_WRITE, MSP_codes.MSP_EEPROM_WRITE, false, function() { + GUI.log('EEPROM saved'); + + var element = $('a.update'); + element.addClass('success'); + + GUI.timeout_add('success_highlight', function() { + element.removeClass('success'); + }, 2000); + }); + } + }); + + // enable data pulling + GUI.interval_add('pid_data_poll', function() { + send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS); + }, 50); + } } \ No newline at end of file diff --git a/tabs/receiver.js b/tabs/receiver.js index f54fdab7..078538ba 100644 --- a/tabs/receiver.js +++ b/tabs/receiver.js @@ -2,9 +2,125 @@ function tab_initialize_receiver() { ga_tracker.sendAppView('Receiver Page'); GUI.active_tab = 'receiver'; - send_message(MSP_codes.MSP_RC_TUNING, MSP_codes.MSP_RC_TUNING, false, function() { - send_message(MSP_codes.MSP_RC, MSP_codes.MSP_RC, false, function() { - $('#content').load("./tabs/receiver.html", function() { + send_message(MSP_codes.MSP_RC_TUNING, MSP_codes.MSP_RC_TUNING, false, get_rc_data); + + function get_rc_data() { + send_message(MSP_codes.MSP_RC, MSP_codes.MSP_RC, false, load_html); + } + + function load_html() { + $('#content').load("./tabs/receiver.html", process_html); + } + + function process_html() { + // fill in data from RC_tuning + $('.tunings .throttle input[name="mid"]').val(RC_tuning.throttle_MID.toFixed(2)); + $('.tunings .throttle input[name="expo"]').val(RC_tuning.throttle_EXPO.toFixed(2)); + + $('.tunings .rate input[name="rate"]').val(RC_tuning.RC_RATE.toFixed(2)); + $('.tunings .rate input[name="expo"]').val(RC_tuning.RC_EXPO.toFixed(2)); + + // Setup plot variables and plot it self + var samples_i = 300; + + RX_plot_data = new Array(8); + for (var i = 0; i < 8; i++) { + RX_plot_data[i] = new Array(); + } + + for (var i = 0; i <= 300; i++) { + RX_plot_data[0].push([i, 0]); + RX_plot_data[1].push([i, 0]); + RX_plot_data[2].push([i, 0]); + RX_plot_data[3].push([i, 0]); + RX_plot_data[4].push([i, 0]); + RX_plot_data[5].push([i, 0]); + RX_plot_data[6].push([i, 0]); + RX_plot_data[7].push([i, 0]); + } + + e_RX_plot = document.getElementById("RX_plot"); + + RX_plot_options = { + title: "Channel width (us)", + shadowSize: 0, + yaxis : { + max: 2200, + min: 800, + noTicks: 10 + }, + xaxis : { + //noTicks = 0 + }, + grid : { + backgroundColor: "#FFFFFF" + }, + legend : { + position: "we", + backgroundOpacity: 0 + } + }; + + chrome.storage.local.get('rx_refresh_rate', function(result) { + if (typeof result.rx_refresh_rate != 'undefined') { + $('select[name="rx_refresh_rate"]').val(result.rx_refresh_rate).change(); + } else { + $('select[name="rx_refresh_rate"]').change(); // start with default value + } + }); + + // UI Hooks + // curves + $('.tunings .throttle input').change(function() { + setTimeout(function() { + var mid = parseFloat($('.tunings .throttle input[name="mid"]').val()); + var expo = parseFloat($('.tunings .throttle input[name="expo"]').val()); + + var throttle_curve = $('.throttle_curve canvas').get(0); + var context = throttle_curve.getContext("2d"); + context.clearRect(0, 0, 220, 58); + + // math magic by englishman + var midx = 220 * mid; + var midxl = midx * .5; + var midxr = (((220 - midx) * .5) + midx); + var midy = 58 - (midx * (58 / 220)); + var midyl = 58 - ((58 - midy) * .5 *(expo + 1)); + var midyr = (midy / 2) * (expo + 1); + + context.beginPath(); + context.moveTo(0, 58); + context.quadraticCurveTo(midxl, midyl, midx, midy); + context.moveTo(midx, midy); + context.quadraticCurveTo(midxr, midyr, 220, 0); + + context.lineWidth = 2; + context.stroke(); + }, 0); // race condition, that should always trigger after all events are processed + }).change(); + + $('.tunings .rate input').change(function() { + setTimeout(function() { + var rate = parseFloat($('.tunings .rate input[name="rate"]').val()); + var expo = parseFloat($('.tunings .rate input[name="expo"]').val()); + + var pitch_roll_curve = $('.pitch_roll_curve canvas').get(0); + var context = pitch_roll_curve.getContext("2d"); + context.clearRect(0, 0, 220, 58); + + // math magic by englishman + var ratey = 58 * rate; + + context.beginPath(); + context.moveTo(0, 58); + context.quadraticCurveTo(110, 58 - ((ratey / 2) * (1 - expo)), 220, 58 - ratey); + context.lineWidth = 2; + context.stroke(); + }, 0); // race condition, that should always trigger after all events are processed + }).change(); + + $('a.refresh').click(function() { + send_message(MSP_codes.MSP_RC_TUNING, MSP_codes.MSP_RC_TUNING, false, function() { // fill in data from RC_tuning $('.tunings .throttle input[name="mid"]').val(RC_tuning.throttle_MID.toFixed(2)); $('.tunings .throttle input[name="expo"]').val(RC_tuning.throttle_EXPO.toFixed(2)); @@ -12,231 +128,127 @@ function tab_initialize_receiver() { $('.tunings .rate input[name="rate"]').val(RC_tuning.RC_RATE.toFixed(2)); $('.tunings .rate input[name="expo"]').val(RC_tuning.RC_EXPO.toFixed(2)); - // Setup plot variables and plot it self - var samples_i = 300; - - RX_plot_data = new Array(8); - for (var i = 0; i < 8; i++) { - RX_plot_data[i] = new Array(); - } - - for (var i = 0; i <= 300; i++) { - RX_plot_data[0].push([i, 0]); - RX_plot_data[1].push([i, 0]); - RX_plot_data[2].push([i, 0]); - RX_plot_data[3].push([i, 0]); - RX_plot_data[4].push([i, 0]); - RX_plot_data[5].push([i, 0]); - RX_plot_data[6].push([i, 0]); - RX_plot_data[7].push([i, 0]); - } - - e_RX_plot = document.getElementById("RX_plot"); - - RX_plot_options = { - title: "Channel width (us)", - shadowSize: 0, - yaxis : { - max: 2200, - min: 800, - noTicks: 10 - }, - xaxis : { - //noTicks = 0 - }, - grid : { - backgroundColor: "#FFFFFF" - }, - legend : { - position: "we", - backgroundOpacity: 0 - } - }; - - chrome.storage.local.get('rx_refresh_rate', function(result) { - if (typeof result.rx_refresh_rate != 'undefined') { - $('select[name="rx_refresh_rate"]').val(result.rx_refresh_rate).change(); - } else { - $('select[name="rx_refresh_rate"]').change(); // start with default value - } - }); - - // UI Hooks - // curves - $('.tunings .throttle input').change(function() { - setTimeout(function() { - var mid = parseFloat($('.tunings .throttle input[name="mid"]').val()); - var expo = parseFloat($('.tunings .throttle input[name="expo"]').val()); - - var throttle_curve = $('.throttle_curve canvas').get(0); - var context = throttle_curve.getContext("2d"); - context.clearRect(0, 0, 220, 58); - - // math magic by englishman - var midx = 220 * mid; - var midxl = midx * .5; - var midxr = (((220 - midx) * .5) + midx); - var midy = 58 - (midx * (58 / 220)); - var midyl = 58 - ((58 - midy) * .5 *(expo + 1)); - var midyr = (midy / 2) * (expo + 1); - - context.beginPath(); - context.moveTo(0, 58); - context.quadraticCurveTo(midxl, midyl, midx, midy); - context.moveTo(midx, midy); - context.quadraticCurveTo(midxr, midyr, 220, 0); - - context.lineWidth = 2; - context.stroke(); - }, 0); // race condition, that should always trigger after all events are processed - }).change(); - - $('.tunings .rate input').change(function() { - setTimeout(function() { - var rate = parseFloat($('.tunings .rate input[name="rate"]').val()); - var expo = parseFloat($('.tunings .rate input[name="expo"]').val()); - - var pitch_roll_curve = $('.pitch_roll_curve canvas').get(0); - var context = pitch_roll_curve.getContext("2d"); - context.clearRect(0, 0, 220, 58); - - // math magic by englishman - var ratey = 58 * rate; - - context.beginPath(); - context.moveTo(0, 58); - context.quadraticCurveTo(110, 58 - ((ratey / 2) * (1 - expo)), 220, 58 - ratey); - context.lineWidth = 2; - context.stroke(); - }, 0); // race condition, that should always trigger after all events are processed - }).change(); - - $('a.refresh').click(function() { - send_message(MSP_codes.MSP_RC_TUNING, MSP_codes.MSP_RC_TUNING, false, function() { - // fill in data from RC_tuning - $('.tunings .throttle input[name="mid"]').val(RC_tuning.throttle_MID.toFixed(2)); - $('.tunings .throttle input[name="expo"]').val(RC_tuning.throttle_EXPO.toFixed(2)); - - $('.tunings .rate input[name="rate"]').val(RC_tuning.RC_RATE.toFixed(2)); - $('.tunings .rate input[name="expo"]').val(RC_tuning.RC_EXPO.toFixed(2)); - - // update visual representation - $('.tunings .throttle input').change(); - $('.tunings .rate input').change(); - }); - }); - - $('a.update').click(function() { - // catch RC_tuning changes - RC_tuning.throttle_MID = parseFloat($('.tunings .throttle input[name="mid"]').val()); - RC_tuning.throttle_EXPO = parseFloat($('.tunings .throttle input[name="expo"]').val()); - - RC_tuning.RC_RATE = parseFloat($('.tunings .rate input[name="rate"]').val()); - RC_tuning.RC_EXPO = parseFloat($('.tunings .rate input[name="expo"]').val()); - - var RC_tuning_buffer_out = new Array(); - RC_tuning_buffer_out[0] = parseInt(RC_tuning.RC_RATE * 100); - RC_tuning_buffer_out[1] = parseInt(RC_tuning.RC_EXPO * 100); - RC_tuning_buffer_out[2] = parseInt(RC_tuning.roll_pitch_rate * 100); - RC_tuning_buffer_out[3] = parseInt(RC_tuning.yaw_rate * 100); - RC_tuning_buffer_out[4] = parseInt(RC_tuning.dynamic_THR_PID * 100); - RC_tuning_buffer_out[5] = parseInt(RC_tuning.throttle_MID * 100); - 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); - - // Save changes to EEPROM - send_message(MSP_codes.MSP_EEPROM_WRITE, MSP_codes.MSP_EEPROM_WRITE, false, function() { - GUI.log('EEPROM saved'); - - var element = $('a.update'); - element.addClass('success'); - - GUI.timeout_add('success_highlight', function() { - element.removeClass('success'); - }, 2000); - }); - }); - - $('select[name="rx_refresh_rate"]').change(function() { - var plot_update_rate = parseInt($(this).val()); - - // timer initialization - GUI.interval_remove('receiver_poll'); - - // enable RC data pulling - GUI.interval_add('receiver_poll', function() { - // Update UI with latest data - $('.tab-receiver meter:eq(0)').val(RC.throttle); - $('.tab-receiver .value:eq(0)').html(RC.throttle); - - $('.tab-receiver meter:eq(1)').val(RC.pitch); - $('.tab-receiver .value:eq(1)').html(RC.pitch); - - $('.tab-receiver meter:eq(2)').val(RC.roll); - $('.tab-receiver .value:eq(2)').html(RC.roll); - - $('.tab-receiver meter:eq(3)').val(RC.yaw); - $('.tab-receiver .value:eq(3)').html(RC.yaw); - - - $('.tab-receiver meter:eq(4)').val(RC.AUX1); - $('.tab-receiver .value:eq(4)').html(RC.AUX1); - - $('.tab-receiver meter:eq(5)').val(RC.AUX2); - $('.tab-receiver .value:eq(5)').html(RC.AUX2); - - $('.tab-receiver meter:eq(6)').val(RC.AUX3); - $('.tab-receiver .value:eq(6)').html(RC.AUX3); - - $('.tab-receiver meter:eq(7)').val(RC.AUX4); - $('.tab-receiver .value:eq(7)').html(RC.AUX4); - - // push latest data to the main array - RX_plot_data[0].push([samples_i, RC.throttle]); - RX_plot_data[1].push([samples_i, RC.pitch]); - RX_plot_data[2].push([samples_i, RC.roll]); - RX_plot_data[3].push([samples_i, RC.yaw]); - RX_plot_data[4].push([samples_i, RC.AUX1]); - RX_plot_data[5].push([samples_i, RC.AUX2]); - RX_plot_data[6].push([samples_i, RC.AUX3]); - RX_plot_data[7].push([samples_i, RC.AUX4]); - - // Remove old data from array - while (RX_plot_data[0].length > 300) { - RX_plot_data[0].shift(); - RX_plot_data[1].shift(); - RX_plot_data[2].shift(); - RX_plot_data[3].shift(); - RX_plot_data[4].shift(); - RX_plot_data[5].shift(); - RX_plot_data[6].shift(); - RX_plot_data[7].shift(); - }; - - // redraw plot - Flotr.draw(e_RX_plot, [ - {data: RX_plot_data[0], label: "THROTTLE"}, - {data: RX_plot_data[1], label: "PITCH"}, - {data: RX_plot_data[2], label: "ROLL"}, - {data: RX_plot_data[3], label: "YAW"}, - {data: RX_plot_data[4], label: "AUX1"}, - {data: RX_plot_data[5], label: "AUX2"}, - {data: RX_plot_data[6], label: "AUX3"}, - {data: RX_plot_data[7], label: "AUX4"} ], RX_plot_options); - - samples_i++; - - // Request new data - send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS); - send_message(MSP_codes.MSP_RC, MSP_codes.MSP_RC); - }, plot_update_rate, true); - - chrome.storage.local.set({'rx_refresh_rate': plot_update_rate}); - }); - + // update visual representation + $('.tunings .throttle input').change(); + $('.tunings .rate input').change(); }); }); - }); + + $('a.update').click(function() { + // catch RC_tuning changes + RC_tuning.throttle_MID = parseFloat($('.tunings .throttle input[name="mid"]').val()); + RC_tuning.throttle_EXPO = parseFloat($('.tunings .throttle input[name="expo"]').val()); + + RC_tuning.RC_RATE = parseFloat($('.tunings .rate input[name="rate"]').val()); + RC_tuning.RC_EXPO = parseFloat($('.tunings .rate input[name="expo"]').val()); + + var RC_tuning_buffer_out = new Array(); + RC_tuning_buffer_out[0] = parseInt(RC_tuning.RC_RATE * 100); + RC_tuning_buffer_out[1] = parseInt(RC_tuning.RC_EXPO * 100); + RC_tuning_buffer_out[2] = parseInt(RC_tuning.roll_pitch_rate * 100); + RC_tuning_buffer_out[3] = parseInt(RC_tuning.yaw_rate * 100); + RC_tuning_buffer_out[4] = parseInt(RC_tuning.dynamic_THR_PID * 100); + RC_tuning_buffer_out[5] = parseInt(RC_tuning.throttle_MID * 100); + 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); + + function save_to_eeprom() { + send_message(MSP_codes.MSP_EEPROM_WRITE, MSP_codes.MSP_EEPROM_WRITE, false, function() { + GUI.log('EEPROM saved'); + + var element = $('a.update'); + element.addClass('success'); + + GUI.timeout_add('success_highlight', function() { + element.removeClass('success'); + }, 2000); + }); + } + }); + + $('select[name="rx_refresh_rate"]').change(function() { + var plot_update_rate = parseInt($(this).val()); + + // save update rate + chrome.storage.local.set({'rx_refresh_rate': plot_update_rate}); + + function get_status_data() { + send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS, false, get_rc_data); + } + + function get_rc_data() { + send_message(MSP_codes.MSP_RC, MSP_codes.MSP_RC, false, update_ui); + } + + function update_ui() { + $('.tab-receiver meter:eq(0)').val(RC.throttle); + $('.tab-receiver .value:eq(0)').html(RC.throttle); + + $('.tab-receiver meter:eq(1)').val(RC.pitch); + $('.tab-receiver .value:eq(1)').html(RC.pitch); + + $('.tab-receiver meter:eq(2)').val(RC.roll); + $('.tab-receiver .value:eq(2)').html(RC.roll); + + $('.tab-receiver meter:eq(3)').val(RC.yaw); + $('.tab-receiver .value:eq(3)').html(RC.yaw); + + + $('.tab-receiver meter:eq(4)').val(RC.AUX1); + $('.tab-receiver .value:eq(4)').html(RC.AUX1); + + $('.tab-receiver meter:eq(5)').val(RC.AUX2); + $('.tab-receiver .value:eq(5)').html(RC.AUX2); + + $('.tab-receiver meter:eq(6)').val(RC.AUX3); + $('.tab-receiver .value:eq(6)').html(RC.AUX3); + + $('.tab-receiver meter:eq(7)').val(RC.AUX4); + $('.tab-receiver .value:eq(7)').html(RC.AUX4); + + // push latest data to the main array + RX_plot_data[0].push([samples_i, RC.throttle]); + RX_plot_data[1].push([samples_i, RC.pitch]); + RX_plot_data[2].push([samples_i, RC.roll]); + RX_plot_data[3].push([samples_i, RC.yaw]); + RX_plot_data[4].push([samples_i, RC.AUX1]); + RX_plot_data[5].push([samples_i, RC.AUX2]); + RX_plot_data[6].push([samples_i, RC.AUX3]); + RX_plot_data[7].push([samples_i, RC.AUX4]); + + // Remove old data from array + while (RX_plot_data[0].length > 300) { + RX_plot_data[0].shift(); + RX_plot_data[1].shift(); + RX_plot_data[2].shift(); + RX_plot_data[3].shift(); + RX_plot_data[4].shift(); + RX_plot_data[5].shift(); + RX_plot_data[6].shift(); + RX_plot_data[7].shift(); + }; + + // redraw plot + Flotr.draw(e_RX_plot, [ + {data: RX_plot_data[0], label: "THROTTLE"}, + {data: RX_plot_data[1], label: "PITCH"}, + {data: RX_plot_data[2], label: "ROLL"}, + {data: RX_plot_data[3], label: "YAW"}, + {data: RX_plot_data[4], label: "AUX1"}, + {data: RX_plot_data[5], label: "AUX2"}, + {data: RX_plot_data[6], label: "AUX3"}, + {data: RX_plot_data[7], label: "AUX4"} ], RX_plot_options); + + samples_i++; + } + + // timer initialization + GUI.interval_remove('receiver_poll'); + + // enable RC data pulling + GUI.interval_add('receiver_poll', get_status_data, plot_update_rate, true); + }); + } } \ No newline at end of file diff --git a/tabs/sensors.js b/tabs/sensors.js index bc26cf9c..43bd6f96 100644 --- a/tabs/sensors.js +++ b/tabs/sensors.js @@ -198,7 +198,6 @@ function tab_initialize_sensors() { 'debug': parseInt($('.tab-sensors select').eq(4).val()) }; - // handling of "data pulling" is a little bit funky here, as MSP_RAW_IMU contains values for gyro/accel/mag but not baro // this means that setting a slower refresh rate on any of the attributes would have no effect // what we will do instead is = determinate the fastest refresh rate for those 3 attributes, use that as a "polling rate" @@ -213,6 +212,9 @@ function tab_initialize_sensors() { fastest = rates.mag; } + // store current/latest refresh rates in the storage + chrome.storage.local.set({'sensor_refresh_rates': rates}); + // timer initialization GUI.interval_kill_all(['port_handler', 'port_usage']); @@ -236,7 +238,7 @@ function tab_initialize_sensors() { } Flotr.draw(e_graph_baro, [ - {data: baro_data[0], label: "X - meters [" + SENSOR_DATA.altitude.toFixed(2) + "]"} ], baro_options); + {data: baro_data[0], label: "Meters [" + SENSOR_DATA.altitude.toFixed(2) + "]"} ], baro_options); samples_baro_i++; }, rates.baro); @@ -319,15 +321,12 @@ function tab_initialize_sensors() { } Flotr.draw(e_graph_mag, [ - {data: mag_data[1], label: "X - Ga [" + SENSOR_DATA.magnetometer[0].toFixed(2) + "]"}, - {data: mag_data[0], label: "Y - Ga [" + SENSOR_DATA.magnetometer[1].toFixed(2) + "]"}, - {data: mag_data[2], label: "Z - Ga [" + SENSOR_DATA.magnetometer[2].toFixed(2) + "]"} ], mag_options); + {data: mag_data[1], label: "X - gauss [" + SENSOR_DATA.magnetometer[0].toFixed(2) + "]"}, + {data: mag_data[0], label: "Y - gauss [" + SENSOR_DATA.magnetometer[1].toFixed(2) + "]"}, + {data: mag_data[2], label: "Z - gauss [" + SENSOR_DATA.magnetometer[2].toFixed(2) + "]"} ], mag_options); samples_mag_i++; }, rates.mag, true); - - // store current/latest refresh rates in the storage - chrome.storage.local.set({'sensor_refresh_rates': rates}); }); }); } \ No newline at end of file diff --git a/tabs/servos.js b/tabs/servos.js index 33791e76..2a49c6fc 100644 --- a/tabs/servos.js +++ b/tabs/servos.js @@ -9,289 +9,296 @@ function tab_initialize_servos() { ga_tracker.sendAppView('Servos'); GUI.active_tab = 'servos'; - // request current Servos Config - send_message(MSP_codes.MSP_IDENT, MSP_codes.MSP_IDENT, false, function() { - send_message(MSP_codes.MSP_SERVO_CONF, MSP_codes.MSP_SERVO_CONF, false, function() { - send_message(MSP_codes.MSP_BOXNAMES, MSP_codes.MSP_BOXNAMES, false, function() { - $('#content').load("./tabs/servos.html", function() { - // drop previous table - $('div.tab-servos table.fields tr:not(:first)').remove(); + send_message(MSP_codes.MSP_IDENT, MSP_codes.MSP_IDENT, false, get_servo_conf_data); - var model = $('div.tab-servos strong.model'); - var supported_models = [1, 4, 5, 8, 14, 20, 21]; + function get_servo_conf_data() { + send_message(MSP_codes.MSP_SERVO_CONF, MSP_codes.MSP_SERVO_CONF, false, get_boxnames_data); + } - switch (CONFIG.multiType) { - case 1: // TRI - // looking ok so far - model.html('TRI'); + function get_boxnames_data() { + send_message(MSP_codes.MSP_BOXNAMES, MSP_codes.MSP_BOXNAMES, false, load_html); + } - process_directions('YAW', 5, 0); + function load_html() { + $('#content').load("./tabs/servos.html", process_html); + } - process_servos('Yaw Servo', '', 5, false); - break; - case 4: // BI - // looking ok so far - model.html('BI'); + function process_html() { + function process_directions(name, obj, bitpos) { + $('div.direction_wrapper').show(); - process_directions('L YAW', 4, 1); - process_directions('R YAW', 5, 1); - process_directions('L NICK', 4, 0); - process_directions('R NICK', 5, 0); + var val; - process_servos('Left Servo', '', 4, false); - process_servos('Right Servo', '', 5, false); - break; - case 5: // Gimbal - // needs to be verified - model.html('Gimbal'); + $('div.tab-servos table.directions').append('\ + \ + ' + name + '\ + \ + \ + \ + \ + '); - // rate - process_servos('Pitch Servo', '', 0, 2); - process_servos('Roll Servo', '', 1, 2); - break; - case 8: // Flying Wing - // looking ok so far - model.html('Flying Wing'); + if (bit_check(SERVO_CONFIG[obj].rate, bitpos)) val = 1; + else val = 0; - process_directions('L ROLL', 3, 1); - process_directions('R ROLL', 4, 1); - process_directions('L NICK', 3, 0); - process_directions('R NICK', 4, 0); + $('div.tab-servos table.directions tr:last select').val(val); + $('div.tab-servos table.directions tr:last select').data('info', {'obj': obj, 'bitpos': bitpos}); + } - process_servos('Left Wing', '', 3, false); - process_servos('Right Wing', '', 4, false); - break; - case 14: // Airplane - model.html('Airplane'); + function process_servos(name, alternate, obj, directions) { + $('div.supported_wrapper').show(); - // rate - process_servos('Wing 1', '', 3, 2); - process_servos('Wing 2', '', 4, 2); - process_servos('Rudd', '', 5, 2); - process_servos('Elev', '', 6, 2); - break; - case 20: // Dualcopter - // looking ok so far - model.html('Dualcopter'); + $('div.tab-servos table.fields').append('\ + \ + ' + name + '\ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + ' + name + '\ + ' + alternate + '\ + \ + \ + '); - process_directions('PITCH', 4, 0); - process_directions('ROLL', 5, 0); + if (SERVO_CONFIG[obj].middle <= 7) { + $('div.tab-servos table.fields tr:last td.middle input').prop('disabled', true); + $('div.tab-servos table.fields tr:last td.channel').find('input').eq(SERVO_CONFIG[obj].middle).prop('checked', true); + } - process_servos('Roll', '', 5, false); - process_servos('Nick', '', 4, false); - break; - case 21: // Singlecopter - // looking ok so far - model.html('Singlecopter'); + if (directions == true) { + $('div.tab-servos table.fields tr:last td.direction input:first').prop('checked', bit_check(SERVO_CONFIG[obj].rate, 0)); + $('div.tab-servos table.fields tr:last td.direction input:last').prop('checked', bit_check(SERVO_CONFIG[obj].rate, 1)); + } else if (directions == 2) { + // removing checkboxes + $('div.tab-servos table.fields tr:last td.direction').html(''); - process_servos('Right', 'R YAW', 3, true); - process_servos('Left', 'L YAW', 4, true); - process_servos('Front', 'F YAW', 5, true); - process_servos('Rear', 'YAW', 6, true); - break; + // adding select box and generating options + $('div.tab-servos table.fields tr:last td.direction').append('\ + \ + '); - default: - model.html("This model doesn't support servos"); + var select = $('div.tab-servos table.fields tr:last td.direction select'); - // implementation of feature servo_tilt - if (AUX_CONFIG.indexOf('CAMSTAB') > -1 || AUX_CONFIG.indexOf('CAMTRIG') > -1) { - // Gimbal on - // needs to be verified - model.html('Gimbal / Tilt Servos'); + for (var i = 100; i > -101; i--) { + select.append(''); + } - // rate - process_servos('Pitch Servo', '', 0, 2); - process_servos('Roll Servo', '', 1, 2); - } - } + // select current rate + select.val(SERVO_CONFIG[obj].rate); + } else { + // removing checkboxes + $('div.tab-servos table.fields tr:last td.direction').html(''); + } - // UI hooks for dynamically generated elements - $('table.directions select, table.directions input, table.fields select, table.fields input').change(function() { - if ($('div.live input').is(':checked')) { - // apply small delay as there seems to be some funky update business going wrong - GUI.timeout_add('servos_update', servos_update, 10); - } - }); + $('div.tab-servos table.fields tr:last').data('info', {'obj': obj}); - $('a.update').click(function() { - // standard check for supported_models + custom implementation for feature servo_tilt - if (supported_models.indexOf(CONFIG.multiType) != -1 || AUX_CONFIG.indexOf('CAMSTAB') > -1 || AUX_CONFIG.indexOf('CAMTRIG') > -1) { - servos_update(true); - } - }); - - // enable data pulling - GUI.interval_add('servos_data_poll', function() { - send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS); - }, 50); - }); + // UI hooks + $('div.tab-servos table.fields tr:last td.channel').find('input').click(function() { + if($(this).is(':checked')) { + $(this).parent().parent().find('td.middle input').prop('disabled', true); + $(this).parent().find('input').not($(this)).prop('checked', false); + } else { + $(this).parent().parent().find('td.middle input').prop('disabled', false).val(1500); + } }); + } + + function servos_update(save_to_eeprom) { + // update bitfields + $('div.tab-servos table.directions tr:not(".main")').each(function() { + var info = $('select', this).data('info'); + var val = parseInt($('select', this).val()); + + // in this stage we need to know which bitfield and which bitposition needs to be flipped + if (val) SERVO_CONFIG[info.obj].rate = bit_set(SERVO_CONFIG[info.obj].rate, info.bitpos); + else SERVO_CONFIG[info.obj].rate = bit_clear(SERVO_CONFIG[info.obj].rate, info.bitpos); + }); + + // update the rest + $('div.tab-servos table.fields tr:not(".main")').each(function() { + var info = $(this).data('info'); + + if ($('.middle input', this).is(':disabled')) { + var val = $('.channel input:checked', this).index(); + + SERVO_CONFIG[info.obj].middle = parseInt(val); + } else { + SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val()); + } + + SERVO_CONFIG[info.obj].min = parseInt($('.min input', this).val()); + SERVO_CONFIG[info.obj].max = parseInt($('.max input', this).val()); + + // update rate if direction fields exist + if ($('.direction input', this).length) { + if ($('.direction input:first', this).is(':checked')) SERVO_CONFIG[info.obj].rate = bit_set(SERVO_CONFIG[info.obj].rate, 0); + else SERVO_CONFIG[info.obj].rate = bit_clear(SERVO_CONFIG[info.obj].rate, 0); + + if ($('.direction input:last', this).is(':checked')) SERVO_CONFIG[info.obj].rate = bit_set(SERVO_CONFIG[info.obj].rate, 1); + else SERVO_CONFIG[info.obj].rate = bit_clear(SERVO_CONFIG[info.obj].rate, 1); + } else if ($('.direction select', this).length) { + var val = parseInt($('.direction select', this).val()); + SERVO_CONFIG[info.obj].rate = val; + } + }); + + // send settings over to mcu + var buffer_out = []; + + var needle = 0; + for (var i = 0; i < SERVO_CONFIG.length; i++) { + buffer_out[needle++] = lowByte(SERVO_CONFIG[i].min); + buffer_out[needle++] = highByte(SERVO_CONFIG[i].min); + + buffer_out[needle++] = lowByte(SERVO_CONFIG[i].max); + buffer_out[needle++] = highByte(SERVO_CONFIG[i].max); + + buffer_out[needle++] = lowByte(SERVO_CONFIG[i].middle); + buffer_out[needle++] = highByte(SERVO_CONFIG[i].middle); + + buffer_out[needle++] = lowByte(SERVO_CONFIG[i].rate); + } + + 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, MSP_codes.MSP_EEPROM_WRITE, false, function() { + GUI.log('EEPROM saved'); + + var element = $('a.update'); + element.addClass('success'); + + GUI.timeout_add('success_highlight', function() { + element.removeClass('success'); + }, 2000); + }); + } + } + + // drop previous table + $('div.tab-servos table.fields tr:not(:first)').remove(); + + var model = $('div.tab-servos strong.model'); + var supported_models = [1, 4, 5, 8, 14, 20, 21]; + + switch (CONFIG.multiType) { + case 1: // TRI + // looking ok so far + model.html('TRI'); + + process_directions('YAW', 5, 0); + + process_servos('Yaw Servo', '', 5, false); + break; + case 4: // BI + // looking ok so far + model.html('BI'); + + process_directions('L YAW', 4, 1); + process_directions('R YAW', 5, 1); + process_directions('L NICK', 4, 0); + process_directions('R NICK', 5, 0); + + process_servos('Left Servo', '', 4, false); + process_servos('Right Servo', '', 5, false); + break; + case 5: // Gimbal + // needs to be verified + model.html('Gimbal'); + + // rate + process_servos('Pitch Servo', '', 0, 2); + process_servos('Roll Servo', '', 1, 2); + break; + case 8: // Flying Wing + // looking ok so far + model.html('Flying Wing'); + + process_directions('L ROLL', 3, 1); + process_directions('R ROLL', 4, 1); + process_directions('L NICK', 3, 0); + process_directions('R NICK', 4, 0); + + process_servos('Left Wing', '', 3, false); + process_servos('Right Wing', '', 4, false); + break; + case 14: // Airplane + model.html('Airplane'); + + // rate + process_servos('Wing 1', '', 3, 2); + process_servos('Wing 2', '', 4, 2); + process_servos('Rudd', '', 5, 2); + process_servos('Elev', '', 6, 2); + break; + case 20: // Dualcopter + // looking ok so far + model.html('Dualcopter'); + + process_directions('PITCH', 4, 0); + process_directions('ROLL', 5, 0); + + process_servos('Roll', '', 5, false); + process_servos('Nick', '', 4, false); + break; + case 21: // Singlecopter + // looking ok so far + model.html('Singlecopter'); + + process_servos('Right', 'R YAW', 3, true); + process_servos('Left', 'L YAW', 4, true); + process_servos('Front', 'F YAW', 5, true); + process_servos('Rear', 'YAW', 6, true); + break; + + default: + model.html("This model doesn't support servos"); + + // implementation of feature servo_tilt + if (AUX_CONFIG.indexOf('CAMSTAB') > -1 || AUX_CONFIG.indexOf('CAMTRIG') > -1) { + // Gimbal on + // needs to be verified + model.html('Gimbal / Tilt Servos'); + + // rate + process_servos('Pitch Servo', '', 0, 2); + process_servos('Roll Servo', '', 1, 2); + } + } + + // UI hooks for dynamically generated elements + $('table.directions select, table.directions input, table.fields select, table.fields input').change(function() { + if ($('div.live input').is(':checked')) { + // apply small delay as there seems to be some funky update business going wrong + GUI.timeout_add('servos_update', servos_update, 10); + } }); - }); -} -function servos_update(save_to_eeprom) { - // update bitfields - $('div.tab-servos table.directions tr:not(".main")').each(function() { - var info = $('select', this).data('info'); - var val = parseInt($('select', this).val()); - - // in this stage we need to know which bitfield and which bitposition needs to be flipped - if (val) SERVO_CONFIG[info.obj].rate = bit_set(SERVO_CONFIG[info.obj].rate, info.bitpos); - else SERVO_CONFIG[info.obj].rate = bit_clear(SERVO_CONFIG[info.obj].rate, info.bitpos); - }); - - // update the rest - $('div.tab-servos table.fields tr:not(".main")').each(function() { - var info = $(this).data('info'); - - if ($('.middle input', this).is(':disabled')) { - var val = $('.channel input:checked', this).index(); - - SERVO_CONFIG[info.obj].middle = parseInt(val); - } else { - SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val()); - } - - SERVO_CONFIG[info.obj].min = parseInt($('.min input', this).val()); - SERVO_CONFIG[info.obj].max = parseInt($('.max input', this).val()); - - // update rate if direction fields exist - if ($('.direction input', this).length) { - if ($('.direction input:first', this).is(':checked')) SERVO_CONFIG[info.obj].rate = bit_set(SERVO_CONFIG[info.obj].rate, 0); - else SERVO_CONFIG[info.obj].rate = bit_clear(SERVO_CONFIG[info.obj].rate, 0); - - if ($('.direction input:last', this).is(':checked')) SERVO_CONFIG[info.obj].rate = bit_set(SERVO_CONFIG[info.obj].rate, 1); - else SERVO_CONFIG[info.obj].rate = bit_clear(SERVO_CONFIG[info.obj].rate, 1); - } else if ($('.direction select', this).length) { - var val = parseInt($('.direction select', this).val()); - SERVO_CONFIG[info.obj].rate = val; - } - }); - - // send settings over to mcu - var buffer_out = []; - - var needle = 0; - for (var i = 0; i < SERVO_CONFIG.length; i++) { - buffer_out[needle++] = lowByte(SERVO_CONFIG[i].min); - buffer_out[needle++] = highByte(SERVO_CONFIG[i].min); - - buffer_out[needle++] = lowByte(SERVO_CONFIG[i].max); - buffer_out[needle++] = highByte(SERVO_CONFIG[i].max); - - buffer_out[needle++] = lowByte(SERVO_CONFIG[i].middle); - buffer_out[needle++] = highByte(SERVO_CONFIG[i].middle); - - buffer_out[needle++] = lowByte(SERVO_CONFIG[i].rate); - } - - 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, MSP_codes.MSP_EEPROM_WRITE, false, function() { - GUI.log('EEPROM saved'); - - var element = $('a.update'); - element.addClass('success'); - - GUI.timeout_add('success_highlight', function() { - element.removeClass('success'); - }, 2000); + $('a.update').click(function() { + // standard check for supported_models + custom implementation for feature servo_tilt + if (supported_models.indexOf(CONFIG.multiType) != -1 || AUX_CONFIG.indexOf('CAMSTAB') > -1 || AUX_CONFIG.indexOf('CAMTRIG') > -1) { + servos_update(true); + } }); + + // enable data pulling + GUI.interval_add('servos_data_poll', function() { + send_message(MSP_codes.MSP_STATUS, MSP_codes.MSP_STATUS); + }, 50); } -} - -function process_directions(name, obj, bitpos) { - $('div.direction_wrapper').show(); - - var val; - - $('div.tab-servos table.directions').append('\ - \ - ' + name + '\ - \ - \ - \ - \ - '); - - if (bit_check(SERVO_CONFIG[obj].rate, bitpos)) val = 1; - else val = 0; - - $('div.tab-servos table.directions tr:last select').val(val); - $('div.tab-servos table.directions tr:last select').data('info', {'obj': obj, 'bitpos': bitpos}); -} - -function process_servos(name, alternate, obj, directions) { - $('div.supported_wrapper').show(); - - $('div.tab-servos table.fields').append('\ - \ - ' + name + '\ - \ - \ - \ - \ - \ - \ - \ - \ - \ - \ - \ - \ - \ - \ - ' + name + '\ - ' + alternate + '\ - \ - \ - '); - - if (SERVO_CONFIG[obj].middle <= 7) { - $('div.tab-servos table.fields tr:last td.middle input').prop('disabled', true); - $('div.tab-servos table.fields tr:last td.channel').find('input').eq(SERVO_CONFIG[obj].middle).prop('checked', true); - } - - if (directions == true) { - $('div.tab-servos table.fields tr:last td.direction input:first').prop('checked', bit_check(SERVO_CONFIG[obj].rate, 0)); - $('div.tab-servos table.fields tr:last td.direction input:last').prop('checked', bit_check(SERVO_CONFIG[obj].rate, 1)); - } else if (directions == 2) { - // removing checkboxes - $('div.tab-servos table.fields tr:last td.direction').html(''); - - // adding select box and generating options - $('div.tab-servos table.fields tr:last td.direction').append('\ - \ - '); - - var select = $('div.tab-servos table.fields tr:last td.direction select'); - - for (var i = 100; i > -101; i--) { - select.append(''); - } - - // select current rate - select.val(SERVO_CONFIG[obj].rate); - } else { - // removing checkboxes - $('div.tab-servos table.fields tr:last td.direction').html(''); - } - - $('div.tab-servos table.fields tr:last').data('info', {'obj': obj}); - - // UI hooks - $('div.tab-servos table.fields tr:last td.channel').find('input').click(function() { - if($(this).is(':checked')) { - $(this).parent().parent().find('td.middle input').prop('disabled', true); - $(this).parent().find('input').not($(this)).prop('checked', false); - } else { - $(this).parent().parent().find('td.middle input').prop('disabled', false).val(1500); - } - }); } \ No newline at end of file