mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
GCS_MAVLink: add EFI_STATUS message
This commit is contained in:
parent
9799302225
commit
00e3344321
@ -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)
|
||||
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
|
||||
|
@ -73,5 +73,6 @@ enum ap_message : uint8_t {
|
||||
MSG_NAMED_FLOAT,
|
||||
MSG_EXTENDED_SYS_STATE,
|
||||
MSG_AUTOPILOT_VERSION,
|
||||
MSG_EFI_STATUS,
|
||||
MSG_LAST // MSG_LAST must be the last entry in this enum
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user