mirror of https://github.com/ArduPilot/ardupilot
Plane: To add a judgment of 0 degrees longitude.
This commit is contained in:
parent
41f2450bf4
commit
2f18d1de73
|
@ -449,7 +449,7 @@ void Plane::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 = 5;
|
||||
|
||||
} else {
|
||||
|
|
|
@ -63,7 +63,7 @@ void Plane::navigate()
|
|||
return;
|
||||
}
|
||||
|
||||
if (next_WP_loc.lat == 0) {
|
||||
if (next_WP_loc.lat == 0 && next_WP_loc.lng == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue