mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ACM: Altered the scaling speed for altitude changes for faster rises.
This commit is contained in:
parent
204f9957b0
commit
eb53200179
@ -429,9 +429,9 @@ static int32_t get_new_altitude()
|
|||||||
if (next_WP.alt < target_altitude){
|
if (next_WP.alt < target_altitude){
|
||||||
// we are below the target alt
|
// we are below the target alt
|
||||||
if(diff < 200){
|
if(diff < 200){
|
||||||
_scale = 5;
|
|
||||||
} else {
|
|
||||||
_scale = 4;
|
_scale = 4;
|
||||||
|
} else {
|
||||||
|
_scale = 3;
|
||||||
}
|
}
|
||||||
}else {
|
}else {
|
||||||
// we are above the target, going down
|
// we are above the target, going down
|
||||||
|
Loading…
Reference in New Issue
Block a user