Refactor arming logic

Arm and disarm with gestures only: left stick right/down for arming, left/down for disarming.
Remove arming switch as it complicates arming gestures logic.
Remove MAV_CTRL_SCALE parameter as it complicates arming gestures logic, advise to decrease TILT_MAX when controlling with a smartphone.
Put some minimal thrust to motors to indicate armed state.
Rename build article to usage article, add flight instructions.
This commit is contained in:
Oleg Kalachev
2025-08-27 03:19:26 +03:00
parent beb655fdcb
commit c1788e2c75
17 changed files with 451 additions and 245 deletions

View File

@@ -13,7 +13,7 @@
double t = NAN; // current step time, s
float dt; // time delta from previous step, s
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlArmed = NAN, controlMode = NAN;
float controlMode = NAN;
Vector gyro; // gyroscope data
Vector acc; // accelerometer data, m/s/s
Vector rates; // filtered angular rates, rad/s