AP_GPS: Fix MAVLink message field SYSTEM_TIME.time_unix_usec when GPS_AUTO_SWITCH = blend
The mavlink message field SYSTEM_TIME.time_unix_usec works fine with GPS_AUTO_SWITCH == 0 (no switch) or ==1 (usebest) But when GPS_AUTO_SWITCH == 2 (blend) then state[GPS_BLENDED_INSTANCE].last_gps_time_ms gets initialized with 0 and never rewritten. The consequence: SYSTEM_TIME.time_unix_usec gets stuck at zero. The solution: Do not reset state[GPS_BLENDED_INSTANCE].last_gps_time_ms because it would overwrite the correct value already set on line 1149
This commit is contained in:
parent
85b7f1bbb4
commit
d3a18e803e
@ -1305,7 +1305,6 @@ void AP_GPS::calc_blended_state(void)
|
||||
state[GPS_BLENDED_INSTANCE].have_speed_accuracy = false;
|
||||
state[GPS_BLENDED_INSTANCE].have_horizontal_accuracy = false;
|
||||
state[GPS_BLENDED_INSTANCE].have_vertical_accuracy = false;
|
||||
state[GPS_BLENDED_INSTANCE].last_gps_time_ms = 0;
|
||||
memset(&state[GPS_BLENDED_INSTANCE].location, 0, sizeof(state[GPS_BLENDED_INSTANCE].location));
|
||||
|
||||
_blended_antenna_offset.zero();
|
||||
|
Loading…
Reference in New Issue
Block a user