Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_ADSB: Set config on uAvionix Transponders like Ping200X #28740

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions Tools/scripts/build_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ def config_option(self):
Feature('Ident', 'ADSB_SAGETECH_MXS', 'HAL_ADSB_SAGETECH_MXS_ENABLED', 'Enable Sagetech MXS ADSB', 0, 'ADSB'),
Feature('Ident', 'ADSB_UAVIONIX', 'HAL_ADSB_UAVIONIX_MAVLINK_ENABLED', 'Enable UAvionix ADSB', 0, 'ADSB'),
Feature('Ident', 'ADSB_UAVIONX_UCP', 'HAL_ADSB_UCP_ENABLED', 'Enable uAvionix UCP ADSB', 0 , 'ADSB'),
Feature('Ident', 'ADSB_UAVIONIX_SET_CONFIG', 'HAL_ADSB_UCP_SET_CONFIG', 'Enable uAvionix set static config', 0 , 'ADSB'),
Feature('Ident', 'AIS', 'AP_AIS_ENABLED', 'Enable AIS', 0, None),
Feature('Ident', 'OpenDroneID', 'AP_OPENDRONEID_ENABLED', 'Enable OpenDroneID (Remote ID)', 0, None),

Expand Down
1 change: 1 addition & 0 deletions Tools/scripts/extract_features.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"):
('HAL_ADSB_ENABLED', 'AP_ADSB::AP_ADSB',),
('HAL_ADSB_{type}_ENABLED', r'AP_ADSB_(?P<type>.*)::update',),
('HAL_ADSB_UCP_ENABLED', 'AP_ADSB_uAvionix_UCP::update',),
('HAL_ADSB_UCP_SET_CONFIG', 'AP_ADSB_uAvionix_UCP::update_Transponder_Config',),

('AP_COMPASS_{type}_ENABLED', r'AP_Compass_(?P<type>.*)::read\b',),
('AP_COMPASS_ICM20948_ENABLED', r'AP_Compass_AK09916::probe_ICM20948',),
Expand Down
20 changes: 20 additions & 0 deletions libraries/AP_ADSB/AP_ADSB.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -958,6 +958,26 @@ bool AP_ADSB::Loc::vertical_accuracy(float &vacc) const
return true;
}

uint8_t AP_ADSB::convert_maxknots_to_enum(const float maxAircraftSpeed_knots)
{
if (maxAircraftSpeed_knots <= 0) {
// not set or unknown. no bits set
return 0;
} else if (maxAircraftSpeed_knots <= 75) {
return 1;
} else if (maxAircraftSpeed_knots <= 150) {
return 2;
} else if (maxAircraftSpeed_knots <= 300) {
return 3;
} else if (maxAircraftSpeed_knots <= 600) {
return 4;
} else if (maxAircraftSpeed_knots <= 1200) {
return 5;
} else {
return 6;
}
}

AP_ADSB *AP::ADSB()
{
return AP_ADSB::get_singleton();
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_ADSB/AP_ADSB.h
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,8 @@ class AP_ADSB {
// confirm a value is a valid callsign
static bool is_valid_callsign(uint16_t octal) WARN_IF_UNUSED;

static uint8_t convert_maxknots_to_enum(const float maxAircraftSpeed_knots);

// Convert base 8 or 16 to decimal. Used to convert an octal/hexadecimal value
// stored on a GCS as a string field in different format, but then transmitted
// over mavlink as a float which is always a decimal.
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ void AP_ADSB_Sagetech_MXS::update()
(mxs_state.inst.icao != (uint32_t)_frontend.out_state.cfg.ICAO_id_param.get() ||
mxs_state.inst.emitter != convert_emitter_type_to_sg(_frontend.out_state.cfg.emitterType.get()) ||
mxs_state.inst.size != _frontend.out_state.cfg.lengthWidth.get() ||
mxs_state.inst.maxSpeed != convert_airspeed_knots_to_sg(_frontend.out_state.cfg.maxAircraftSpeed_knots)
mxs_state.inst.maxSpeed != (sg_airspeed_t)AP_ADSB::convert_maxknots_to_enum(_frontend.out_state.cfg.maxAircraftSpeed_knots)
)) {
last.packet_initialize_ms = now_ms;
send_install_msg();
Expand Down Expand Up @@ -358,7 +358,7 @@ void AP_ADSB_Sagetech_MXS::auto_config_installation()
mxs_state.inst.sda = sg_sda_t::sdaUnknown;
mxs_state.inst.emitter = convert_emitter_type_to_sg(_frontend.out_state.cfg.emitterType.get());
mxs_state.inst.size = (sg_size_t)_frontend.out_state.cfg.lengthWidth.get();
mxs_state.inst.maxSpeed = convert_airspeed_knots_to_sg(_frontend.out_state.cfg.maxAircraftSpeed_knots);
mxs_state.inst.maxSpeed = (sg_airspeed_t)AP_ADSB::convert_maxknots_to_enum(_frontend.out_state.cfg.maxAircraftSpeed_knots);
mxs_state.inst.altOffset = 0; // Alt encoder offset is legacy field that should always be 0.
mxs_state.inst.antenna = sg_antenna_t::antBottom;

Expand Down Expand Up @@ -511,7 +511,7 @@ void AP_ADSB_Sagetech_MXS::send_install_msg()
mxs_state.inst.icao = (uint32_t)_frontend.out_state.cfg.ICAO_id_param.get();
mxs_state.inst.emitter = convert_emitter_type_to_sg(_frontend.out_state.cfg.emitterType.get());
mxs_state.inst.size = (sg_size_t)_frontend.out_state.cfg.lengthWidth.get();
mxs_state.inst.maxSpeed = convert_airspeed_knots_to_sg(_frontend.out_state.cfg.maxAircraftSpeed_knots);
mxs_state.inst.maxSpeed = (sg_airspeed_t)AP_ADSB::convert_maxknots_to_enum(_frontend.out_state.cfg.maxAircraftSpeed_knots);
mxs_state.inst.antenna = sg_antenna_t::antBottom;

last.msg.type = SG_MSG_TYPE_HOST_INSTALL;
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_ADSB/AP_ADSB_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,12 @@
#define HAL_ADSB_UCP_ENABLED HAL_ADSB_BACKEND_DEFAULT_ENABLED
#endif

#ifndef HAL_ADSB_UCP_SET_CONFIG
// NOTE: this feature is disabled by default because it is only meant to be used only by certified aircraft maintenance
// personnel and not by your typical pilot. If used incorrectly this may void the TSO certification of the hardware
#define HAL_ADSB_UCP_SET_CONFIG 0
#endif

#ifndef HAL_ADSB_SAGETECH_MXS_ENABLED
// this feature is only enabled by default by select hardware
#define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL
Expand Down
17 changes: 1 addition & 16 deletions libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,22 +177,7 @@ uint8_t AP_ADSB_uAvionix_MAVLink::get_encoded_callsign_null_char()

uint8_t encoded_null = 0;

if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 0) {
// not set or unknown. no bits set
} else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 75) {
encoded_null |= 0x01;
} else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 150) {
encoded_null |= 0x02;
} else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 300) {
encoded_null |= 0x03;
} else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 600) {
encoded_null |= 0x04;
} else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 1200) {
encoded_null |= 0x05;
} else {
encoded_null |= 0x06;
}

encoded_null = AP_ADSB::convert_maxknots_to_enum(_frontend.out_state.cfg.maxAircraftSpeed_knots);

if (_frontend.out_state.cfg.rf_capable & ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN) {
encoded_null |= 0x10;
Expand Down
Loading
Loading