mirror of
https://github.com/okalachev/flix.git
synced 2025-07-27 09:39:33 +00:00
Don't let throttle be less than 0 in failsafe
This commit is contained in:
parent
f06a9301df
commit
4f2cf0c0b1
@ -19,4 +19,5 @@ void descend() {
|
||||
controls[RC_CHANNEL_PITCH] = 0;
|
||||
controls[RC_CHANNEL_YAW] = 0;
|
||||
controls[RC_CHANNEL_THROTTLE] -= dt / DESCEND_TIME;
|
||||
if (controls[RC_CHANNEL_THROTTLE] < 0) controls[RC_CHANNEL_THROTTLE] = 0;
|
||||
}
|
||||
|
Loading…
x
Reference in New Issue
Block a user