Skip to content

Commit

Permalink
AP_GPS: add checking of instance number before update with incoming data
Browse files Browse the repository at this point in the history
  • Loading branch information
Bron2002 committed May 29, 2024
1 parent faf47f2 commit ad5bab7
Showing 1 changed file with 4 additions and 0 deletions.
4 changes: 4 additions & 0 deletions libraries/AP_GPS/AP_GPS_MAV.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,9 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t &msg)

// check if target instatce belong to incoming gps data.
if (state.instance != packet.gps_id)
{
return;
}

bool have_alt = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_ALT) == 0);
bool have_hdop = ((packet.ignore_flags & GPS_INPUT_IGNORE_FLAG_HDOP) == 0);
Expand Down Expand Up @@ -150,7 +152,9 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t &msg)

// check if target instatce belong to incoming gps data.
if (state.instance != packet.id)
{
return;
}

state.time_week = 0;
state.time_week_ms = packet.time_usec/1000;
Expand Down

0 comments on commit ad5bab7

Please sign in to comment.