mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_RCTelemetry: don't process VTX frames when VTX support is disabled
This commit is contained in:
parent
f7e23566ac
commit
f1eee860c0
@ -392,7 +392,12 @@ void AP_CRSF_Telem::process_vtx_frame(VTXFrame* vtx) {
|
||||
vtx->is_in_pitmode, vtx->power, vtx->pitmode);
|
||||
AP_VideoTX& apvtx = AP::vtx();
|
||||
|
||||
apvtx.set_enabled(vtx->is_vtx_available);
|
||||
// the user may have a VTX connected but not want AP to control it
|
||||
// (for instance because they are using myVTX on the transmitter)
|
||||
if (!apvtx.get_enabled()) {
|
||||
return;
|
||||
}
|
||||
|
||||
apvtx.set_band(vtx->band);
|
||||
apvtx.set_channel(vtx->channel);
|
||||
if (vtx->is_in_user_frequency_mode) {
|
||||
@ -428,12 +433,17 @@ void AP_CRSF_Telem::process_vtx_frame(VTXFrame* vtx) {
|
||||
_vtx_power_change_pending = _vtx_freq_change_pending = _vtx_options_change_pending = false;
|
||||
}
|
||||
|
||||
void AP_CRSF_Telem::process_vtx_telem_frame(VTXTelemetryFrame* vtx) {
|
||||
void AP_CRSF_Telem::process_vtx_telem_frame(VTXTelemetryFrame* vtx)
|
||||
{
|
||||
vtx->frequency = be16toh(vtx->frequency);
|
||||
debug("VTXTelemetry: Freq: %d, PitMode: %d, Power: %d", vtx->frequency, vtx->pitmode, vtx->power);
|
||||
|
||||
AP_VideoTX& apvtx = AP::vtx();
|
||||
|
||||
if (!apvtx.get_enabled()) {
|
||||
return;
|
||||
}
|
||||
|
||||
apvtx.set_frequency_mhz(vtx->frequency);
|
||||
|
||||
AP_VideoTX::VideoBand band;
|
||||
@ -550,6 +560,10 @@ void AP_CRSF_Telem::update_vtx_params()
|
||||
{
|
||||
AP_VideoTX& vtx = AP::vtx();
|
||||
|
||||
if (!vtx.get_enabled()) {
|
||||
return;
|
||||
}
|
||||
|
||||
_vtx_freq_change_pending = vtx.update_band() || vtx.update_channel() || vtx.update_frequency() || _vtx_freq_change_pending;
|
||||
_vtx_power_change_pending = vtx.update_power() || _vtx_power_change_pending;
|
||||
_vtx_options_change_pending = vtx.update_options() || _vtx_options_change_pending;
|
||||
|
Loading…
Reference in New Issue
Block a user