mirror of https://github.com/ArduPilot/ardupilot
Rover: To add a judgment of 0 degrees longitude.
This commit is contained in:
parent
0d113b265c
commit
eec491a1f9
|
@ -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();
|
||||
|
|
Loading…
Reference in New Issue