mirror of https://github.com/ArduPilot/ardupilot
Rover: GPS fix to ensure we only look at new GPS messages
This commit is contained in:
parent
e81973cd29
commit
bbbbd07935
|
@ -348,7 +348,8 @@ void Rover::update_GPS_10Hz(void)
|
|||
{
|
||||
have_position = ahrs.get_position(current_loc);
|
||||
|
||||
if (have_position && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||
if (gps.last_message_time_ms() != last_gps_msg_ms && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||
last_gps_msg_ms = gps.last_message_time_ms();
|
||||
|
||||
if (ground_start_count > 1){
|
||||
ground_start_count--;
|
||||
|
|
|
@ -375,6 +375,8 @@ private:
|
|||
// we need to run the speed controller
|
||||
bool auto_throttle_mode;
|
||||
|
||||
// Store the time the last GPS message was received.
|
||||
uint32_t last_gps_msg_ms{0};
|
||||
|
||||
private:
|
||||
// private member functions
|
||||
|
|
Loading…
Reference in New Issue