|
|
|
@ -38,6 +38,7 @@
@@ -38,6 +38,7 @@
|
|
|
|
|
#include <AP_VisualOdom/AP_VisualOdom.h> |
|
|
|
|
#include <AP_OpticalFlow/OpticalFlow.h> |
|
|
|
|
#include <AP_Baro/AP_Baro.h> |
|
|
|
|
#include <AP_EFI/AP_EFI.h> |
|
|
|
|
|
|
|
|
|
#include <stdio.h> |
|
|
|
|
|
|
|
|
@ -4477,6 +4478,17 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
@@ -4477,6 +4478,17 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
case MSG_EFI_STATUS: { |
|
|
|
|
#if EFI_ENABLED |
|
|
|
|
CHECK_PAYLOAD_SIZE(EFI_STATUS); |
|
|
|
|
AP_EFI *efi = AP::EFI(); |
|
|
|
|
if (efi) { |
|
|
|
|
efi->send_mavlink_status(chan); |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
// try_send_message must always at some stage return true for
|
|
|
|
|
// a message, or we will attempt to infinitely retry the
|
|
|
|
|