GCS_MAVLink: added support for passthrough telemetry over crossfire
This commit is contained in:
parent
6b26a64f77
commit
1c3b7d5ecd
@ -45,6 +45,7 @@
|
|||||||
#include <AP_Scripting/AP_Scripting.h>
|
#include <AP_Scripting/AP_Scripting.h>
|
||||||
#include <AP_Winch/AP_Winch.h>
|
#include <AP_Winch/AP_Winch.h>
|
||||||
#include <AP_OSD/AP_OSD.h>
|
#include <AP_OSD/AP_OSD.h>
|
||||||
|
#include <AP_RCTelemetry/AP_CRSF_Telem.h>
|
||||||
|
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
@ -1947,6 +1948,12 @@ void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, u
|
|||||||
if (spektrum != nullptr) {
|
if (spektrum != nullptr) {
|
||||||
spektrum->queue_message(severity, first_piece_of_text);
|
spektrum->queue_message(severity, first_piece_of_text);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
#if HAL_CRSF_TELEM_ENABLED
|
||||||
|
AP_CRSF_Telem* crsf = AP::crsf_telem();
|
||||||
|
if (crsf != nullptr) {
|
||||||
|
crsf->queue_message(severity, first_piece_of_text);
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
AP_Notify *notify = AP_Notify::get_singleton();
|
AP_Notify *notify = AP_Notify::get_singleton();
|
||||||
if (notify) {
|
if (notify) {
|
||||||
|
Loading…
Reference in New Issue
Block a user