mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-14 11:59:51 +03:00
Switch to new frames for servos
This commit is contained in:
parent
d6b6c34ef9
commit
857cd73673
3 changed files with 9 additions and 32 deletions
|
@ -110,7 +110,6 @@ var MSPCodes = {
|
|||
MSP_SET_WP: 209,
|
||||
MSP_SELECT_SETTING: 210,
|
||||
MSP_SET_HEAD: 211,
|
||||
MSP_SET_SERVO_CONFIGURATION: 212,
|
||||
MSP_SET_MOTOR: 214,
|
||||
MSP_SET_3D: 217,
|
||||
MSP_SET_RC_DEADBAND: 218,
|
||||
|
@ -242,4 +241,7 @@ var MSPCodes = {
|
|||
MSP2_INAV_CUSTOM_OSD_ELEMENTS: 0x2100,
|
||||
MSP2_INAV_SET_CUSTOM_OSD_ELEMENTS: 0x2101,
|
||||
|
||||
MSP2_INAV_SERVO_CONFIG: 0x2200,
|
||||
MSP2_INAV_SET_SERVO_CONFIG: 0x2201,
|
||||
|
||||
};
|
||||
|
|
|
@ -570,20 +570,18 @@ var mspHelper = (function (gui) {
|
|||
console.log("motor mixer saved");
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SERVO_CONFIGURATIONS:
|
||||
case MSPCodes.MSP2_INAV_SERVO_CONFIG:
|
||||
//noinspection JSUndeclaredVariable
|
||||
SERVO_CONFIG = []; // empty the array as new data is coming in
|
||||
|
||||
if (data.byteLength % 14 == 0) {
|
||||
for (i = 0; i < data.byteLength; i += 14) {
|
||||
if (data.byteLength % 7 == 0) {
|
||||
for (i = 0; i < data.byteLength; i += 7) {
|
||||
var arr = {
|
||||
'min': data.getInt16(i + 0, true),
|
||||
'max': data.getInt16(i + 2, true),
|
||||
'middle': data.getInt16(i + 4, true),
|
||||
'rate': data.getInt8(i + 6),
|
||||
'indexOfChannelToForward': data.getInt8(i + 9)
|
||||
};
|
||||
data.getUint32(i + 10); // Skip 4 bytes that used to be reversed Sources
|
||||
SERVO_CONFIG.push(arr);
|
||||
}
|
||||
}
|
||||
|
@ -628,7 +626,7 @@ var mspHelper = (function (gui) {
|
|||
case MSPCodes.MSP_SELECT_SETTING:
|
||||
console.log('Profile selected');
|
||||
break;
|
||||
case MSPCodes.MSP_SET_SERVO_CONFIGURATION:
|
||||
case MSPCodes.MSP2_INAV_SET_SERVO_CONFIG:
|
||||
console.log('Servo Configuration saved');
|
||||
break;
|
||||
case MSPCodes.MSP_RTC:
|
||||
|
@ -2217,7 +2215,6 @@ var mspHelper = (function (gui) {
|
|||
buffer.push(EZ_TUNE.aggressiveness);
|
||||
buffer.push(EZ_TUNE.rate);
|
||||
buffer.push(EZ_TUNE.expo);
|
||||
console.log(buffer);
|
||||
break;
|
||||
|
||||
|
||||
|
@ -2292,27 +2289,12 @@ var mspHelper = (function (gui) {
|
|||
|
||||
buffer.push(lowByte(servoConfiguration.rate));
|
||||
|
||||
buffer.push(0);
|
||||
buffer.push(0);
|
||||
|
||||
var out = servoConfiguration.indexOfChannelToForward;
|
||||
if (out == undefined) {
|
||||
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
|
||||
}
|
||||
buffer.push(out);
|
||||
|
||||
//Mock 4 bytes of servoConfiguration.reversedInputSources
|
||||
buffer.push(0);
|
||||
buffer.push(0);
|
||||
buffer.push(0);
|
||||
buffer.push(0);
|
||||
|
||||
// prepare for next iteration
|
||||
servoIndex++;
|
||||
if (servoIndex == SERVO_CONFIG.length) {
|
||||
nextFunction = onCompleteCallback;
|
||||
}
|
||||
MSP.send_message(MSPCodes.MSP_SET_SERVO_CONFIGURATION, buffer, false, nextFunction);
|
||||
MSP.send_message(MSPCodes.MSP2_INAV_SET_SERVO_CONFIG, buffer, false, nextFunction);
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -3316,7 +3298,7 @@ var mspHelper = (function (gui) {
|
|||
};
|
||||
|
||||
self.loadServoConfiguration = function (callback) {
|
||||
MSP.send_message(MSPCodes.MSP_SERVO_CONFIGURATIONS, false, false, callback);
|
||||
MSP.send_message(MSPCodes.MSP2_INAV_SERVO_CONFIG, false, false, callback);
|
||||
};
|
||||
|
||||
self.loadServoMixRules = function (callback) {
|
||||
|
|
|
@ -272,11 +272,6 @@ TABS.outputs.initialize = function (callback) {
|
|||
|
||||
let $currentRow = $servoConfigTable.find('tr:last');
|
||||
|
||||
//This routine is pre 2.0 only
|
||||
if (SERVO_CONFIG[obj].indexOfChannelToForward >= 0) {
|
||||
$currentRow.find('td.channel input').eq(SERVO_CONFIG[obj].indexOfChannelToForward).prop('checked', true);
|
||||
}
|
||||
|
||||
// adding select box and generating options
|
||||
$currentRow.find('td.rate').append(
|
||||
'<input class="rate-input" type="number" min="' + FC.MIN_SERVO_RATE + '" max="' + FC.MAX_SERVO_RATE + '" value="' + Math.abs(SERVO_CONFIG[obj].rate) + '" />'
|
||||
|
@ -324,8 +319,6 @@ TABS.outputs.initialize = function (callback) {
|
|||
channelIndex = undefined;
|
||||
}
|
||||
|
||||
SERVO_CONFIG[info.obj].indexOfChannelToForward = channelIndex;
|
||||
|
||||
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());
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue