mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Plane: fixed conditional for 0 lat/lon
This commit is contained in:
parent
fdac41dbab
commit
343a682d22
@ -390,7 +390,7 @@ static void do_loiter_to_alt(const AP_Mission::Mission_Command& cmd)
|
|||||||
condition_value = next_WP_loc.alt;
|
condition_value = next_WP_loc.alt;
|
||||||
|
|
||||||
//are lat and lon 0? if so, don't change the current wp lat/lon
|
//are lat and lon 0? if so, don't change the current wp lat/lon
|
||||||
if (cmd.content.location.lat != 0 && cmd.content.location.lng != 0) {
|
if (cmd.content.location.lat != 0 || cmd.content.location.lng != 0) {
|
||||||
set_next_WP(cmd.content.location);
|
set_next_WP(cmd.content.location);
|
||||||
}
|
}
|
||||||
//set loiter direction
|
//set loiter direction
|
||||||
|
Loading…
Reference in New Issue
Block a user