1 Commits

Author SHA1 Message Date
Oleg Kalachev
f8f746b0cd Add level calibration 2026-01-30 07:49:26 +03:00
18 changed files with 63 additions and 73 deletions

Binary file not shown.

Before

Width:  |  Height:  |  Size: 44 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 55 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 105 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 34 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 36 KiB

View File

@@ -148,29 +148,27 @@ Reboot the drone to apply the changes.
> [!CAUTION] > [!CAUTION]
> **Remove the props when configuring the motors!** If improperly configured, you may not be able to stop them. > **Remove the props when configuring the motors!** If improperly configured, you may not be able to stop them.
### Important: check everything works ### Check everything works
1. Check the IMU is working: perform `imu` command in the console and check the output: 1. Check the IMU is working: perform `imu` command and check its output:
* The `status` field should be `OK`. * The `status` field should be `OK`.
* The `rate` field should be about 1000 (Hz). * The `rate` field should be about 1000 (Hz).
* The `accel` and `gyro` fields should change as you move the drone. * The `accel` and `gyro` fields should change as you move the drone.
* The `accel bias` and `accel scale` fields should contain calibration parameters (not zeros and ones).
* The `gyro bias` field should contain estimated gyro bias (not zeros).
* The `landed` field should be `1` when the drone is still on the ground and `0` when you lift it up. * The `landed` field should be `1` when the drone is still on the ground and `0` when you lift it up.
2. Check the attitude estimation: connect to the drone using QGroundControl, rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. Compare your attitude indicator (in the *large vertical* mode) to the video: 2. Check the attitude estimation: connect to the drone using QGroundControl, rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. Compare your attitude indicator (in the *large vertical* mode) to the video:
<a href="https://youtu.be/yVRN23-GISU"><img width=300 src="https://i3.ytimg.com/vi/yVRN23-GISU/maxresdefault.jpg"></a> <a href="https://youtu.be/yVRN23-GISU"><img width=300 src="https://i3.ytimg.com/vi/yVRN23-GISU/maxresdefault.jpg"></a>
3. Perform motor tests. Use the following commands **— remove the propellers before running the tests!** 3. Perform motor tests in the console. Use the following commands **— remove the propellers before running the tests!**
* `mfr` — rotate front right motor (counter-clockwise). * `mfr` — should rotate front right motor (counter-clockwise).
* `mfl` — rotate front left motor (clockwise). * `mfl` — should rotate front left motor (clockwise).
* `mrl` — rotate rear left motor (counter-clockwise). * `mrl` — should rotate rear left motor (counter-clockwise).
* `mrr` — rotate rear right motor (clockwise). * `mrr` — should rotate rear right motor (clockwise).
Make sure rotation directions and propeller types match the following diagram: Rotation diagram:
<img src="img/motors.svg" width=200> <img src="img/motors.svg" width=200>
@@ -236,11 +234,11 @@ When finished flying, **disarm** the drone, moving the left stick to the bottom
### Flight modes ### Flight modes
Flight mode is changed using mode switch on the remote control (if configured) or using the console commands. The main flight mode is *STAB*. Flight mode is changed using mode switch on the remote control or using the command line.
#### STAB #### STAB
In this mode, the drone stabilizes its attitude (orientation). The left stick controls throttle and yaw rate, the right stick controls pitch and roll angles. The default mode is *STAB*. In this mode, the drone stabilizes its attitude (orientation). The left stick controls throttle and yaw rate, the right stick controls pitch and roll angles.
> [!IMPORTANT] > [!IMPORTANT]
> The drone doesn't stabilize its position, so slight drift is possible. The pilot should compensate it manually. > The drone doesn't stabilize its position, so slight drift is possible. The pilot should compensate it manually.
@@ -255,7 +253,7 @@ In this mode, the pilot controls the angular rates. This control method is diffi
#### AUTO #### AUTO
In this mode, the pilot inputs are ignored (except the mode switch). The drone can be controlled using [pyflix](../tools/pyflix/) Python library, or by modifying the firmware to implement the needed behavior. In this mode, the pilot inputs are ignored (except the mode switch, if configured). The drone can be controlled using [pyflix](../tools/pyflix/) Python library, or by modifying the firmware to implement the needed autonomous behavior.
If the pilot moves the control sticks, the drone will switch back to *STAB* mode. If the pilot moves the control sticks, the drone will switch back to *STAB* mode.

View File

@@ -4,22 +4,6 @@ This page contains user-built drones based on the Flix project. Publish your pro
--- ---
Author: [FanBy0ru](https://https://github.com/FanBy0ru).<br>
Description: custom 3D-printed frame.<br>
Frame STLs and flight validation: https://cults3d.com/en/3d-model/gadget/armature-pour-flix-drone.
<img src="img/user/fanby0ru/1.jpg" height=200> <img src="img/user/fanby0ru/2.jpg" height=200>
---
Author: Ivan44 Phalko.<br>
Description: custom PCB, cusom test bench.<br>
[Flight validation](https://drive.google.com/file/d/17DNDJ1gPmCmDRAwjedCbJ9RXAyqMqqcX/view?usp=sharing).
<img src="img/user/phalko/1.jpg" height=200> <img src="img/user/phalko/2.jpg" height=200> <img src="img/user/phalko/3.jpg" height=200>
---
Author: **Arkadiy "Arky" Matsekh**, Foucault Dynamics, Gold Coast, Australia.<br> Author: **Arkadiy "Arky" Matsekh**, Foucault Dynamics, Gold Coast, Australia.<br>
The drone was built for the University of Queensland industry-led Master's capstone project. The drone was built for the University of Queensland industry-led Master's capstone project.

View File

@@ -46,6 +46,7 @@ const char* motd =
"log [dump] - print log header [and data]\n" "log [dump] - print log header [and data]\n"
"cr - calibrate RC\n" "cr - calibrate RC\n"
"ca - calibrate accel\n" "ca - calibrate accel\n"
"cl - calibrate level\n"
"mfr, mfl, mrr, mrl - test motor (remove props)\n" "mfr, mfl, mrr, mrl - test motor (remove props)\n"
"sys - show system info\n" "sys - show system info\n"
"reset - reset drone's state\n" "reset - reset drone's state\n"
@@ -151,6 +152,8 @@ void doCommand(String str, bool echo = false) {
calibrateRC(); calibrateRC();
} else if (command == "ca") { } else if (command == "ca") {
calibrateAccel(); calibrateAccel();
} else if (command == "cl") {
calibrateLevel();
} else if (command == "mfr") { } else if (command == "mfr") {
testMotor(MOTOR_FRONT_RIGHT); testMotor(MOTOR_FRONT_RIGHT);
} else if (command == "mfl") { } else if (command == "mfl") {

View File

@@ -1,7 +1,7 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com> // Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix // Repository: https://github.com/okalachev/flix
// Attitude estimation using gyro and accelerometer // Attitude estimation from gyro and accelerometer
#include "quaternion.h" #include "quaternion.h"
#include "vector.h" #include "vector.h"

View File

@@ -21,8 +21,8 @@ void setup() {
disableBrownOut(); disableBrownOut();
setupParameters(); setupParameters();
setupLED(); setupLED();
setLED(true);
setupMotors(); setupMotors();
setLED(true);
setupWiFi(); setupWiFi();
setupIMU(); setupIMU();
setupRC(); setupRC();

View File

@@ -110,6 +110,14 @@ void calibrateAccelOnce() {
accBias = (accMax + accMin) / 2; accBias = (accMax + accMin) / 2;
} }
void calibrateLevel() {
print("Place perfectly level [1 sec]\n");
pause(1);
Quaternion correction = Quaternion::fromBetweenVectors(Quaternion::rotateVector(Vector(0, 0, 1), attitude), Vector(0, 0, 1));
imuRotation = Quaternion::rotate(correction, Quaternion::fromEuler(imuRotation)).toEuler();
print("✓ Done: %.3f %.3f %.3f\n", degrees(imuRotation.x), degrees(imuRotation.y), degrees(imuRotation.z));
}
void printIMUCalibration() { void printIMUCalibration() {
print("gyro bias: %f %f %f\n", gyroBias.x, gyroBias.y, gyroBias.z); print("gyro bias: %f %f %f\n", gyroBias.x, gyroBias.y, gyroBias.z);
print("accel bias: %f %f %f\n", accBias.x, accBias.y, accBias.z); print("accel bias: %f %f %f\n", accBias.x, accBias.y, accBias.z);

View File

@@ -8,13 +8,12 @@
extern float controlTime; extern float controlTime;
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
int mavlinkSysId = 1; int mavlinkSysId = 1;
Rate telemetryFast(10); Rate telemetryFast(10);
Rate telemetrySlow(2); Rate telemetrySlow(2);
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
void processMavlink() { void processMavlink() {
sendMavlink(); sendMavlink();
receiveMavlink(); receiveMavlink();
@@ -42,9 +41,9 @@ void sendMavlink() {
} }
if (telemetryFast && mavlinkConnected) { if (telemetryFast && mavlinkConnected) {
const float offset[] = {0, 0, 0, 0}; const float zeroQuat[] = {0, 0, 0, 0};
mavlink_msg_attitude_quaternion_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, mavlink_msg_attitude_quaternion_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, offset); // convert to frd time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd
sendMessage(&msg); sendMessage(&msg);
mavlink_msg_rc_channels_raw_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0, mavlink_msg_rc_channels_raw_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,

View File

@@ -24,7 +24,6 @@ void setupMotors() {
// configure pins // configure pins
for (int i = 0; i < 4; i++) { for (int i = 0; i < 4; i++) {
ledcAttach(motorPins[i], pwmFrequency, pwmResolution); ledcAttach(motorPins[i], pwmFrequency, pwmResolution);
pwmFrequency = ledcChangeFrequency(motorPins[i], pwmFrequency, pwmResolution); // when reconfiguring
} }
sendMotors(); sendMotors();
print("Motors initialized\n"); print("Motors initialized\n");

View File

@@ -6,22 +6,21 @@
#include <Preferences.h> #include <Preferences.h>
#include "util.h" #include "util.h"
extern int channelZero[16]; extern float channelZero[16];
extern int channelMax[16]; extern float channelMax[16];
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel; extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern int wifiMode, udpLocalPort, udpRemotePort; extern int wifiMode, udpLocalPort, udpRemotePort;
extern float rcLossTimeout, descendTime; extern float rcLossTimeout, descendTime;
Preferences storage; Preferences storage;
struct Parameter { struct Parameter {
const char *name; // max length is 15 const char *name; // max length is 15 (Preferences key limit)
bool integer; bool integer;
union { float *f; int *i; }; // pointer to the variable union { float *f; int *i; }; // pointer to variable
float cache; // what's stored in flash float cache; // what's stored in flash
void (*callback)(); // called after parameter change Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {};
Parameter(const char *name, float *variable, void (*callback)() = nullptr) : name(name), integer(false), f(variable), callback(callback) {}; Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {};
Parameter(const char *name, int *variable, void (*callback)() = nullptr) : name(name), integer(true), i(variable), callback(callback) {};
float getValue() const { return integer ? *i : *f; }; float getValue() const { return integer ? *i : *f; };
void setValue(const float value) { if (integer) *i = value; else *f = value; }; void setValue(const float value) { if (integer) *i = value; else *f = value; };
}; };
@@ -68,12 +67,12 @@ Parameter parameters[] = {
{"EST_ACC_WEIGHT", &accWeight}, {"EST_ACC_WEIGHT", &accWeight},
{"EST_RATES_LPF_A", &ratesFilter.alpha}, {"EST_RATES_LPF_A", &ratesFilter.alpha},
// motors // motors
{"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT], setupMotors}, {"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT]},
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT], setupMotors}, {"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT]},
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT], setupMotors}, {"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT]},
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT], setupMotors}, {"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT]},
{"MOT_PWM_FREQ", &pwmFrequency, setupMotors}, {"MOT_PWM_FREQ", &pwmFrequency},
{"MOT_PWM_RES", &pwmResolution, setupMotors}, {"MOT_PWM_RES", &pwmResolution},
{"MOT_PWM_STOP", &pwmStop}, {"MOT_PWM_STOP", &pwmStop},
{"MOT_PWM_MIN", &pwmMin}, {"MOT_PWM_MIN", &pwmMin},
{"MOT_PWM_MAX", &pwmMax}, {"MOT_PWM_MAX", &pwmMax},
@@ -113,8 +112,7 @@ Parameter parameters[] = {
}; };
void setupParameters() { void setupParameters() {
print("Setup parameters\n"); storage.begin("flix", false);
storage.begin("flix");
// Read parameters from storage // Read parameters from storage
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
if (!storage.isKey(parameter.name)) { if (!storage.isKey(parameter.name)) {
@@ -153,7 +151,6 @@ bool setParameter(const char *name, const float value) {
if (strcasecmp(parameter.name, name) == 0) { if (strcasecmp(parameter.name, name) == 0) {
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
parameter.setValue(value); parameter.setValue(value);
if (parameter.callback) parameter.callback();
return true; return true;
} }
} }
@@ -167,7 +164,8 @@ void syncParameters() {
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
if (parameter.getValue() == parameter.cache) continue; // no change if (parameter.getValue() == parameter.cache) continue; // no change
if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NAN if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NaN
if (isinf(parameter.getValue()) && isinf(parameter.cache)) continue; // both are Inf
storage.putFloat(parameter.name, parameter.getValue()); storage.putFloat(parameter.name, parameter.getValue());
parameter.cache = parameter.getValue(); // update cache parameter.cache = parameter.getValue(); // update cache

View File

@@ -9,14 +9,15 @@
SBUS rc(Serial2); SBUS rc(Serial2);
uint16_t channels[16]; // raw rc channels uint16_t channels[16]; // raw rc channels
int channelZero[16]; // calibration zero values float channelZero[16]; // calibration zero values
int channelMax[16]; // calibration max values float channelMax[16]; // calibration max values
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1] float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN; float controlMode = NAN;
float controlTime = NAN; // time of the last controls update float controlTime = NAN; // time of the last controls update
int rollChannel = -1, pitchChannel = -1, throttleChannel = -1, yawChannel = -1, modeChannel = -1; // channel mapping // Channels mapping (nan means not assigned):
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
void setupRC() { void setupRC() {
print("Setup RC\n"); print("Setup RC\n");
@@ -40,11 +41,11 @@ void normalizeRC() {
controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1); controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1);
} }
// Update control values // Update control values
controlRoll = rollChannel < 0 ? 0 : controls[rollChannel]; controlRoll = rollChannel >= 0 ? controls[(int)rollChannel] : 0;
controlPitch = pitchChannel < 0 ? 0 : controls[pitchChannel]; controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : 0;
controlYaw = yawChannel < 0 ? 0 : controls[yawChannel]; controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : 0;
controlThrottle = throttleChannel < 0 ? 0 : controls[throttleChannel]; controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : 0;
controlMode = modeChannel < 0 ? NAN : controls[modeChannel]; // mode control is ineffective if not mapped controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN; // mode switch should not have affect if not set
} }
void calibrateRC() { void calibrateRC() {
@@ -63,7 +64,7 @@ void calibrateRC() {
printRCCalibration(); printRCCalibration();
} }
void calibrateRCChannel(int *channel, uint16_t in[16], uint16_t out[16], const char *str) { void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const char *str) {
print("%s", str); print("%s", str);
pause(3); pause(3);
for (int i = 0; i < 30; i++) readRC(); // try update 30 times max for (int i = 0; i < 30; i++) readRC(); // try update 30 times max
@@ -84,15 +85,15 @@ void calibrateRCChannel(int *channel, uint16_t in[16], uint16_t out[16], const c
channelZero[ch] = in[ch]; channelZero[ch] = in[ch];
channelMax[ch] = out[ch]; channelMax[ch] = out[ch];
} else { } else {
*channel = -1; *channel = NAN;
} }
} }
void printRCCalibration() { void printRCCalibration() {
print("Control Ch Zero Max\n"); print("Control Ch Zero Max\n");
print("Roll %-7d%-7d%-7d\n", rollChannel, rollChannel < 0 ? 0 : channelZero[rollChannel], rollChannel < 0 ? 0 : channelMax[rollChannel]); print("Roll %-7g%-7g%-7g\n", rollChannel, rollChannel >= 0 ? channelZero[(int)rollChannel] : NAN, rollChannel >= 0 ? channelMax[(int)rollChannel] : NAN);
print("Pitch %-7d%-7d%-7d\n", pitchChannel, pitchChannel < 0 ? 0 : channelZero[pitchChannel], pitchChannel < 0 ? 0 : channelMax[pitchChannel]); print("Pitch %-7g%-7g%-7g\n", pitchChannel, pitchChannel >= 0 ? channelZero[(int)pitchChannel] : NAN, pitchChannel >= 0 ? channelMax[(int)pitchChannel] : NAN);
print("Yaw %-7d%-7d%-7d\n", yawChannel, yawChannel < 0 ? 0 : channelZero[yawChannel], yawChannel < 0 ? 0 : channelMax[yawChannel]); print("Yaw %-7g%-7g%-7g\n", yawChannel, yawChannel >= 0 ? channelZero[(int)yawChannel] : NAN, yawChannel >= 0 ? channelMax[(int)yawChannel] : NAN);
print("Throttle %-7d%-7d%-7d\n", throttleChannel, throttleChannel < 0 ? 0 : channelZero[throttleChannel], throttleChannel < 0 ? 0 : channelMax[throttleChannel]); print("Throttle %-7g%-7g%-7g\n", throttleChannel, throttleChannel >= 0 ? channelZero[(int)throttleChannel] : NAN, throttleChannel >= 0 ? channelMax[(int)throttleChannel] : NAN);
print("Mode %-7d%-7d%-7d\n", modeChannel, modeChannel < 0 ? 0 : channelZero[modeChannel], modeChannel < 0 ? 0 : channelMax[modeChannel]); print("Mode %-7g%-7g%-7g\n", modeChannel, modeChannel >= 0 ? channelZero[(int)modeChannel] : NAN, modeChannel >= 0 ? channelMax[(int)modeChannel] : NAN);
} }

View File

@@ -165,7 +165,6 @@ void delay(uint32_t ms) {
bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { return true; } bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { return true; }
bool ledcWrite(uint8_t pin, uint32_t duty) { return true; } bool ledcWrite(uint8_t pin, uint32_t duty) { return true; }
uint32_t ledcChangeFrequency(uint8_t pin, uint32_t freq, uint8_t resolution) { return freq; }
unsigned long __micros; unsigned long __micros;
unsigned long __resetTime = 0; unsigned long __resetTime = 0;

View File

@@ -43,7 +43,7 @@ void doCommand(String str, bool echo);
void handleInput(); void handleInput();
void normalizeRC(); void normalizeRC();
void calibrateRC(); void calibrateRC();
void calibrateRCChannel(int *channel, uint16_t zero[16], uint16_t max[16], const char *str); void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str);
void printRCCalibration(); void printRCCalibration();
void printLogHeader(); void printLogHeader();
void printLogData(); void printLogData();
@@ -71,6 +71,7 @@ void resetParameters();
void setLED(bool on) {}; void setLED(bool on) {};
void calibrateGyro() { print("Skip gyro calibrating\n"); }; void calibrateGyro() { print("Skip gyro calibrating\n"); };
void calibrateAccel() { print("Skip accel calibrating\n"); }; void calibrateAccel() { print("Skip accel calibrating\n"); };
void calibrateLevel() { print("Skip level calibrating\n"); };
void printIMUCalibration() { print("cal: N/A\n"); }; void printIMUCalibration() { print("cal: N/A\n"); };
void printIMUInfo() {}; void printIMUInfo() {};
void printWiFiInfo() {}; void printWiFiInfo() {};

View File

@@ -138,7 +138,7 @@ class Flix:
while True: while True:
try: try:
msg: Optional[mavlink.MAVLink_message] = self.connection.recv_match(blocking=True) msg: Optional[mavlink.MAVLink_message] = self.connection.recv_match(blocking=True)
if msg is None or msg.get_srcSystem() != self.system_id: if msg is None:
continue continue
self._connected() self._connected()
msg_dict = msg.to_dict() msg_dict = msg.to_dict()