|
|
|
@ -1169,7 +1169,7 @@ void GCS_MAVLINK::send_ahrs(AP_AHRS &ahrs)
@@ -1169,7 +1169,7 @@ void GCS_MAVLINK::send_ahrs(AP_AHRS &ahrs)
|
|
|
|
|
/*
|
|
|
|
|
send a statustext message to all active MAVLink connections |
|
|
|
|
*/ |
|
|
|
|
void GCS_MAVLINK::send_statustext_all(const prog_char_t *fmt, ...) |
|
|
|
|
void GCS_MAVLINK::send_statustext_all(MAV_SEVERITY severity, const prog_char_t *fmt, ...) |
|
|
|
|
{ |
|
|
|
|
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) { |
|
|
|
|
if ((1U<<i) & mavlink_active) { |
|
|
|
@ -1181,7 +1181,7 @@ void GCS_MAVLINK::send_statustext_all(const prog_char_t *fmt, ...)
@@ -1181,7 +1181,7 @@ void GCS_MAVLINK::send_statustext_all(const prog_char_t *fmt, ...)
|
|
|
|
|
hal.util->vsnprintf_P((char *)msg2, sizeof(msg2), fmt, arg_list); |
|
|
|
|
va_end(arg_list); |
|
|
|
|
mavlink_msg_statustext_send(chan, |
|
|
|
|
MAV_SEVERITY_CRITICAL, |
|
|
|
|
severity, |
|
|
|
|
msg2); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|