mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: Don't defeat the GCS message interval code
This commit is contained in:
parent
80bd038333
commit
5bafd7d72c
@ -960,21 +960,6 @@ void AP_GPS::inject_data(uint8_t instance, uint8_t *data, uint16_t len)
|
||||
|
||||
void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
|
||||
{
|
||||
static uint32_t last_send_time_ms[MAVLINK_COMM_NUM_BUFFERS];
|
||||
if (status(0) > AP_GPS::NO_GPS) {
|
||||
// when we have a GPS then only send new data
|
||||
if (last_send_time_ms[chan] == last_message_time_ms(0)) {
|
||||
return;
|
||||
}
|
||||
last_send_time_ms[chan] = last_message_time_ms(0);
|
||||
} else {
|
||||
// when we don't have a GPS then send at 1Hz
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if (now - last_send_time_ms[chan] < 1000) {
|
||||
return;
|
||||
}
|
||||
last_send_time_ms[chan] = now;
|
||||
}
|
||||
const Location &loc = location(0);
|
||||
float hacc = 0.0f;
|
||||
float vacc = 0.0f;
|
||||
@ -1004,15 +989,9 @@ 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)
|
||||
{
|
||||
static uint32_t last_send_time_ms[MAVLINK_COMM_NUM_BUFFERS];
|
||||
if (num_instances < 2 || status(1) <= AP_GPS::NO_GPS) {
|
||||
return;
|
||||
}
|
||||
// when we have a GPS then only send new data
|
||||
if (last_send_time_ms[chan] == last_message_time_ms(1)) {
|
||||
return;
|
||||
}
|
||||
last_send_time_ms[chan] = last_message_time_ms(1);
|
||||
|
||||
const Location &loc = location(1);
|
||||
mavlink_msg_gps2_raw_send(
|
||||
|
Loading…
Reference in New Issue
Block a user