mirror of
https://github.com/okalachev/flix.git
synced 2025-07-29 12:28:59 +00:00
Don't let throttle be less than 0 in failsafe
This commit is contained in:
parent
441f82af95
commit
931f46b92d
@ -19,4 +19,5 @@ void descend() {
|
|||||||
controls[RC_CHANNEL_PITCH] = 0;
|
controls[RC_CHANNEL_PITCH] = 0;
|
||||||
controls[RC_CHANNEL_YAW] = 0;
|
controls[RC_CHANNEL_YAW] = 0;
|
||||||
controls[RC_CHANNEL_THROTTLE] -= dt / DESCEND_TIME;
|
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