mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-24 08:45:26 +03:00
commit
23ef794d5b
13 changed files with 1054 additions and 245 deletions
|
@ -42,7 +42,7 @@ var mspHelper = (function (gui) {
|
|||
'BLACKBOX': 7,
|
||||
'TELEMETRY_MAVLINK': 8,
|
||||
'TELEMETRY_IBUS': 9,
|
||||
'RUNCAM_DEVICE_CONTROL' : 10,
|
||||
'RUNCAM_DEVICE_CONTROL': 10,
|
||||
'TBS_SMARTAUDIO': 11,
|
||||
'IRC_TRAMP': 12
|
||||
};
|
||||
|
@ -138,14 +138,14 @@ var mspHelper = (function (gui) {
|
|||
|
||||
case MSPCodes.MSP_SENSOR_STATUS:
|
||||
SENSOR_STATUS.isHardwareHealthy = data.getUint8(0);
|
||||
SENSOR_STATUS.gyroHwStatus = data.getUint8(1);
|
||||
SENSOR_STATUS.accHwStatus = data.getUint8(2);
|
||||
SENSOR_STATUS.magHwStatus = data.getUint8(3);
|
||||
SENSOR_STATUS.baroHwStatus = data.getUint8(4);
|
||||
SENSOR_STATUS.gpsHwStatus = data.getUint8(5);
|
||||
SENSOR_STATUS.rangeHwStatus = data.getUint8(6);
|
||||
SENSOR_STATUS.speedHwStatus = data.getUint8(7);
|
||||
SENSOR_STATUS.flowHwStatus = data.getUint8(8);
|
||||
SENSOR_STATUS.gyroHwStatus = data.getUint8(1);
|
||||
SENSOR_STATUS.accHwStatus = data.getUint8(2);
|
||||
SENSOR_STATUS.magHwStatus = data.getUint8(3);
|
||||
SENSOR_STATUS.baroHwStatus = data.getUint8(4);
|
||||
SENSOR_STATUS.gpsHwStatus = data.getUint8(5);
|
||||
SENSOR_STATUS.rangeHwStatus = data.getUint8(6);
|
||||
SENSOR_STATUS.speedHwStatus = data.getUint8(7);
|
||||
SENSOR_STATUS.flowHwStatus = data.getUint8(8);
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||
sensor_status_ex(SENSOR_STATUS);
|
||||
}
|
||||
|
@ -345,7 +345,12 @@ var mspHelper = (function (gui) {
|
|||
}
|
||||
break;
|
||||
case MSPCodes.MSP_WP:
|
||||
console.log(data);
|
||||
MISSION_PLANER.bufferPoint.number = data.getUint8(0);
|
||||
MISSION_PLANER.bufferPoint.action = data.getUint8(1);
|
||||
MISSION_PLANER.bufferPoint.lat = data.getInt32(2, true) / 10000000;
|
||||
MISSION_PLANER.bufferPoint.lon = data.getInt32(6, true) / 10000000;
|
||||
MISSION_PLANER.bufferPoint.alt = data.getInt32(10, true);
|
||||
|
||||
break;
|
||||
case MSPCodes.MSP_BOXIDS:
|
||||
//noinspection JSUndeclaredVariable
|
||||
|
@ -1144,6 +1149,23 @@ var mspHelper = (function (gui) {
|
|||
case MSPCodes.MSPV2_SET_SETTING:
|
||||
console.log("Setting set");
|
||||
break;
|
||||
case MSPCodes.MSP_WP_GETINFO:
|
||||
// Reserved for waypoint capabilities data.getUint8(0);
|
||||
MISSION_PLANER.maxWaypoints = data.getUint8(1);
|
||||
MISSION_PLANER.isValidMission = data.getUint8(2);
|
||||
MISSION_PLANER.countBusyPoints = data.getUint8(3);
|
||||
break;
|
||||
case MSPCodes.MSP_SET_WP:
|
||||
console.log('Point saved');
|
||||
break;
|
||||
case MSPCodes.MSP_WP_MISSION_SAVE:
|
||||
// buffer.push(0);
|
||||
console.log(data);
|
||||
|
||||
break;
|
||||
case MSPCodes.MSP_WP_MISSION_LOAD:
|
||||
console.log('Mission load');
|
||||
break;
|
||||
default:
|
||||
console.log('Unknown code detected: ' + dataHandler.code);
|
||||
} else {
|
||||
|
@ -1323,7 +1345,7 @@ var mspHelper = (function (gui) {
|
|||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_fw_yaw_rate));
|
||||
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_stick_motion_threshold));
|
||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_stick_motion_threshold));
|
||||
}
|
||||
}
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) {
|
||||
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_min_distance));
|
||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_min_distance));
|
||||
|
@ -1624,6 +1646,44 @@ var mspHelper = (function (gui) {
|
|||
buffer.push(SENSOR_CONFIG.opflow);
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_WP:
|
||||
buffer.push(MISSION_PLANER.bufferPoint.number); // sbufReadU8(src); // number
|
||||
buffer.push(MISSION_PLANER.bufferPoint.action); // sbufReadU8(src); // action
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.lat, 0)); // sbufReadU32(src); // lat
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.lat, 1));
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.lat, 2));
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.lat, 3));
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.lon, 0)); // sbufReadU32(src); // lon
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.lon, 1));
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.lon, 2));
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.lon, 3));
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.alt, 0)); // sbufReadU32(src); // to set altitude (cm)
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.alt, 1));
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.alt, 2));
|
||||
buffer.push(specificByte(MISSION_PLANER.bufferPoint.alt, 3));
|
||||
buffer.push(lowByte(0)); //sbufReadU16(src); // P1
|
||||
buffer.push(highByte(0));
|
||||
buffer.push(lowByte(0)); //sbufReadU16(src); // P2
|
||||
buffer.push(highByte(0));
|
||||
buffer.push(lowByte(0)); //sbufReadU16(src); // P3
|
||||
buffer.push(highByte(0));
|
||||
buffer.push(MISSION_PLANER.bufferPoint.endMission); //sbufReadU8(src); // future: to set nav flag
|
||||
break;
|
||||
case MSPCodes.MSP_WP:
|
||||
console.log(MISSION_PLANER.bufferPoint.number);
|
||||
buffer.push(MISSION_PLANER.bufferPoint.number+1);
|
||||
|
||||
break;
|
||||
case MSPCodes.MSP_WP_MISSION_SAVE:
|
||||
// buffer.push(0);
|
||||
console.log(buffer);
|
||||
|
||||
break;
|
||||
case MSPCodes.MSP_WP_MISSION_LOAD:
|
||||
// buffer.push(0);
|
||||
console.log(buffer);
|
||||
|
||||
break;
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
@ -1649,9 +1709,9 @@ var mspHelper = (function (gui) {
|
|||
|
||||
self.sendBlackboxConfiguration = function (onDataCallback) {
|
||||
var message = [
|
||||
BLACKBOX.blackboxDevice & 0xFF,
|
||||
BLACKBOX.blackboxRateNum & 0xFF,
|
||||
BLACKBOX.blackboxRateDenom & 0xFF
|
||||
BLACKBOX.blackboxDevice & 0xFF,
|
||||
BLACKBOX.blackboxRateNum & 0xFF,
|
||||
BLACKBOX.blackboxRateDenom & 0xFF
|
||||
];
|
||||
|
||||
//noinspection JSUnusedLocalSymbols
|
||||
|
@ -2095,7 +2155,7 @@ var mspHelper = (function (gui) {
|
|||
MSP.send_message(MSPCodes.MSP_IDENT, false, false, callback);
|
||||
};
|
||||
|
||||
self.loadINAVPidConfig = function(callback) {
|
||||
self.loadINAVPidConfig = function (callback) {
|
||||
if (semver.gt(CONFIG.flightControllerVersion, "1.3.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_INAV_PID, false, false, callback);
|
||||
} else {
|
||||
|
@ -2107,7 +2167,7 @@ var mspHelper = (function (gui) {
|
|||
MSP.send_message(MSPCodes.MSP_LOOP_TIME, false, false, callback);
|
||||
};
|
||||
|
||||
self.loadAdvancedConfig = function(callback) {
|
||||
self.loadAdvancedConfig = function (callback) {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "1.3.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, callback);
|
||||
} else {
|
||||
|
@ -2288,7 +2348,7 @@ var mspHelper = (function (gui) {
|
|||
};
|
||||
|
||||
self.saveRxConfig = function (callback) {
|
||||
if(semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG), false, callback);
|
||||
} else {
|
||||
callback();
|
||||
|
@ -2296,7 +2356,7 @@ var mspHelper = (function (gui) {
|
|||
};
|
||||
|
||||
self.saveSensorConfig = function (callback) {
|
||||
if(semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_SET_SENSOR_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_SENSOR_CONFIG), false, callback);
|
||||
} else {
|
||||
callback();
|
||||
|
@ -2383,20 +2443,28 @@ var mspHelper = (function (gui) {
|
|||
}
|
||||
};
|
||||
|
||||
self._getSetting = function(name) {
|
||||
self.getMissionInfo = function (callback) {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) {
|
||||
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback);
|
||||
} else {
|
||||
callback();
|
||||
}
|
||||
};
|
||||
|
||||
self._getSetting = function (name) {
|
||||
var promise;
|
||||
if (this._settings) {
|
||||
promise = Promise.resolve(this._settings);
|
||||
} else {
|
||||
promise = new Promise(function(resolve, reject) {
|
||||
promise = new Promise(function (resolve, reject) {
|
||||
var $this = this;
|
||||
$.ajax({
|
||||
url: chrome.runtime.getURL('/resources/settings.json'),
|
||||
dataType: 'json',
|
||||
error: function(jqXHR, text, error) {
|
||||
error: function (jqXHR, text, error) {
|
||||
reject(error);
|
||||
},
|
||||
success: function(data) {
|
||||
success: function (data) {
|
||||
$this._settings = data;
|
||||
resolve(data);
|
||||
}
|
||||
|
@ -2408,19 +2476,19 @@ var mspHelper = (function (gui) {
|
|||
});
|
||||
};
|
||||
|
||||
self._encodeSettingName = function(name, data) {
|
||||
self._encodeSettingName = function (name, data) {
|
||||
for (var ii = 0; ii < name.length; ii++) {
|
||||
data.push(name.charCodeAt(ii));
|
||||
}
|
||||
data.push(0);
|
||||
};
|
||||
|
||||
self.getSetting = function(name, callback) {
|
||||
self.getSetting = function (name, callback) {
|
||||
var $this = this;
|
||||
return this._getSetting(name).then(function (setting) {
|
||||
var data = [];
|
||||
var data = [];
|
||||
$this._encodeSettingName(name, data);
|
||||
MSP.send_message(MSPCodes.MSPV2_SETTING, data, false, function(resp) {
|
||||
MSP.send_message(MSPCodes.MSPV2_SETTING, data, false, function (resp) {
|
||||
var value;
|
||||
switch (setting.type) {
|
||||
case "uint8_t":
|
||||
|
@ -2457,7 +2525,7 @@ var mspHelper = (function (gui) {
|
|||
});
|
||||
};
|
||||
|
||||
self.encodeSetting = function(name, value) {
|
||||
self.encodeSetting = function (name, value) {
|
||||
var $this = this;
|
||||
return this._getSetting(name).then(function (setting) {
|
||||
if (setting.table) {
|
||||
|
@ -2500,15 +2568,15 @@ var mspHelper = (function (gui) {
|
|||
});
|
||||
};
|
||||
|
||||
self.setSetting = function(name, value, callback) {
|
||||
self.setSetting = function (name, value, callback) {
|
||||
this.encodeSetting(name, value).then(function (data) {
|
||||
MSP.send_message(MSPCodes.MSPV2_SET_SETTING, data, false, callback);
|
||||
});
|
||||
};
|
||||
|
||||
self.getRTC = function(callback) {
|
||||
self.getRTC = function (callback) {
|
||||
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
|
||||
MSP.send_message(MSPCodes.MSP_RTC, false, false, function(resp) {
|
||||
MSP.send_message(MSPCodes.MSP_RTC, false, false, function (resp) {
|
||||
var seconds = resp.data.read32();
|
||||
var millis = resp.data.readU16();
|
||||
if (callback) {
|
||||
|
@ -2520,7 +2588,7 @@ var mspHelper = (function (gui) {
|
|||
}
|
||||
};
|
||||
|
||||
self.setRTC = function(callback) {
|
||||
self.setRTC = function (callback) {
|
||||
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
|
||||
var now = Date.now();
|
||||
var secs = now / 1000;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue