1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-15 04:15:28 +03:00

Initial build

This commit is contained in:
breadoven 2021-10-17 23:44:33 +01:00
parent 3d1fcca7bb
commit 8fcdf76945
8 changed files with 657 additions and 130 deletions

View file

@ -455,7 +455,8 @@ var mspHelper = (function (gui) {
data.getInt32(10, true),
data.getInt16(14, true),
data.getInt16(16, true),
data.getInt16(18, true)
data.getInt16(18, true), // CR8
data.getUint8(20) // CR8
));
break;
case MSPCodes.MSP_BOXIDS:
@ -519,7 +520,7 @@ var mspHelper = (function (gui) {
));
}
}
break;
case MSPCodes.MSP2_INAV_LOGIC_CONDITIONS_STATUS:
@ -1297,7 +1298,7 @@ var mspHelper = (function (gui) {
CALIBRATION_DATA.magZero.Y = data.getInt16(15, true);
CALIBRATION_DATA.magZero.Z = data.getInt16(17, true);
CALIBRATION_DATA.opflow.Scale = (data.getInt16(19, true) / 256.0);
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
CALIBRATION_DATA.magGain.X = data.getInt16(21, true);
CALIBRATION_DATA.magGain.Y = data.getInt16(23, true);
@ -1513,8 +1514,8 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP2_INAV_SET_SAFEHOME:
console.log('Safehome points saved');
break;
break;
default:
console.log('Unknown code detected: ' + dataHandler.code);
} else {
@ -2125,7 +2126,7 @@ var mspHelper = (function (gui) {
buffer.push(SENSOR_CONFIG.opflow);
break;
case MSPCodes.MSP_WP_MISSION_SAVE:
// buffer.push(0);
console.log(buffer);
@ -2985,29 +2986,32 @@ var mspHelper = (function (gui) {
self.getMissionInfo = function (callback) {
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback);
};
self.loadWaypoints = function (callback) {
MISSION_PLANER.reinit();
let waypointId = 1;
let startTime = new Date().getTime();
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, getFirstWP);
function getFirstWP() {
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, nextWaypoint)
};
function nextWaypoint() {
waypointId++;
if (waypointId < MISSION_PLANER.getCountBusyPoints()) {
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, nextWaypoint);
}
else {
GUI.log('Receive time: ' + (new Date().getTime() - startTime) + 'ms');
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, callback);
}
};
};
self.saveWaypoints = function (callback) {
let waypointId = 1;
let startTime = new Date().getTime();
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, nextWaypoint)
function nextWaypoint() {
@ -3019,17 +3023,18 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, endMission);
}
};
function endMission() {
GUI.log('Send time: ' + (new Date().getTime() - startTime) + 'ms');
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback);
}
};
self.loadSafehomes = function (callback) {
SAFEHOMES.flush();
let safehomeId = 0;
MSP.send_message(MSPCodes.MSP2_INAV_SAFEHOME, [safehomeId], false, nextSafehome);
function nextSafehome() {
safehomeId++;
if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {
@ -3040,11 +3045,11 @@ var mspHelper = (function (gui) {
}
};
};
self.saveSafehomes = function (callback) {
let safehomeId = 0;
MSP.send_message(MSPCodes.MSP2_INAV_SET_SAFEHOME, SAFEHOMES.extractBuffer(safehomeId), false, nextSendSafehome);
function nextSendSafehome() {
safehomeId++;
if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {