betaflight-configurator/tabs/servos.js

304 lines
13 KiB
JavaScript
Raw Normal View History

2013-11-11 04:38:48 +00:00
/* Please don't take code in this file very seriously !!!
I was "kinda" forced to write this implementation "this way" because the Servo code implementation
from multiwii is so horrible, obstructive and non dynamic, not to mention it doesn't make any sense
that there was just no other way around this then hardcoding/implementing each model separately.
*/
'use strict';
2013-11-11 04:38:48 +00:00
TABS.servos = {};
2014-08-12 14:20:26 +00:00
TABS.servos.initialize = function (callback) {
var self = this;
if (GUI.active_tab != 'servos') {
GUI.active_tab = 'servos';
googleAnalytics.sendAppView('Servos');
}
2014-03-08 05:25:15 +00:00
function get_servo_conf_data() {
MSP.send_message(MSP_codes.MSP_SERVO_CONF, false, false, get_channel_forwarding_data);
}
function get_channel_forwarding_data() {
MSP.send_message(MSP_codes.MSP_CHANNEL_FORWARDING, false, false, get_boxnames_data);
}
function get_boxnames_data() {
MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, load_html);
}
function load_html() {
$('#content').load("./tabs/servos.html", process_html);
}
MSP.send_message(MSP_codes.MSP_IDENT, false, false, get_servo_conf_data);
function process_html() {
// translate to user-selected language
localize();
function process_directions(name, obj, bitpos) {
$('div.direction_wrapper').show();
var val;
$('div.tab-servos table.directions').append('\
<tr>\
<td class="name" style="text-align: center">' + name + '</td>\
<td class="direction" style="text-align: right">\
<select name="direction">\
2014-05-06 21:57:57 +00:00
<option value="0">' + chrome.i18n.getMessage('servosNormal') + '</option>\
<option value="1">' + chrome.i18n.getMessage('servosReverse') + '</option>\
</select>\
</td>\
</tr>\
');
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('\
<tr> \
<td style="text-align: center">' + name + '</td>\
<td class="middle"><input type="number" min="1000" max="2000" value="' + SERVO_CONFIG[obj].middle + '" /></td>\
<td class="min"><input type="number" min="1000" max="2000" value="' + SERVO_CONFIG[obj].min +'" /></td>\
<td class="max"><input type="number" min="1000" max="2000" value="' + SERVO_CONFIG[obj].max +'" /></td>\
2014-04-02 13:47:34 +00:00
<td class="channel"><input type="checkbox"/></td>\
<td class="channel"><input type="checkbox"/></td>\
<td class="channel"><input type="checkbox"/></td>\
<td class="channel"><input type="checkbox"/></td>\
<td class="channel"><input type="checkbox"/></td>\
<td class="channel"><input type="checkbox"/></td>\
<td class="channel"><input type="checkbox"/></td>\
<td class="channel"><input type="checkbox"/></td>\
<td class="direction">\
<input class="first" type="checkbox"/><span class="name">' + name + '</span>\
<input class="second" type="checkbox"/><span class="alternate">' + alternate + '</span>\
</td>\
</tr> \
');
$('div.tab-servos table.fields tr:last td.channel input').eq(SERVO_CONFIG[obj].indexOfChannelToForward).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('\
<select class="rate" name="rate"></select>\
');
var select = $('div.tab-servos table.fields tr:last td.direction select');
for (var i = 100; i > -101; i--) {
select.append('<option value="' + i + '">Rate: ' + i + '%</option>');
}
// 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
// only one checkbox for indicating a channel to forward can be selected at a time, perhaps a radio group would be best here.
2014-08-12 14:20:26 +00:00
$('div.tab-servos table.fields tr:last td.channel input').click(function () {
if($(this).is(':checked')) {
2014-04-02 13:47:34 +00:00
$(this).parent().parent().find('.channel input').not($(this)).prop('checked', false);
}
2013-11-12 10:43:08 +00:00
});
}
2014-03-08 05:25:15 +00:00
function servos_update(save_to_eeprom) {
// update bitfields
2014-08-12 14:20:26 +00:00
$('div.tab-servos table.directions tr:not(".main")').each(function () {
var info = $('select', this).data('info');
var val = parseInt($('select', this).val());
2013-11-12 10:43:08 +00:00
// 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);
});
2014-03-08 05:25:15 +00:00
// update the rest
2014-08-12 14:20:26 +00:00
$('div.tab-servos table.fields tr:not(".main")').each(function () {
var info = $(this).data('info');
2014-03-08 05:25:15 +00:00
var selection = $('.channel input', this);
var val = selection.index(selection.filter(':checked'));
SERVO_CONFIG[info.obj].indexOfChannelToForward = parseInt(val);
2014-03-08 05:25:15 +00:00
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());
2014-03-08 05:25:15 +00:00
// 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);
2014-03-08 05:25:15 +00:00
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 channel forwarding over to mcu
var buffer_out = [];
var needle = 0;
for (var i = 0; i < SERVO_CONFIG.length; i++) {
buffer_out[needle++] = SERVO_CONFIG[i].indexOfChannelToForward;
}
MSP.send_message(MSP_codes.MSP_SET_CHANNEL_FORWARDING, buffer_out);
2014-03-08 05:25:15 +00:00
MSP.send_message(MSP_codes.MSP_SET_SERVO_CONF, MSP.crunch(MSP_codes.MSP_SET_SERVO_CONF), false, function () {
if (save_to_eeprom) {
// Save changes to EEPROM
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
GUI.log(chrome.i18n.getMessage('servosEepromSave'));
});
}
});
}
2014-03-08 05:25:15 +00:00
// 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
2014-05-06 21:57:57 +00:00
model.text('TRI');
process_directions('YAW', 5, 0);
process_servos('Yaw Servo', '', 5, false);
break;
case 4: // BI
// looking ok so far
2014-05-06 21:57:57 +00:00
model.text('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
2014-05-06 21:57:57 +00:00
model.text('Gimbal');
// rate
process_servos('Pitch Servo', '', 0, 2);
process_servos('Roll Servo', '', 1, 2);
break;
case 8: // Flying Wing
// looking ok so far
2014-05-06 21:57:57 +00:00
model.text('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
2014-05-06 21:57:57 +00:00
model.text('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
2014-05-06 21:57:57 +00:00
model.text('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
2014-05-06 21:57:57 +00:00
model.text('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:
2014-05-06 21:57:57 +00:00
model.text(chrome.i18n.getMessage('servosModelNoSupport'));
// implementation of feature servo_tilt
if (AUX_CONFIG.indexOf('CAMSTAB') > -1 || AUX_CONFIG.indexOf('CAMTRIG') > -1) {
// Gimbal on
// needs to be verified
2014-05-06 21:57:57 +00:00
model.text('Gimbal / Tilt Servos');
// rate
process_servos('Pitch Servo', '', 0, 2);
process_servos('Roll Servo', '', 1, 2);
}
}
2014-03-08 05:25:15 +00:00
// UI hooks for dynamically generated elements
2014-08-12 14:20:26 +00:00
$('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);
}
});
2014-03-08 05:25:15 +00:00
2014-08-12 14:20:26 +00:00
$('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);
}
});
// status data pulled via separate timer with static speed
2014-08-12 14:20:26 +00:00
GUI.interval_add('status_pull', function () {
MSP.send_message(MSP_codes.MSP_STATUS);
}, 250, true);
2014-07-10 16:24:56 +00:00
if (callback) callback();
}
2014-07-10 16:24:56 +00:00
};
2014-08-12 14:20:26 +00:00
TABS.servos.cleanup = function (callback) {
2014-07-10 16:24:56 +00:00
if (callback) callback();
};