Move handling of servo channel forwarding into the MSP.
parent
745c2dc793
commit
34d72feb69
|
@ -35,7 +35,6 @@ var BOARD_DEFINITIONS = [
|
||||||
name: "SP Racing F3",
|
name: "SP Racing F3",
|
||||||
identifier: "SRF3"
|
identifier: "SRF3"
|
||||||
}
|
}
|
||||||
}
|
|
||||||
];
|
];
|
||||||
|
|
||||||
var DEFAULT_BOARD_DEFINITION = {
|
var DEFAULT_BOARD_DEFINITION = {
|
||||||
|
|
13
js/msp.js
13
js/msp.js
|
@ -619,7 +619,12 @@ var MSP = {
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_CHANNEL_FORWARDING:
|
case MSP_codes.MSP_CHANNEL_FORWARDING:
|
||||||
for (var i = 0; i < 8; i ++) {
|
for (var i = 0; i < 8; i ++) {
|
||||||
SERVO_CONFIG[i].indexOfChannelToForward = data.getUint8(i);
|
var channelIndex = data.getUint8(i);
|
||||||
|
if (channelIndex < 255) {
|
||||||
|
SERVO_CONFIG[i].indexOfChannelToForward;
|
||||||
|
} else {
|
||||||
|
SERVO_CONFIG[i].indexOfChannelToForward = undefined;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -915,7 +920,11 @@ MSP.crunch = function (code) {
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_SET_CHANNEL_FORWARDING:
|
case MSP_codes.MSP_SET_CHANNEL_FORWARDING:
|
||||||
for (var i = 0; i < SERVO_CONFIG.length; i++) {
|
for (var i = 0; i < SERVO_CONFIG.length; i++) {
|
||||||
buffer.push(SERVO_CONFIG[i].indexOfChannelToForward);
|
var out = SERVO_CONFIG[i].indexOfChannelToForward;
|
||||||
|
if (out == undefined) {
|
||||||
|
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
|
||||||
|
}
|
||||||
|
buffer.push(out);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_SET_CF_SERIAL_CONFIG:
|
case MSP_codes.MSP_SET_CF_SERIAL_CONFIG:
|
||||||
|
|
|
@ -163,9 +163,12 @@ TABS.servos.initialize = function (callback) {
|
||||||
|
|
||||||
|
|
||||||
var selection = $('.channel input', this);
|
var selection = $('.channel input', this);
|
||||||
var val = selection.index(selection.filter(':checked'));
|
var channelIndex = parseInt(selection.index(selection.filter(':checked')));
|
||||||
|
if (channelIndex == -1) {
|
||||||
|
channelIndex = undefined;
|
||||||
|
}
|
||||||
|
|
||||||
SERVO_CONFIG[info.obj].indexOfChannelToForward = parseInt(val);
|
SERVO_CONFIG[info.obj].indexOfChannelToForward = channelIndex;
|
||||||
|
|
||||||
|
|
||||||
SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val());
|
SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val());
|
||||||
|
|
Loading…
Reference in New Issue