AP_ADSB: add option to force Mode3AC Only

This commit is contained in:
Tom Pittenger 2024-11-27 16:42:02 -08:00 committed by Tom Pittenger
parent 137915ab46
commit a48ff8431b
4 changed files with 5 additions and 4 deletions

View File

@ -172,7 +172,7 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = {
// @Param: OPTIONS
// @DisplayName: ADS-B Options
// @Description: Options for emergency failsafe codes and device capabilities
// @Bitmask: 0:Ping200X Send GPS,1:Squawk 7400 on RC failsafe,2:Squawk 7400 on GCS failsafe,3:Sagetech MXS use External Config
// @Bitmask: 0:Ping200X Send GPS,1:Squawk 7400 on RC failsafe,2:Squawk 7400 on GCS failsafe,3:Sagetech MXS use External Config,4:Transmit in traditional Mode 3A/C only and inhibit Mode-S and ES (ADSB) transmissions
// @User: Advanced
AP_GROUPINFO("OPTIONS", 15, AP_ADSB, _options, 0),

View File

@ -78,6 +78,7 @@ public:
Squawk_7400_FS_RC = (1<<1),
Squawk_7400_FS_GCS = (1<<2),
SagteTech_MXS_External_Config = (1<<3),
Mode3_Only = (1<<4),
};
// for holding parameters

View File

@ -150,7 +150,7 @@ void AP_ADSB_Sagetech_MXS::update()
last.operating_rf_select = _frontend.out_state.cfg.rfSelect;
last.modeAEnabled = _frontend.out_state.ctrl.modeAEnabled;
last.modeCEnabled = _frontend.out_state.ctrl.modeCEnabled;
last.modeSEnabled = _frontend.out_state.ctrl.modeSEnabled;
last.modeSEnabled = (_frontend._options & uint32_t(AP_ADSB::AdsbOption::Mode3_Only)) ? 0 : _frontend.out_state.ctrl.modeSEnabled;
last.operating_alt = _frontend._my_loc.alt;
last.packet_Operating_ms = now_ms;

View File

@ -411,8 +411,8 @@ void AP_ADSB_uAvionix_UCP::send_Transponder_Control()
_frontend.out_state.ctrl.identActive = false; // only send identButtonActive once per request
msg.modeAEnabled = _frontend.out_state.ctrl.modeAEnabled;
msg.modeCEnabled = _frontend.out_state.ctrl.modeCEnabled;
msg.modeSEnabled = _frontend.out_state.ctrl.modeSEnabled;
msg.es1090TxEnabled = _frontend.out_state.ctrl.es1090TxEnabled;
msg.modeSEnabled = (_frontend._options & uint32_t(AP_ADSB::AdsbOption::Mode3_Only)) ? 0 : _frontend.out_state.ctrl.modeSEnabled;
msg.es1090TxEnabled = (_frontend._options & uint32_t(AP_ADSB::AdsbOption::Mode3_Only)) ? 0 : _frontend.out_state.ctrl.es1090TxEnabled;
// if enabled via param ADSB_OPTIONS, use squawk 7400 while in any Loss-Comms related failsafe
// https://www.faa.gov/documentLibrary/media/Notice/N_JO_7110.724_5-2-9_UAS_Lost_Link_2.pdf