Rover: To add a judgment of 0 degrees longitude.

This commit is contained in:
murata 2016-10-04 02:16:23 +09:00 committed by Lucas De Marchi
parent 0d113b265c
commit eec491a1f9
1 changed files with 1 additions and 1 deletions

View File

@ -369,7 +369,7 @@ void Rover::update_GPS_10Hz(void)
// We countdown N number of good GPS fixes
// so that the altitude is more accurate
// -------------------------------------
if (current_loc.lat == 0) {
if (current_loc.lat == 0 && current_loc.lng == 0) {
ground_start_count = 20;
} else {
init_home();