mirror of https://github.com/ArduPilot/ardupilot
added workaround for resetting alt.
This commit is contained in:
parent
fa32b084bd
commit
bcd5129f9b
|
@ -326,6 +326,13 @@ static void clear_new_altitude()
|
|||
|
||||
static void set_new_altitude(int32_t _new_alt)
|
||||
{
|
||||
if(_new_alt == current_loc.alt){
|
||||
next_WP.alt = _new_alt;
|
||||
target_altitude = _new_alt;
|
||||
alt_change_flag = REACHED_ALT;
|
||||
return;
|
||||
}
|
||||
|
||||
// just to be clear
|
||||
next_WP.alt = current_loc.alt;
|
||||
|
||||
|
|
Loading…
Reference in New Issue