AP_ADSB: correct compilation when GCS not compiled in

... and logging.

Also correct default compilation for mavlink backend to not be attempted if HAL_GCS_ENABLED is false
This commit is contained in:
Tom Pittenger 2023-03-01 12:33:09 -08:00 committed by Tom Pittenger
parent 4f2344f397
commit 61f6c0dc3d
6 changed files with 25 additions and 14 deletions

View File

@ -198,7 +198,7 @@ void AP_ADSB::init(void)
if (in_state.vehicle_list == nullptr) {
// dynamic RAM allocation of in_state.vehicle_list[] failed
_init_failed = true; // this keeps us from constantly trying to init forever in main update
gcs().send_text(MAV_SEVERITY_INFO, "ADSB: Unable to initialize ADSB vehicle list");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: Unable to initialize ADSB vehicle list");
return;
}
in_state.list_size_allocated = in_state.list_size_param;
@ -222,7 +222,7 @@ void AP_ADSB::init(void)
if (detected_num_instances == 0) {
_init_failed = true;
gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB: Unable to initialize ADSB driver");
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB: Unable to initialize ADSB driver");
}
}
@ -563,7 +563,9 @@ void AP_ADSB::set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle)
}
in_state.vehicle_list[index] = vehicle;
#if HAL_LOGGING_ENABLED
write_log(vehicle);
#endif
}
void AP_ADSB::send_adsb_vehicle(const mavlink_channel_t chan)
@ -632,7 +634,7 @@ void AP_ADSB::handle_out_cfg(const mavlink_uavionix_adsb_out_cfg_t &packet)
// guard against string with non-null end char
const char c = out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1];
out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = 0;
gcs().send_text(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", (int)out_state.cfg.ICAO_id, out_state.cfg.callsign);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", (int)out_state.cfg.ICAO_id, out_state.cfg.callsign);
out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = c;
// send now
@ -666,7 +668,7 @@ 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)
{
if (out_state.chan != chan) {
gcs().send_text(MAV_SEVERITY_DEBUG, "ADSB: Found transceiver on channel %d", chan);
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "ADSB: Found transceiver on channel %d", chan);
}
out_state.chan_last_ms = AP_HAL::millis();
@ -820,6 +822,7 @@ bool AP_ADSB::get_vehicle_by_ICAO(const uint32_t icao, adsb_vehicle_t &vehicle)
return false;
}
#if HAL_LOGGING_ENABLED
/*
* Write vehicle to log
*/
@ -854,6 +857,7 @@ void AP_ADSB::write_log(const adsb_vehicle_t &vehicle) const
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}
#endif // HAL_LOGGING_ENABLED
/**
* @brief 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.

View File

@ -19,6 +19,8 @@
#if HAL_ADSB_SAGETECH_ENABLED
#include <GCS_MAVLink/GCS.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_RTC/AP_RTC.h>
#include <AP_HAL/utility/sparse-endian.h>
@ -190,7 +192,7 @@ void AP_ADSB_Sagetech::handle_ack(const Packet_XP &msg)
if (prev_transponder_mode != last_ack_transponder_mode) {
static const char *mode_names[] = {"OFF", "STBY", "ON", "ON-ALT"};
if (last_ack_transponder_mode < ARRAY_SIZE(mode_names)) {
gcs().send_text(MAV_SEVERITY_INFO, "ADSB: RF Mode: %s", mode_names[last_ack_transponder_mode]);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: RF Mode: %s", mode_names[last_ack_transponder_mode]);
}
}
}

View File

@ -26,6 +26,8 @@
#if HAL_ADSB_SAGETECH_MXS_ENABLED
#include <GCS_MAVLink/GCS.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_RTC/AP_RTC.h>
#include <stdio.h>
#include <time.h>
@ -109,7 +111,7 @@ void AP_ADSB_Sagetech_MXS::update()
}
} else if (last.packet_initialize_ms > MXS_INIT_TIMEOUT && !mxs_state.init_failed) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB Sagetech MXS: Initialization Timeout. Failed to initialize.");
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Sagetech MXS: Initialization Timeout. Failed to initialize.");
mxs_state.init_failed = true;
}
@ -312,7 +314,7 @@ void AP_ADSB_Sagetech_MXS::msg_write(const uint8_t *data, const uint16_t len) co
void AP_ADSB_Sagetech_MXS::auto_config_operating()
{
// Configure the Default Operation Message Data
// Configure the Default Operation Message Data
mxs_state.op.squawk = AP_ADSB::convert_base_to_decimal(8, _frontend.out_state.cfg.squawk_octal);
mxs_state.op.opMode = sg_op_mode_t::modeOff; // MXS needs to start in OFF mode to accept installation message
mxs_state.op.savePowerUp = true; // Save power-up state in non-volatile
@ -421,15 +423,15 @@ void AP_ADSB_Sagetech_MXS::auto_config_flightid()
void AP_ADSB_Sagetech_MXS::handle_ack(const sg_ack_t ack)
{
if ((ack.ackId != last.msg.id) || (ack.ackType != last.msg.type)) {
// gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: ACK: Message %d of type %02x not acknowledged.", last.msg.id, last.msg.type);
// GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: ACK: Message %d of type %02x not acknowledged.", last.msg.id, last.msg.type);
}
// System health
if (ack.failXpdr && !last.failXpdr) {
gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: Transponder Failure");
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: Transponder Failure");
_frontend.out_state.tx_status.fault |= UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL;
}
if (ack.failSystem && !last.failSystem) {
gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: System Failure");
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: System Failure");
_frontend.out_state.tx_status.fault |= UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL;
}
last.failXpdr = ack.failXpdr;
@ -529,7 +531,7 @@ void AP_ADSB_Sagetech_MXS::send_install_msg()
{
// MXS must be in OFF mode to change ICAO or Registration
if (mxs_state.op.opMode != modeOff) {
// gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: unable to send installation data while not in OFF mode.");
// GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: unable to send installation data while not in OFF mode.");
return;
}

View File

@ -2,13 +2,14 @@
#include <AP_HAL/AP_HAL_Boards.h>
#include <GCS_MAVLink/GCS_config.h>
#ifndef HAL_ADSB_ENABLED
#define HAL_ADSB_ENABLED BOARD_FLASH_SIZE > 1024
#endif
#ifndef HAL_ADSB_UAVIONIX_MAVLINK_ENABLED
#define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED HAL_ADSB_ENABLED
#define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED HAL_ADSB_ENABLED && HAL_GCS_ENABLED
#endif
#ifndef HAL_ADSB_SAGETECH_ENABLED

View File

@ -45,7 +45,7 @@ void AP_ADSB_uAvionix_MAVLink::update()
// haven't gotten a heartbeat health status packet in a while, assume hardware failure
_frontend.out_state.chan = -1;
_frontend.out_state.chan_last_ms = 0; // if the time isn't reset we spam the message
gcs().send_text(MAV_SEVERITY_ERROR, "ADSB: Transceiver heartbeat timed out");
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "ADSB: Transceiver heartbeat timed out");
} else if (_frontend.out_state.chan >= 0 && !_frontend._my_loc.is_zero() && _frontend.out_state.chan < MAVLINK_COMM_NUM_BUFFERS) {
const mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0 + _frontend.out_state.chan);
if (now - _frontend.out_state.last_config_ms >= 5000 && HAVE_PAYLOAD_SPACE(chan, UAVIONIX_ADSB_OUT_CFG)) {
@ -253,4 +253,4 @@ void AP_ADSB_uAvionix_MAVLink::send_configure(const mavlink_channel_t chan)
(uint8_t)_frontend.out_state.cfg.rfSelect);
}
#endif // HAL_ADSB_ENABLED
#endif // HAL_ADSB_UAVIONIX_MAVLINK_ENABLED

View File

@ -253,7 +253,9 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg)
_frontend.out_state.ctrl.x_bit = rx.decoded.transponder_status.x_bit;
}
run_state.last_packet_Transponder_Status_ms = AP_HAL::millis();
#if HAL_GCS_ENABLED
gcs().send_message(MSG_UAVIONIX_ADSB_OUT_STATUS);
#endif
break;
#endif // AP_ADSB_UAVIONIX_UCP_CAPTURE_ALL_RX_PACKETS