mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
ACM: Added force_new_altitude call to do immediate changes in altitude and no gradual changes.
This commit is contained in:
parent
83729d0f75
commit
204f9957b0
@ -347,16 +347,21 @@ static void clear_new_altitude()
|
|||||||
alt_change_flag = REACHED_ALT;
|
alt_change_flag = REACHED_ALT;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void set_new_altitude(int32_t _new_alt)
|
static void force_new_altitude(int32_t _new_alt)
|
||||||
{
|
{
|
||||||
if(_new_alt == current_loc.alt){
|
|
||||||
next_WP.alt = _new_alt;
|
next_WP.alt = _new_alt;
|
||||||
target_altitude = _new_alt;
|
target_altitude = _new_alt;
|
||||||
alt_change_flag = REACHED_ALT;
|
alt_change_flag = REACHED_ALT;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void set_new_altitude(int32_t _new_alt)
|
||||||
|
{
|
||||||
|
if(_new_alt == current_loc.alt){
|
||||||
|
force_new_altitude(_new_alt);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// just to be clear
|
// We start at the current location altitude and gradually change alt
|
||||||
next_WP.alt = current_loc.alt;
|
next_WP.alt = current_loc.alt;
|
||||||
|
|
||||||
// for calculating the delta time
|
// for calculating the delta time
|
||||||
|
Loading…
Reference in New Issue
Block a user