Skip to content

Commit

Permalink
AP_GPS: prevent announcing DroneCAN at 5Hz
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Feb 21, 2024
1 parent feff639 commit 77a5512
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 2 deletions.
3 changes: 1 addition & 2 deletions libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1000,8 +1000,7 @@ void AP_GPS::update_instance(uint8_t instance)
state[instance].corrected_timestamp_updated = false;
}

// we set delta_time_ms to the timeout value when clearing
// state; use it being zero to mark first message
// announce the GPS type once
if (!state[instance].announced_detection) {
state[instance].announced_detection = true;
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: detected %s", instance + 1, drivers[instance]->name());
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_GPS/AP_GPS_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -717,6 +717,9 @@ bool AP_GPS_DroneCAN::read(void)
interim_state.vertical_accuracy = MIN(interim_state.vertical_accuracy, 1000.0);
interim_state.speed_accuracy = MIN(interim_state.speed_accuracy, 1000.0);

// prevent announcing multiple times
interim_state.announced_detection = state.announced_detection;

state = interim_state;
if (interim_state.last_corrected_gps_time_us) {
// If we were able to get a valid last_corrected_gps_time_us
Expand Down

0 comments on commit 77a5512

Please sign in to comment.