mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
fixed the "reboot on GPS lock" bug
the problem was that with APM2 we may not have a 2nd GCS instance. The "gps alt: xxx" message was being unconditionally sent to both GCS instances, which caused a crash
This commit is contained in:
parent
b4965d34a9
commit
39a36fe946
@ -1799,5 +1799,7 @@ static void gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
||||
vsnprintf((char *)pending_status.text, sizeof(pending_status.text), fmtstr, ap);
|
||||
va_end(ap);
|
||||
mavlink_send_message(MAVLINK_COMM_0, MSG_STATUSTEXT, 0);
|
||||
mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0);
|
||||
if (gcs3.initialised) {
|
||||
mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0);
|
||||
}
|
||||
}
|
||||
|
@ -2103,5 +2103,7 @@ static void gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
||||
vsnprintf((char *)pending_status.text, sizeof(pending_status.text), fmtstr, ap);
|
||||
va_end(ap);
|
||||
mavlink_send_message(MAVLINK_COMM_0, MSG_STATUSTEXT, 0);
|
||||
mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0);
|
||||
if (gcs3.initialised) {
|
||||
mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user