AP_ADSB: Allow MAVLink backends to be in only

This commit is contained in:
Michael du Breuil 2023-06-27 11:38:49 -07:00
parent 514434193d
commit bf9d87521b
3 changed files with 22 additions and 8 deletions

View File

@ -56,7 +56,7 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = {
// @Param: TYPE
// @DisplayName: ADSB Type
// @Description: Type of ADS-B hardware for ADSB-in and ADSB-out configuration and operation. If any type is selected then MAVLink based ADSB-in messages will always be enabled
// @Values: 0:Disabled,1:uAvionix-MAVLink,2:Sagetech,3:uAvionix-UCP,4:Sagetech MX Series
// @Values: 0:Disabled,1:uAvionix-MAVLink-InOut,2:Sagetech,3:uAvionix-UCP,4:Sagetech MX Series,5:uAvionix-MAVLink-In
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO_FLAGS("TYPE", 0, AP_ADSB, _type[0], 0, AP_PARAM_FLAG_ENABLE),
@ -258,7 +258,8 @@ void AP_ADSB::detect_instance(uint8_t instance)
case Type::None:
return;
case Type::uAvionix_MAVLink:
case Type::uAvionix_MAVLink_In:
case Type::uAvionix_MAVLink_InOut:
#if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED
if (AP_ADSB_uAvionix_MAVLink::detect()) {
_backend[instance] = new AP_ADSB_uAvionix_MAVLink(*this, instance);
@ -665,6 +666,13 @@ void AP_ADSB::handle_out_control(const mavlink_uavionix_adsb_out_control_t &pack
*/
void AP_ADSB::handle_transceiver_report(const mavlink_channel_t chan, const mavlink_uavionix_adsb_transceiver_health_report_t &packet)
{
// Don't ingest a transciever report, as it's used to trigger sending out control packets
if (_type[0] == (int8_t)(AP_ADSB::Type::uAvionix_MAVLink_In)) {
return;
}
// we need to refactor the code to use AP_SerialManager and ask the user to tell us which serial port is rx vs tx
static_assert(ADSB_MAX_INSTANCES == 1, "Transceiver control is not correctly handled with more then one receiver");
if (out_state.chan != chan) {
gcs().send_text(MAV_SEVERITY_DEBUG, "ADSB: Found transceiver on channel %d", chan);
}
@ -794,7 +802,7 @@ void AP_ADSB::handle_message(const mavlink_channel_t chan, const mavlink_message
break;
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL: {
mavlink_uavionix_adsb_out_control_t packet {};
mavlink_uavionix_adsb_out_control_t packet {};
mavlink_msg_uavionix_adsb_out_control_decode(&msg, &packet);
handle_out_control(packet);
break;

View File

@ -59,11 +59,12 @@ public:
// ADSB driver types
enum class Type {
None = 0,
uAvionix_MAVLink = 1,
Sagetech = 2,
uAvionix_UCP = 3,
Sagetech_MXS = 4,
None = 0,
uAvionix_MAVLink_InOut = 1,
Sagetech = 2,
uAvionix_UCP = 3,
Sagetech_MXS = 4,
uAvionix_MAVLink_In = 5,
};
struct adsb_vehicle_t {

View File

@ -38,6 +38,11 @@ bool AP_ADSB_uAvionix_MAVLink::detect()
void AP_ADSB_uAvionix_MAVLink::update()
{
// if we are an in only instance then we are done here, the work below is all related to sending outputs
if (_frontend.get_type(_instance) != AP_ADSB::Type::uAvionix_MAVLink_InOut) {
return;
}
const uint32_t now = AP_HAL::millis();
// send static configuration data to transceiver, every 5s