diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 5af6e0c1672fbc..cdf136e973851a 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -402,12 +402,14 @@ class GCS_MAVLINK void send_uavionix_adsb_out_status() const; void send_autopilot_state_for_gimbal_device() const; +#if AP_MAVLINK_MSG_FLIGHT_INFORMATION_ENABLED struct { MAV_LANDED_STATE last_landed_state; uint64_t takeoff_time_us; } flight_info; void send_flight_information(); +#endif // lock a channel, preventing use by MAVLink void lock(bool _lock) { diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index f3b49273e7de16..609b4f798ad1b9 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5964,6 +5964,7 @@ void GCS_MAVLINK::send_autopilot_state_for_gimbal_device() const #endif // AP_AHRS_ENABLED } +#if AP_MAVLINK_MSG_FLIGHT_INFORMATION_ENABLED void GCS_MAVLINK::send_flight_information() { const uint32_t time_boot_us = AP_HAL::millis64(); @@ -6013,6 +6014,7 @@ void GCS_MAVLINK::send_flight_information() flight_number ); } +#endif // AP_MAVLINK_MSG_FLIGHT_INFORMATION_ENABLED void GCS_MAVLINK::send_received_message_deprecation_warning(const char * message) { @@ -6445,10 +6447,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; #endif +#if AP_MAVLINK_MSG_FLIGHT_INFORMATION_ENABLED case MSG_FLIGHT_INFORMATION: CHECK_PAYLOAD_SIZE(FLIGHT_INFORMATION); send_flight_information(); break; +#endif default: // try_send_message must always at some stage return true for diff --git a/libraries/GCS_MAVLink/GCS_config.h b/libraries/GCS_MAVLink/GCS_config.h index 0bf028f64f6dfd..26628a43fad360 100644 --- a/libraries/GCS_MAVLink/GCS_config.h +++ b/libraries/GCS_MAVLink/GCS_config.h @@ -135,3 +135,7 @@ #ifndef AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED #define AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED (BOARD_FLASH_SIZE > 1024) #endif + +#ifndef AP_MAVLINK_MSG_FLIGHT_INFORMATION_ENABLED +#define AP_MAVLINK_MSG_FLIGHT_INFORMATION_ENABLED 1 +#endif diff --git a/libraries/GCS_MAVLink/ap_message.h b/libraries/GCS_MAVLink/ap_message.h index 8d1f3d6133a1ac..6d0bdc95ddde2f 100644 --- a/libraries/GCS_MAVLink/ap_message.h +++ b/libraries/GCS_MAVLink/ap_message.h @@ -97,6 +97,8 @@ enum ap_message : uint8_t { #if AP_MAVLINK_MSG_HIGHRES_IMU_ENABLED MSG_HIGHRES_IMU, #endif +#if AP_MAVLINK_MSG_FLIGHT_INFORMATION_ENABLED MSG_FLIGHT_INFORMATION, +#endif MSG_LAST // MSG_LAST must be the last entry in this enum };