mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-16 04:45:18 +03:00
Update MSPHelper.js
This commit is contained in:
parent
bfeb8ff33d
commit
075e4a6f3d
1 changed files with 27 additions and 28 deletions
|
@ -519,7 +519,7 @@ var mspHelper = (function (gui) {
|
||||||
));
|
));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP2_INAV_LOGIC_CONDITIONS_STATUS:
|
case MSPCodes.MSP2_INAV_LOGIC_CONDITIONS_STATUS:
|
||||||
|
@ -1297,7 +1297,7 @@ var mspHelper = (function (gui) {
|
||||||
CALIBRATION_DATA.magZero.Y = data.getInt16(15, true);
|
CALIBRATION_DATA.magZero.Y = data.getInt16(15, true);
|
||||||
CALIBRATION_DATA.magZero.Z = data.getInt16(17, true);
|
CALIBRATION_DATA.magZero.Z = data.getInt16(17, true);
|
||||||
CALIBRATION_DATA.opflow.Scale = (data.getInt16(19, true) / 256.0);
|
CALIBRATION_DATA.opflow.Scale = (data.getInt16(19, true) / 256.0);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
|
||||||
CALIBRATION_DATA.magGain.X = data.getInt16(21, true);
|
CALIBRATION_DATA.magGain.X = data.getInt16(21, true);
|
||||||
CALIBRATION_DATA.magGain.Y = data.getInt16(23, true);
|
CALIBRATION_DATA.magGain.Y = data.getInt16(23, true);
|
||||||
|
@ -1513,8 +1513,8 @@ var mspHelper = (function (gui) {
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP2_INAV_SET_SAFEHOME:
|
case MSPCodes.MSP2_INAV_SET_SAFEHOME:
|
||||||
console.log('Safehome points saved');
|
console.log('Safehome points saved');
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
console.log('Unknown code detected: ' + dataHandler.code);
|
console.log('Unknown code detected: ' + dataHandler.code);
|
||||||
} else {
|
} else {
|
||||||
|
@ -2125,7 +2125,7 @@ var mspHelper = (function (gui) {
|
||||||
buffer.push(SENSOR_CONFIG.opflow);
|
buffer.push(SENSOR_CONFIG.opflow);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
|
||||||
case MSPCodes.MSP_WP_MISSION_SAVE:
|
case MSPCodes.MSP_WP_MISSION_SAVE:
|
||||||
// buffer.push(0);
|
// buffer.push(0);
|
||||||
console.log(buffer);
|
console.log(buffer);
|
||||||
|
@ -2985,51 +2985,50 @@ var mspHelper = (function (gui) {
|
||||||
self.getMissionInfo = function (callback) {
|
self.getMissionInfo = function (callback) {
|
||||||
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback);
|
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback);
|
||||||
};
|
};
|
||||||
|
|
||||||
self.loadWaypoints = function (callback) {
|
self.loadWaypoints = function (callback) {
|
||||||
MISSION_PLANER.reinit();
|
MISSION_PLANER.reinit();
|
||||||
let waypointId = 1;
|
let waypointId = 0;
|
||||||
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, getFirstWP);
|
let startTime = new Date().getTime();
|
||||||
|
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, loadWaypoint);
|
||||||
function getFirstWP() {
|
|
||||||
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, nextWaypoint)
|
function loadWaypoint() {
|
||||||
};
|
|
||||||
|
|
||||||
function nextWaypoint() {
|
|
||||||
waypointId++;
|
waypointId++;
|
||||||
if (waypointId < MISSION_PLANER.getCountBusyPoints()) {
|
if (waypointId < MISSION_PLANER.getCountBusyPoints()) {
|
||||||
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, nextWaypoint);
|
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, loadWaypoint);
|
||||||
}
|
} else {
|
||||||
else {
|
GUI.log('Receive time: ' + (new Date().getTime() - startTime) + 'ms');
|
||||||
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, callback);
|
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, callback);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
};
|
};
|
||||||
|
|
||||||
self.saveWaypoints = function (callback) {
|
|
||||||
let waypointId = 1;
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, nextWaypoint)
|
|
||||||
|
|
||||||
function nextWaypoint() {
|
self.saveWaypoints = function (callback) {
|
||||||
|
let waypointId = 0;
|
||||||
|
let startTime = new Date().getTime();
|
||||||
|
sendWaypoint();
|
||||||
|
|
||||||
|
function sendWaypoint() {
|
||||||
waypointId++;
|
waypointId++;
|
||||||
if (waypointId < MISSION_PLANER.get().length) {
|
if (waypointId < MISSION_PLANER.get().length) {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, nextWaypoint);
|
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, sendWaypoint);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, endMission);
|
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, endMission);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
function endMission() {
|
function endMission() {
|
||||||
|
GUI.log('Send time: ' + (new Date().getTime() - startTime) + 'ms');
|
||||||
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback);
|
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
self.loadSafehomes = function (callback) {
|
self.loadSafehomes = function (callback) {
|
||||||
SAFEHOMES.flush();
|
SAFEHOMES.flush();
|
||||||
let safehomeId = 0;
|
let safehomeId = 0;
|
||||||
MSP.send_message(MSPCodes.MSP2_INAV_SAFEHOME, [safehomeId], false, nextSafehome);
|
MSP.send_message(MSPCodes.MSP2_INAV_SAFEHOME, [safehomeId], false, nextSafehome);
|
||||||
|
|
||||||
function nextSafehome() {
|
function nextSafehome() {
|
||||||
safehomeId++;
|
safehomeId++;
|
||||||
if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {
|
if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {
|
||||||
|
@ -3040,11 +3039,11 @@ var mspHelper = (function (gui) {
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
};
|
};
|
||||||
|
|
||||||
self.saveSafehomes = function (callback) {
|
self.saveSafehomes = function (callback) {
|
||||||
let safehomeId = 0;
|
let safehomeId = 0;
|
||||||
MSP.send_message(MSPCodes.MSP2_INAV_SET_SAFEHOME, SAFEHOMES.extractBuffer(safehomeId), false, nextSendSafehome);
|
MSP.send_message(MSPCodes.MSP2_INAV_SET_SAFEHOME, SAFEHOMES.extractBuffer(safehomeId), false, nextSendSafehome);
|
||||||
|
|
||||||
function nextSendSafehome() {
|
function nextSendSafehome() {
|
||||||
safehomeId++;
|
safehomeId++;
|
||||||
if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {
|
if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue