mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-24 16:55:22 +03:00
Add support for the new VTX settings API
When a controllable VTX is configured, a new section appears in the configuration tab which allows the user to set the band, channel power and "low power on disarm" option.
This commit is contained in:
parent
ba45e316e3
commit
6da922919f
8 changed files with 229 additions and 2 deletions
10
js/fc.js
10
js/fc.js
|
@ -39,6 +39,7 @@ var CONFIG,
|
|||
RX_CONFIG,
|
||||
FAILSAFE_CONFIG,
|
||||
RXFAIL_CONFIG,
|
||||
VTX_CONFIG,
|
||||
ADVANCED_CONFIG,
|
||||
INAV_PID_CONFIG,
|
||||
PID_ADVANCED,
|
||||
|
@ -296,6 +297,15 @@ var FC = {
|
|||
capacity_unit: 0
|
||||
};
|
||||
|
||||
VTX_CONFIG = {
|
||||
device_type: VTXDEV_UNKNOWN,
|
||||
band: 0,
|
||||
channel: 1,
|
||||
power: 0,
|
||||
pitmode: 0,
|
||||
low_power_disarm: 0,
|
||||
};
|
||||
|
||||
ADVANCED_CONFIG = {
|
||||
gyroSyncDenominator: null,
|
||||
pidProcessDenom: null,
|
||||
|
|
|
@ -66,6 +66,8 @@ var MSPCodes = {
|
|||
MSP_SET_OSD_CONFIG: 85,
|
||||
MSP_OSD_CHAR_READ: 86,
|
||||
MSP_OSD_CHAR_WRITE: 87,
|
||||
MSP_VTX_CONFIG: 88,
|
||||
MSP_SET_VTX_CONFIG: 89,
|
||||
MSP_ADVANCED_CONFIG: 90,
|
||||
MSP_SET_ADVANCED_CONFIG: 91,
|
||||
MSP_FILTER_CONFIG: 92,
|
||||
|
|
|
@ -1052,7 +1052,18 @@ var mspHelper = (function (gui) {
|
|||
case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
|
||||
console.log("Transponder config saved");
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_VTX_CONFIG:
|
||||
VTX_CONFIG.device_type = data.getUint8(offset++);
|
||||
if (VTX_CONFIG.device_type != VTXDEV_UNKNOWN) {
|
||||
VTX_CONFIG.band = data.getUint8(offset++);
|
||||
VTX_CONFIG.channel = data.getUint8(offset++);
|
||||
VTX_CONFIG.power = data.getUint8(offset++);
|
||||
VTX_CONFIG.pitmode = data.getUint8(offset++);
|
||||
// Ignore wether the VTX is ready for now
|
||||
offset++;
|
||||
VTX_CONFIG.low_power_disarm = data.getUint8(offset++);
|
||||
}
|
||||
break;
|
||||
case MSPCodes.MSP_ADVANCED_CONFIG:
|
||||
ADVANCED_CONFIG.gyroSyncDenominator = data.getUint8(offset);
|
||||
offset++;
|
||||
|
@ -1069,6 +1080,10 @@ var mspHelper = (function (gui) {
|
|||
ADVANCED_CONFIG.gyroSync = data.getUint8(offset);
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_VTX_CONFIG:
|
||||
console.log("VTX config saved");
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_ADVANCED_CONFIG:
|
||||
console.log("Advanced config saved");
|
||||
break;
|
||||
|
@ -1393,6 +1408,18 @@ var mspHelper = (function (gui) {
|
|||
buffer.push(lowByte(BF_CONFIG.currentoffset));
|
||||
buffer.push(highByte(BF_CONFIG.currentoffset));
|
||||
break;
|
||||
case MSPCodes.MSP_SET_VTX_CONFIG:
|
||||
if (VTX_CONFIG.band > 0) {
|
||||
buffer.push16(((VTX_CONFIG.band - 1) * 8) + (VTX_CONFIG.channel - 1));
|
||||
} else {
|
||||
// This tells the firmware to ignore this value.
|
||||
buffer.push16(VTX_MAX_FREQUENCY_MHZ + 1);
|
||||
}
|
||||
buffer.push(VTX_CONFIG.power);
|
||||
// Don't enable PIT mode
|
||||
buffer.push(0);
|
||||
buffer.push(VTX_CONFIG.low_power_disarm);
|
||||
break;
|
||||
case MSPCodes.MSP_SET_PID:
|
||||
for (i = 0; i < PIDs.length; i++) {
|
||||
buffer.push(parseInt(PIDs[i][0]));
|
||||
|
@ -2995,5 +3022,21 @@ var mspHelper = (function (gui) {
|
|||
}
|
||||
};
|
||||
|
||||
self.loadVTXConfig = function (callback) {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_VTX_CONFIG, false, false, callback);
|
||||
} else {
|
||||
callback();
|
||||
}
|
||||
};
|
||||
|
||||
self.saveVTXConfig = function(callback) {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_SET_VTX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VTX_CONFIG), false, callback);
|
||||
} else {
|
||||
callback();
|
||||
}
|
||||
}
|
||||
|
||||
return self;
|
||||
})(GUI);
|
||||
|
|
23
js/vtx.js
Normal file
23
js/vtx.js
Normal file
|
@ -0,0 +1,23 @@
|
|||
var VTXDEV_UNKNOWN = 0xFF;
|
||||
|
||||
var VTX_BANDS = [
|
||||
{code: 1, name: 'Boscam A'},
|
||||
{code: 2, name: 'Boscam B'},
|
||||
{code: 3, name: 'Boscam E'},
|
||||
{code: 4, name: 'Fatshark'},
|
||||
{code: 5, name: 'Raceband'},
|
||||
];
|
||||
|
||||
var VTX_BAND_MIN = 1;
|
||||
var VTX_BAND_MAX = 5;
|
||||
|
||||
var VTX_CHANNEL_MIN = 1;
|
||||
var VTX_CHANNEL_MAX = 8;
|
||||
|
||||
var VTX_POWER_MIN = 0;
|
||||
var VTX_POWER_MAX = 4;
|
||||
|
||||
var VTX_LOW_POWER_DISARM_MIN = 0;
|
||||
var VTX_LOW_POWER_DISARM_MAX = 2;
|
||||
|
||||
var VTX_MAX_FREQUENCY_MHZ = 5999;
|
Loading…
Add table
Add a link
Reference in a new issue