AP_GPS: always send GPS2_RAW if 2nd GPS configured

this improves the display on the GCS when the GPS has not yet been
found. This is particularly important after a reboot, as otherwise the
GCS may display stale information from the previous boot
This commit is contained in:
Andrew Tridgell 2020-10-05 08:18:12 +11:00 committed by Peter Barker
parent 92f34a19d3
commit e995a198bd
2 changed files with 2 additions and 8 deletions

View File

@ -665,9 +665,6 @@ found_gps:
timing[instance].last_message_time_ms = now;
timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
new_gps->broadcast_gps_type();
if (instance == 1) {
has_had_second_instance = true;
}
}
}
@ -1186,8 +1183,8 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
#if GPS_MAX_RECEIVERS > 1
void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
{
// always send the message once we've ever seen the GPS
if (!has_had_second_instance) {
// always send the message if 2nd GPS is configured
if (_type[1] == GPS_TYPE_NONE) {
return;
}

View File

@ -659,9 +659,6 @@ private:
// used for flight testing with GPS yaw loss
bool _force_disable_gps_yaw;
// used to ensure we continue sending status messages if we ever detected the second GPS
bool has_had_second_instance;
};
namespace AP {