mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
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:
parent
92f34a19d3
commit
e995a198bd
@ -665,9 +665,6 @@ found_gps:
|
|||||||
timing[instance].last_message_time_ms = now;
|
timing[instance].last_message_time_ms = now;
|
||||||
timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
|
timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
|
||||||
new_gps->broadcast_gps_type();
|
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
|
#if GPS_MAX_RECEIVERS > 1
|
||||||
void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
|
void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
// always send the message once we've ever seen the GPS
|
// always send the message if 2nd GPS is configured
|
||||||
if (!has_had_second_instance) {
|
if (_type[1] == GPS_TYPE_NONE) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -659,9 +659,6 @@ private:
|
|||||||
|
|
||||||
// used for flight testing with GPS yaw loss
|
// used for flight testing with GPS yaw loss
|
||||||
bool _force_disable_gps_yaw;
|
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 {
|
namespace AP {
|
||||||
|
Loading…
Reference in New Issue
Block a user