mirror of
https://github.com/okalachev/flix.git
synced 2026-01-11 21:46:55 +00:00
Increase thrust to ARMED_THRUST if it's less
This commit is contained in:
@@ -135,7 +135,7 @@ void controlTorque() {
|
||||
return;
|
||||
}
|
||||
|
||||
if (thrustTarget < 0.05) {
|
||||
if (thrustTarget < ARMED_THRUST) {
|
||||
// minimal thrust to indicate armed state
|
||||
motors[0] = ARMED_THRUST;
|
||||
motors[1] = ARMED_THRUST;
|
||||
|
||||
Reference in New Issue
Block a user