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

@@ -14,6 +14,7 @@ extern double t;
extern uint16_t channels[16];
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
extern int mode;
extern bool armed;
const char* motd =
"\nWelcome to\n"
@@ -33,6 +34,8 @@ const char* motd =
"ps - show pitch/roll/yaw\n"
"psq - show attitude quaternion\n"
"imu - show IMU data\n"
"arm - arm the drone\n"
"disarm - disarm the drone\n"
"stab / acro - set mode\n"
"rc - show RC data\n"
"mot - show motor output\n"
@@ -109,6 +112,10 @@ void doCommand(String str, bool echo = false) {
printIMUInfo();
printIMUCalibration();
print("landed: %d\n", landed);
} else if (command == "arm") {
armed = true;
} else if (command == "disarm") {
armed = false;
} else if (command == "stab") {
mode = STAB;
} else if (command == "acro") {
@@ -121,6 +128,7 @@ void doCommand(String str, bool echo = false) {
print("\nroll: %g pitch: %g yaw: %g throttle: %g mode: %g\n",
controlRoll, controlPitch, controlYaw, controlThrottle, controlMode);
print("mode: %s\n", getModeName());
print("armed: %d\n", armed);
} else if (command == "mot") {
print("front-right %g front-left %g rear-right %g rear-left %g\n",
motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]);

View File

@@ -9,6 +9,7 @@
#include "lpf.h"
#include "util.h"
#define ARMED_THRUST 0.1 // thrust to indicate armed state
#define PITCHRATE_P 0.05
#define PITCHRATE_I 0.2
#define PITCHRATE_D 0.001
@@ -54,7 +55,7 @@ Vector torqueTarget;
float thrustTarget;
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlArmed, controlMode;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
void control() {
interpretControls();
@@ -65,14 +66,14 @@ void control() {
}
void interpretControls() {
armed = controlThrottle >= 0.05;
if (controlArmed < 0.5) armed = false;
// NOTE: put ACRO or MANUAL modes there if you want to use them
if (controlMode < 0.25) mode = STAB;
if (controlMode < 0.75) mode = STAB;
if (controlMode > 0.75) mode = STAB;
if (controlThrottle < 0.05 && controlYaw > 0.95) armed = true; // arm gesture
if (controlThrottle < 0.05 && controlYaw < -0.95) armed = false; // disarm gesture
thrustTarget = controlThrottle;
if (mode == STAB) {
@@ -137,8 +138,17 @@ void controlRates() {
void controlTorque() {
if (!torqueTarget.valid()) return; // skip torque control
if (!armed || thrustTarget < 0.05) {
memset(motors, 0, sizeof(motors)); // stop motors if no thrust
if (!armed) {
memset(motors, 0, sizeof(motors)); // stop motors if disarmed
return;
}
if (thrustTarget < 0.05) {
// minimal thrust to indicate armed state
motors[0] = ARMED_THRUST;
motors[1] = ARMED_THRUST;
motors[2] = ARMED_THRUST;
motors[3] = ARMED_THRUST;
return;
}

View File

@@ -10,19 +10,9 @@ extern double controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
void failsafe() {
armingFailsafe();
rcLossFailsafe();
}
// Prevent arming without zero throttle input
void armingFailsafe() {
static double zeroThrottleTime;
static double armingTime;
if (!armed) armingTime = t; // stores the last time when the drone was disarmed, therefore contains arming time
if (controlTime > 0 && controlThrottle < 0.05) zeroThrottleTime = controlTime;
if (armingTime - zeroThrottleTime > 0.1) armed = false; // prevent arming if there was no zero throttle for 0.1 sec
}
// RC loss failsafe
void rcLossFailsafe() {
if (t - controlTime > RC_LOSS_TIMEOUT) {
@@ -37,5 +27,8 @@ void descend() {
controlPitch = 0;
controlYaw = 0;
controlThrottle -= dt / DESCEND_TIME;
if (controlThrottle < 0) controlThrottle = 0;
if (controlThrottle < 0) {
armed = false;
controlThrottle = 0;
}
}

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

View File

@@ -12,11 +12,10 @@
#define PERIOD_FAST 0.1
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
float mavlinkControlScale = 0.7;
String mavlinkPrintBuffer;
extern double controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlArmed, controlMode;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
void processMavlink() {
sendMavlink();
@@ -99,11 +98,10 @@ void handleMavlink(const void *_msg) {
if (m.target && m.target != SYSTEM_ID) return; // 0 is broadcast
controlThrottle = m.z / 1000.0f;
controlPitch = m.x / 1000.0f * mavlinkControlScale;
controlRoll = m.y / 1000.0f * mavlinkControlScale;
controlYaw = m.r / 1000.0f * mavlinkControlScale;
controlPitch = m.x / 1000.0f;
controlRoll = m.y / 1000.0f;
controlYaw = m.r / 1000.0f;
controlMode = NAN;
controlArmed = NAN;
controlTime = t;
if (abs(controlYaw) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controlYaw = 0;

View File

@@ -70,12 +70,7 @@ Parameter parameters[] = {
{"RC_PITCH", &pitchChannel},
{"RC_THROTTLE", &throttleChannel},
{"RC_YAW", &yawChannel},
{"RC_ARMED", &armedChannel},
{"RC_MODE", &modeChannel},
#if WIFI_ENABLED
// MAVLink
{"MAV_CTRL_SCALE", &mavlinkControlScale},
#endif
};
void setupParameters() {

View File

@@ -14,7 +14,7 @@ float channelZero[16]; // calibration zero values
float channelMax[16]; // calibration max values
// Channels mapping (using float to store in parameters):
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, armedChannel = NAN, modeChannel = NAN;
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
void setupRC() {
print("Setup RC\n");
@@ -42,7 +42,6 @@ void normalizeRC() {
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN;
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN;
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN;
controlArmed = armedChannel >= 0 ? controls[(int)armedChannel] : NAN;
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN;
}
@@ -58,8 +57,7 @@ void calibrateRC() {
calibrateRCChannel(&yawChannel, center, max, "5/9 Move sticks [3 sec]\n... ...\n..o .o.\n... ...\n");
calibrateRCChannel(&pitchChannel, zero, max, "6/9 Move sticks [3 sec]\n... .o.\n... ...\n.o. ...\n");
calibrateRCChannel(&rollChannel, zero, max, "7/9 Move sticks [3 sec]\n... ...\n... ..o\n.o. ...\n");
calibrateRCChannel(&armedChannel, zero, max, "8/9 Switch to armed [3 sec]\n");
calibrateRCChannel(&modeChannel, zero, max, "9/9 Disarm and switch mode to max [3 sec]\n");
calibrateRCChannel(&modeChannel, zero, max, "9/9 Put mode switch to max [3 sec]\n");
printRCCalibration();
}
@@ -94,6 +92,5 @@ void printRCCalibration() {
print("Pitch %-7g%-7g%-7g\n", pitchChannel, pitchChannel >= 0 ? channelZero[(int)pitchChannel] : NAN, pitchChannel >= 0 ? channelMax[(int)pitchChannel] : NAN);
print("Yaw %-7g%-7g%-7g\n", yawChannel, yawChannel >= 0 ? channelZero[(int)yawChannel] : NAN, yawChannel >= 0 ? channelMax[(int)yawChannel] : NAN);
print("Throttle %-7g%-7g%-7g\n", throttleChannel, throttleChannel >= 0 ? channelZero[(int)throttleChannel] : NAN, throttleChannel >= 0 ? channelMax[(int)throttleChannel] : NAN);
print("Armed %-7g%-7g%-7g\n", armedChannel, armedChannel >= 0 ? channelZero[(int)armedChannel] : NAN, armedChannel >= 0 ? channelMax[(int)armedChannel] : NAN);
print("Mode %-7g%-7g%-7g\n", modeChannel, modeChannel >= 0 ? channelZero[(int)modeChannel] : NAN, modeChannel >= 0 ? channelMax[(int)modeChannel] : NAN);
}