7 Commits

Author SHA1 Message Date
Oleg Kalachev
2a8faf5759 Fix logo svg slightly 2026-01-08 19:45:08 +03:00
Oleg Kalachev
f4e58a652a Add project logo 2026-01-08 17:58:59 +03:00
Oleg Kalachev
6c46328da1 Minor doc fixes 2026-01-04 15:01:53 +03:00
Oleg Kalachev
c8e5e08b03 Move all global variable declarations to the appropriate subsystems
As it makes the subsystems code easier to understand.
Declare the most used variables in main sketch file as forward declarations.
Make all control input zero by default (except controlMode).
Minor changes.
2026-01-03 13:28:18 +03:00
Oleg Kalachev
a5e3dfcf69 Some updates to the docs 2026-01-03 12:18:47 +03:00
Oleg Kalachev
d6e8be0c05 Add parameters for easier IMU orientation definition 2025-12-26 21:14:15 +03:00
Oleg Kalachev
68d16855df Add motors rotation diagram to usage article 2025-12-25 07:22:09 +03:00
29 changed files with 144 additions and 76 deletions

View File

@@ -65,5 +65,6 @@
"PX4"
]
},
"MD045": false
"MD045": false,
"MD060": false
}

View File

@@ -1,6 +1,9 @@
# Flix
<!-- markdownlint-disable MD041 -->
**Flix** (*flight + X*) — open source ESP32-based quadcopter made from scratch.
<p align="center">
<img src="docs/img/flix.svg" width=180 alt="Flix logo"><br>
<b>Flix</b> (<i>flight + X</i>) — open source ESP32-based quadcopter made from scratch.
</p>
<table>
<tr>

View File

@@ -35,7 +35,7 @@
### Подсистема управления
Состояние органов управления обрабатывается в функции `interpretControls()` и преобразуется в *команду управления*, которая включает следующее:
Состояние органов управления обрабатывается в функции `interpretControls()` и преобразуется в **команду управления**, которая включает следующее:
* `attitudeTarget` *(Quaternion)* — целевая ориентация дрона.
* `ratesTarget` *(Vector)* — целевые угловые скорости, *рад/с*.

View File

@@ -38,13 +38,13 @@ Utility files:
### Control subsystem
Pilot inputs are interpreted in `interpretControls()`, and then converted to the *control command*, which consists of the following:
Pilot inputs are interpreted in `interpretControls()`, and then converted to the **control command**, which consists of the following:
* `attitudeTarget` *(Quaternion)* — target attitude of the drone.
* `ratesTarget` *(Vector)* — target angular rates, *rad/s*.
* `ratesExtra` *(Vector)* — additional (feed-forward) angular rates , used for yaw rate control in STAB mode, *rad/s*.
* `torqueTarget` *(Vector)* — target torque, range [-1, 1].
* `thrustTarget` *(float)* — collective thrust target, range [0, 1].
* `thrustTarget` *(float)* — collective motor thrust target, range [0, 1].
Control command is handled in `controlAttitude()`, `controlRates()`, `controlTorque()` functions. Each function may be skipped if the corresponding control target is set to `NAN`.
@@ -62,6 +62,11 @@ print("Test value: %.2f\n", testValue);
In order to add a console command, modify the `doCommand()` function in `cli.ino` file.
> [!IMPORTANT]
> Avoid using delays in in-flight commands, it will **crash** the drone! (The design is one-threaded.)
>
> For on-the-ground commands, use `pause()` function, instead of `delay()`. This function allows to pause in a way that MAVLink connection will continue working.
## Building the firmware
See build instructions in [usage.md](usage.md).

38
docs/img/flix.svg Normal file
View File

@@ -0,0 +1,38 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 734.86 378.46">
<defs>
<style>
.a {
fill: none;
stroke: #d5d5d5;
stroke-miterlimit: 10;
stroke-width: 31px;
}
.b {
fill: #c1c1c1;
}
.c {
fill: #ff9400;
}
.d {
fill: #d5d5d5;
}
</style>
</defs>
<g>
<g>
<line class="a" x1="448.78" y1="294.23" x2="648.77" y2="93.24"/>
<line class="a" x1="449.78" y1="94.24" x2="649.77" y2="295.23"/>
<circle class="b" cx="549.27" cy="193.73" r="41.5"/>
<circle class="c" cx="449.35" cy="93.74" r="77.95"/>
<circle class="c" cx="648.89" cy="93.53" r="77.95"/>
<circle class="c" cx="647.89" cy="294.51" r="77.95"/>
<circle class="c" cx="448.9" cy="294.51" r="77.95"/>
</g>
<path class="d" d="M8,161.93q0-17.85,22.36-17.85h4.81V100.57Q35.17,8.49,131.23,8h1q36.87,0,47.31,7.48L181,17.41l1,2.41V50q0,12.32-5.82,12.31-2.43,0-7.4-4.64t-14.19-9a48.63,48.63,0,0,0-21.22-4.41q-12,0-19.17,3.5a18.85,18.85,0,0,0-9.82,10.62,67.35,67.35,0,0,0-3.52,12.06,82.52,82.52,0,0,0-.85,13.39v60.32h27.28q10.86,0,16.05,5.43a17.52,17.52,0,0,1,5.19,12.42,22.5,22.5,0,0,1-1.21,7.36q-1.22,3.51-6.64,7.24t-14.36,3.74H101.64V344.82a56,56,0,0,1-.61,9.65,37.8,37.8,0,0,1-2.56,7.6,11.83,11.83,0,0,1-6.94,6.4q-5,1.93-13.51,1.93H57.08q-10.47,0-15.7-4.71t-5.73-8.44a77.31,77.31,0,0,1-.48-9.53V180.27H29.4Q8,180.27,8,161.93Z"/>
<path class="d" d="M201.21,348.2V37q0-23.16,20.86-23.4h22.81q22.8,0,22.8,22.44V346.27a68.92,68.92,0,0,1-.49,9.41,22.59,22.59,0,0,1-2.42,7.12,11.48,11.48,0,0,1-6.67,5.43,47.78,47.78,0,0,1-12.74,2.17H225q-11.4,0-17.58-4.47T201.21,348.2Z"/>
<path class="d" d="M284.9,61.08V36.47a40.39,40.39,0,0,1,1.7-12.91,11.36,11.36,0,0,1,6.18-7,25.27,25.27,0,0,1,6.68-2.3c1.45-.15,4-.4,7.76-.72h25.23q10.43,0,16.73,4.7t6.31,18.22V62.05a27.94,27.94,0,0,1-.85,7.11,23,23,0,0,1-2.06,5.43,20,20,0,0,1-2.91,4,10,10,0,0,1-3.52,2.54c-1.21.48-2.54,1-4,1.44a11.53,11.53,0,0,1-3.4.73,13.71,13.71,0,0,0-3.15.48H307.7q-10.43,0-16.61-4.7T284.9,61.08Zm1.94,284.71V166.28q0-22.2,21.83-22.2h20.38q10.92,0,16.62,4t6.67,8.45a60.47,60.47,0,0,1,1,12.18V348.2q0,22.2-21.83,22.2H308.67q-10.43,0-15.64-4.95t-5.7-8.81A90.93,90.93,0,0,1,286.84,345.79Z"/>
</g>
</svg>

After

Width:  |  Height:  |  Size: 2.2 KiB

BIN
docs/img/imu-axes.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 23 KiB

BIN
docs/img/imu-rot-1.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 18 KiB

BIN
docs/img/imu-rot-2.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 18 KiB

BIN
docs/img/imu-rot-3.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

BIN
docs/img/imu-rot-4.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

BIN
docs/img/imu-rot-5.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 10 KiB

BIN
docs/img/imu-rot-6.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 9.6 KiB

BIN
docs/img/imu-rot-7.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 10 KiB

BIN
docs/img/imu-rot-8.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 10 KiB

View File

@@ -4,7 +4,7 @@
Do the following:
* **Check ESP32 core is installed**. Check if the version matches the one used in the [tutorial](usage.md#firmware).
* **Check ESP32 core is installed**. Check if the version matches the one used in the [tutorial](usage.md#building-the-firmware).
* **Check libraries**. Install all the required libraries from the tutorial. Make sure there are no MPU9250 or other peripherals libraries that may conflict with the ones used in the tutorial.
* **Check the chosen board**. The correct board to choose in Arduino IDE for ESP32 Mini is *WEMOS D1 MINI ESP32*.
@@ -25,7 +25,7 @@ Do the following:
* The `accel` and `gyro` fields should change as you move the drone.
* **Calibrate the accelerometer.** if is wasn't done before. Type `ca` command in Serial Monitor and follow the instructions.
* **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.
* **Check the IMU orientation is set correctly**. If the attitude estimation is rotated, make sure `rotateIMU` function is defined correctly in `imu.ino` file.
* **Check the IMU orientation is set correctly**. If the attitude estimation is rotated, set the correct IMU orientation as described in the [tutorial](usage.md#define-imu-orientation).
* **Check the motors type**. Motors with exact 3.7V voltage are needed, not ranged working voltage (3.7V — 6V).
* **Check the motors**. Perform the following commands using Serial Monitor:
* `mfr` — should rotate front right motor (counter-clockwise).

View File

@@ -73,14 +73,6 @@ ICM20948 imu(SPI); // For ICM-20948
MPU6050 imu(Wire); // For MPU-6050
```
### Setup the IMU orientation
The IMU orientation is defined in `rotateIMU` function in the `imu.ino` file. Change it so it converts the IMU axes to the drone's axes correctly. **Drone axes are X forward, Y left, Z up**:
<img src="img/drone-axes.svg" width="200">
See various [IMU boards axes orientations table](https://github.com/okalachev/flixperiph/?tab=readme-ov-file#imu-axes-orientation) to help you set up the correct orientation.
### Connect using QGroundControl
QGroundControl is a ground control station software that can be used to monitor and control the drone.
@@ -88,7 +80,7 @@ QGroundControl is a ground control station software that can be used to monitor
1. Install mobile or desktop version of [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html).
2. Power up the drone.
3. Connect your computer or smartphone to the appeared `flix` Wi-Fi network (password: `flixwifi`).
4. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically
4. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
### Access console
@@ -104,11 +96,37 @@ To access the console using QGroundControl:
1. Connect to the drone using QGroundControl app.
2. Go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*.
<img src="img/cli.png" width="400">
<img src="img/cli.png" width="400">
> [!TIP]
> Use `help` command to see the list of available commands.
### Access parameters
The drone is configured using parameters. To access and modify them, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*:
<img src="img/parameters.png" width="400">
You can also work with parameters using `p` command in the console.
### Define IMU orientation
Use parameters, to define the IMU board axes orientation relative to the drone's axes: `IMU_ROT_ROLL`, `IMU_ROT_PITCH`, and `IMU_ROT_YAW`.
The drone has *X* axis pointing forward, *Y* axis pointing left, and *Z* axis pointing up, and the supported IMU boards have *X* axis pointing to the pins side and *Z* axis pointing up from the component side:
<img src="img/imu-axes.png" width="200">
Use the following table to set the parameters for common IMU orientations:
|Orientation|Parameters|Orientation|Parameters|
|:-:|-|-|-|
|<img src="img/imu-rot-1.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0 |<img src="img/imu-rot-5.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0|
|<img src="img/imu-rot-2.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|<img src="img/imu-rot-6.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|
|<img src="img/imu-rot-3.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|<img src="img/imu-rot-7.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|
|<img src="img/imu-rot-4.png" width="180"><br>☑️ **Default**|<br>`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|<img src="img/imu-rot-8.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|
### Calibrate accelerometer
Before flight you need to calibrate the accelerometer:
@@ -136,6 +154,10 @@ Before flight you need to calibrate the accelerometer:
* `mrl` — should rotate rear left motor (counter-clockwise).
* `mrr` — should rotate rear right motor (clockwise).
Rotation diagram:
<img src="img/motors.svg" width=200>
> [!WARNING]
> Never run the motors when powering the drone from USB, always use the battery for that.
@@ -143,7 +165,7 @@ Before flight you need to calibrate the accelerometer:
There are several ways to control the drone's flight: using **smartphone** (Wi-Fi), using **SBUS remote control**, or using **USB remote control** (Wi-Fi).
### Control with smartphone
### Control with a smartphone
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone.
2. Power the drone using the battery.
@@ -155,7 +177,7 @@ There are several ways to control the drone's flight: using **smartphone** (Wi-F
> [!TIP]
> Decrease `CTL_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
### Control with remote control
### Control with a remote control
Before using remote SBUS-connected remote control, you need to calibrate it:
@@ -163,7 +185,7 @@ Before using remote SBUS-connected remote control, you need to calibrate it:
2. Type `cr` command and follow the instructions.
3. Use the remote control to fly the drone!
### Control with USB remote control
### Control with a USB remote control
If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it.
@@ -221,12 +243,6 @@ In this mode, the pilot inputs are ignored (except the mode switch, if configure
If the pilot moves the control sticks, the drone will switch back to *STAB* mode.
## Adjusting parameters
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*.
<img src="img/parameters.png" width="400">
## Flight log
After the flight, you can download the flight log for analysis wirelessly. Use the following for that:

View File

@@ -16,7 +16,7 @@ Author: [goldarte](https://t.me/goldarte).<br>
## School 548 course
Special quadcopter design and engineering course took place in october-november 2025 in School 548, Moscow. Course included UAV control theory, electronics, and practical drone assembly and setup using the Flix project.
Special course on quadcopter design and engineering took place in october-november 2025 in School 548, Moscow. The course included UAV control theory, electronics, drone assembly and setup practice, using the Flix project.
<img height=200 src="img/user/school548/1.jpg"> <img height=200 src="img/user/school548/2.jpg"> <img height=200 src="img/user/school548/3.jpg">
@@ -25,7 +25,7 @@ STL files and other materials: see [here](https://drive.google.com/drive/folders
### Selected works
Author: [KiraFlux](https://t.me/@kiraflux_0XC0000005).<br>
Description: **custom ESPNOW remote control** is implemented, firmware modified to support ESPNOW protocol.<br>
Description: **custom ESPNOW remote control** was implemented, modified firmware to support ESPNOW protocol.<br>
Telegram posts: [1](https://t.me/opensourcequadcopter/106), [2](https://t.me/opensourcequadcopter/114).<br>
Modified Flix firmware: https://github.com/KiraFlux/flix/tree/klyax.<br>
Remote control project: https://github.com/KiraFlux/ESP32-DJC.<br>

View File

@@ -11,7 +11,7 @@ extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRO
extern const int RAW, ACRO, STAB, AUTO;
extern float t, dt, loopRate;
extern uint16_t channels[16];
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
extern float controlTime;
extern int mode;
extern bool armed;
@@ -132,6 +132,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("time: %.1f\n", controlTime);
print("mode: %s\n", getModeName());
print("armed: %d\n", armed);
} else if (command == "wifi") {

View File

@@ -8,6 +8,10 @@
#include "lpf.h"
#include "util.h"
Vector rates; // estimated angular rates, rad/s
Quaternion attitude; // estimated attitude
bool landed;
float accWeight = 0.003;
LowPassFilter<Vector> ratesFilter(0.2); // cutoff frequency ~ 40 Hz

View File

@@ -9,16 +9,13 @@
#define WIFI_ENABLED 1
float 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 controlMode = NAN;
Vector gyro; // gyroscope data
Vector acc; // accelerometer data, m/s/s
Vector rates; // filtered angular rates, rad/s
Quaternion attitude; // estimated attitude
bool landed; // are we landed and stationary
float motors[4]; // normalized motors thrust in range [0..1]
extern float t, dt;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
extern Vector gyro, acc;
extern Vector rates;
extern Quaternion attitude;
extern bool landed;
extern float motors[4];
void setup() {
Serial.begin(115200);

View File

@@ -10,10 +10,14 @@
#include "util.h"
MPU9250 imu(SPI);
Vector imuRotation(0, 0, -PI / 2); // imu orientation as Euler angles
Vector gyro; // gyroscope output, rad/s
Vector gyroBias;
Vector acc; // accelerometer output, m/s/s
Vector accBias;
Vector accScale(1, 1, 1);
Vector gyroBias;
void setupIMU() {
print("Setup IMU\n");
@@ -37,16 +41,10 @@ void readIMU() {
// apply scale and bias
acc = (acc - accBias) / accScale;
gyro = gyro - gyroBias;
// rotate
rotateIMU(acc);
rotateIMU(gyro);
}
void rotateIMU(Vector& data) {
// Rotate from LFD to FLU
// NOTE: In case of using other IMU orientation, change this line:
data = Vector(data.y, data.x, -data.z);
// Axes orientation for various boards: https://github.com/okalachev/flixperiph#imu-axes-orientation
// rotate to body frame
Quaternion rotation = Quaternion::fromEuler(imuRotation);
acc = Quaternion::rotateVector(acc, rotation.inversed());
gyro = Quaternion::rotateVector(gyro, rotation.inversed());
}
void calibrateGyroOnce() {

View File

@@ -12,12 +12,11 @@
#define MAVLINK_RATE_SLOW 1
#define MAVLINK_RATE_FAST 10
extern float controlTime;
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
extern float controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
void processMavlink() {
sendMavlink();
receiveMavlink();

View File

@@ -17,7 +17,8 @@
#define PWM_MIN 0
#define PWM_MAX 1000000 / PWM_FREQUENCY
// Motors array indexes:
float motors[4]; // normalized motor thrusts in range [0..1]
const int MOTOR_REAR_LEFT = 0;
const int MOTOR_REAR_RIGHT = 1;
const int MOTOR_FRONT_RIGHT = 2;

View File

@@ -43,6 +43,9 @@ Parameter parameters[] = {
{"CTL_Y_RATE_MAX", &maxRate.z},
{"CTL_TILT_MAX", &tiltMax},
// imu
{"IMU_ROT_ROLL", &imuRotation.x},
{"IMU_ROT_PITCH", &imuRotation.y},
{"IMU_ROT_YAW", &imuRotation.z},
{"IMU_ACC_BIAS_X", &accBias.x},
{"IMU_ACC_BIAS_Y", &accBias.y},
{"IMU_ACC_BIAS_Z", &accBias.z},

View File

@@ -6,13 +6,16 @@
#include <SBUS.h>
#include "util.h"
SBUS rc(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
SBUS rc(Serial2);
uint16_t channels[16]; // raw rc channels
float controlTime; // time of the last controls update
float channelZero[16]; // calibration zero values
float channelMax[16]; // calibration max values
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN; //
float controlTime; // time of the last controls update (0 when no RC)
// Channels mapping (using float to store in parameters):
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
@@ -38,11 +41,11 @@ void normalizeRC() {
controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1);
}
// Update control values
controlRoll = rollChannel >= 0 ? controls[(int)rollChannel] : NAN;
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN;
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN;
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN;
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN;
controlRoll = rollChannel >= 0 ? controls[(int)rollChannel] : 0;
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : 0;
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : 0;
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : 0;
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN; // mode switch should not have affect if not set
}
void calibrateRC() {

View File

@@ -3,6 +3,8 @@
// Time related functions
float t = NAN; // current time, s
float dt; // time delta with the previous step, s
float loopRate; // Hz
void step() {

View File

@@ -35,7 +35,6 @@ public:
z = NAN;
}
float norm() const {
return sqrt(x * x + y * y + z * z);
}

View File

@@ -12,16 +12,15 @@
#define WIFI_ENABLED 1
float t = NAN;
float dt;
float motors[4];
float controlRoll, controlPitch, controlYaw, controlThrottle = NAN;
float controlMode = NAN;
Vector acc;
Vector gyro;
Vector rates;
Quaternion attitude;
bool landed;
extern float t, dt;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
extern Vector rates;
extern Quaternion attitude;
extern bool landed;
extern float motors[4];
Vector gyro, acc, imuRotation;
Vector accBias, gyroBias, accScale(1, 1, 1);
// declarations
void step();
@@ -74,4 +73,3 @@ void calibrateAccel() { print("Skip accel calibrating\n"); };
void printIMUCalibration() { print("cal: N/A\n"); };
void printIMUInfo() {};
void printWiFiInfo() {};
Vector accBias, gyroBias, accScale(1, 1, 1);

View File

@@ -95,7 +95,7 @@ Full list of events:
|`armed`|Armed state update|Armed state (*bool*)|
|`mode`|Flight mode update|Flight mode (*str*)|
|`landed`|Landed state update|Landed state (*bool*)|
|`print`|The drone sends text to the console|Text|
|`print`|The drone prints text to the console|Text|
|`attitude`|Attitude update|Attitude quaternion (*list*)|
|`attitude_euler`|Attitude update|Euler angles (*list*)|
|`rates`|Angular rates update|Angular rates (*list*)|
@@ -112,7 +112,7 @@ Full list of events:
> [!NOTE]
> Update events trigger on every new piece of data from the drone, and do not mean the value has changed.
### Common methods
### Basic methods
Get and set firmware parameters using `get_param` and `set_param` methods: