16 Commits

Author SHA1 Message Date
Oleg Kalachev
9fd35ba361 Simplify lpf filter code
Begin with zero instead of the initializing value, as the latter doesn't make much sense in practice, but complicates the code much.
2026-01-24 09:43:46 +03:00
Oleg Kalachev
ca50f75576 Various minor fixes 2026-01-24 09:34:16 +03:00
Oleg Kalachev
e47a31f981 Fix mavlink parameter set acknowledgement value
If the parameter is integer the acknowledgement should contain the rounded value.
2026-01-24 09:32:49 +03:00
Oleg Kalachev
7ad3022798 Add parameter for configuring gyro bias lpf
+ reset the filter on `reset` command
2026-01-24 09:31:32 +03:00
Oleg Kalachev
5b654e4d8e Update ESP32-Core to 3.3.6 2026-01-23 02:41:43 +03:00
Oleg Kalachev
cf10ec6161 Update MAVLink-Arduino to 2.0.16 2026-01-23 01:11:35 +03:00
Oleg Kalachev
6d01cd2e79 Make failsafe configurable using parameters
SF_RC_LOSS_TIME - time without rc to activate failsafe.
SD_DESCEND_TIME - total time to decrease the throttle to zero.
Make controlTime nan on the start to simplify the logic.
2026-01-22 23:57:52 +03:00
Oleg Kalachev
0abb18c616 Make parameter names case-insensitive
+ minor fix
2026-01-22 23:11:47 +03:00
Oleg Kalachev
30326a5662 Add parameters for configuring the mavlink subsystem
MAV_SYS_ID - mavlink system id.
MAV_RATE_SLOW - rate of slow telemetry (e. g. heartbeats).
MAV_RATE_FAST - rate of fast telemetry (e. g. attitude, imu data).
2026-01-22 23:04:45 +03:00
Oleg Kalachev
dd3575174b Add wifi configuration using parameters and cli
Add console commands to setup wifi.
Add a parameter for choosing between STA and AP mode.
Add parameters for udp ports.
Remove WIFI_ENABLED macro.
2026-01-22 22:58:43 +03:00
Oleg Kalachev
c0f3301da4 Support integer parameters in addition to floats
The variable pointer is stored as a union field.
If `.integer` field is true, then integer pointer should be used.
Interfaces to parameters (cli and mavlink) keep working using floats.
Setting a non-finite value to int parameter will cause an error.
`.value` field is renamed to `.cache`.
2026-01-22 22:54:05 +03:00
a.golubtsov
a6bad3a69b Add log dir creation before log writing 2026-01-22 17:56:23 +03:00
Oleg Kalachev
9a9bd07251 Add correct attitude estimation video to the usage article 2026-01-15 23:46:23 +03:00
Oleg Kalachev
28f5855a57 Re-arrange control.ino declarations to make a bit more sensible
So the control command is above the PID controllers.
2026-01-13 17:43:53 +03:00
Oleg Kalachev
7e24ee30f7 Documentation and book updates
Improve the main list of features.
Use lowercase imu variable for consistency with the firmware code.
Minor fixes.
2026-01-13 17:26:40 +03:00
Oleg Kalachev
2a8faf5759 Fix logo svg slightly 2026-01-08 19:45:08 +03:00
23 changed files with 257 additions and 199 deletions

View File

@@ -25,8 +25,6 @@ jobs:
path: flix/build
- name: Build firmware for ESP32-S3
run: make BOARD=esp32:esp32:esp32s3
- name: Build firmware with WiFi disabled
run: sed -i 's/^#define WIFI_ENABLED 1$/#define WIFI_ENABLED 0/' flix/flix.ino && make
- name: Check c_cpp_properties.json
run: tools/check_c_cpp_properties.py

View File

@@ -7,6 +7,7 @@
"MD024": false,
"MD033": false,
"MD034": false,
"MD040": false,
"MD059": false,
"MD044": {
"html_elements": false,

View File

@@ -6,19 +6,18 @@
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"${workspaceFolder}/tools/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32",
"~/.arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**",
"~/Arduino/libraries/**",
"/usr/include/gazebo-11/",
"/usr/include/ignition/math6/"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32/Arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",
@@ -31,9 +30,10 @@
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
"${workspaceFolder}/flix/parameters.ino",
"${workspaceFolder}/flix/safety.ino"
],
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2511/bin/xtensa-esp32-elf-g++",
"cStandard": "c11",
"cppStandard": "c++17",
"defines": [
@@ -53,19 +53,18 @@
"name": "Mac",
"includePath": [
"${workspaceFolder}/flix",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/include/**",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32",
"~/Library/Arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**",
"~/Documents/Arduino/libraries/**",
"/opt/homebrew/include/gazebo-11/",
"/opt/homebrew/include/ignition/math6/"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32/Arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/flix.ino",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
@@ -78,9 +77,10 @@
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
"${workspaceFolder}/flix/parameters.ino",
"${workspaceFolder}/flix/safety.ino"
],
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2511/bin/xtensa-esp32-elf-g++",
"cStandard": "c11",
"cppStandard": "c++17",
"defines": [
@@ -103,17 +103,16 @@
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"${workspaceFolder}/tools/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**",
"~/Documents/Arduino/libraries/**"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32/Arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",
@@ -126,9 +125,10 @@
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
"${workspaceFolder}/flix/parameters.ino",
"${workspaceFolder}/flix/safety.ino"
],
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++.exe",
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2511/bin/xtensa-esp32-elf-g++.exe",
"cStandard": "c11",
"cppStandard": "c++17",
"defines": [

View File

@@ -13,10 +13,10 @@ monitor:
dependencies .dependencies:
arduino-cli core update-index --config-file arduino-cli.yaml
arduino-cli core install esp32:esp32@3.2.0 --config-file arduino-cli.yaml
arduino-cli core install esp32:esp32@3.3.6 --config-file arduino-cli.yaml
arduino-cli lib update-index
arduino-cli lib install "FlixPeriph"
arduino-cli lib install "MAVLink"@2.0.16
arduino-cli lib install "MAVLink"@2.0.25
touch .dependencies
gazebo/build cmake: gazebo/CMakeLists.txt

View File

@@ -21,15 +21,13 @@
* Dedicated for education and research.
* Made from general-purpose components.
* Simple and clean source code in Arduino (<2k lines firmware).
* Connectivity using Wi-Fi and MAVLink protocol.
* Control using USB gamepad, remote control or smartphone.
* Wi-Fi and MAVLink support.
* Wireless command line interface and analyzing.
* Precise simulation with Gazebo.
* Python library.
* Python library for scripting and automatic flights.
* Textbook on flight control theory and practice ([in development](https://quadcopter.dev)).
* *Position control (using external camera) and autonomous flights¹*.
*¹ — planned.*
* *Position control (planned)*.
## It actually flies

View File

@@ -87,13 +87,13 @@ Flix поддерживает следующие модели IMU:
#include <FlixPeriph.h>
#include <SPI.h>
MPU9250 IMU(SPI);
MPU9250 imu(SPI);
void setup() {
Serial.begin(115200);
bool success = IMU.begin();
bool success = imu.begin();
if (!success) {
Serial.println("Failed to initialize IMU");
Serial.println("Failed to initialize the IMU");
}
}
```
@@ -108,21 +108,21 @@ void setup() {
#include <FlixPeriph.h>
#include <SPI.h>
MPU9250 IMU(SPI);
MPU9250 imu(SPI);
void setup() {
Serial.begin(115200);
bool success = IMU.begin();
bool success = imu.begin();
if (!success) {
Serial.println("Failed to initialize IMU");
Serial.println("Failed to initialize the IMU");
}
}
void loop() {
IMU.waitForData();
imu.waitForData();
float gx, gy, gz;
IMU.getGyro(gx, gy, gz);
imu.getGyro(gx, gy, gz);
Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
delay(50); // замедление вывода
@@ -135,36 +135,36 @@ void loop() {
## Конфигурация гироскопа
В коде Flix настройка IMU происходит в функции `configureIMU`. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплов и частота LPF-фильтра.
В коде Flix настройка IMU происходит в функции `configureIMU`. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплирования и частота LPF-фильтра.
### Частота сэмплов
### Частота сэмплирования
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер.
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота, тем выше точность управления полетом, но и тем больше нагрузка на микроконтроллер.
Частота сэмплов устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
Частота сэмплирования устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
```cpp
IMU.setRate(IMU.RATE_1KHZ_APPROX);
```
Поскольку не все поддерживаемые IMU могут работать строго на частоте 1 кГц, в библиотеке FlixPeriph существует возможность приближенной настройки частоты сэмплов. Например, у IMU ICM-20948 при такой настройке реальная частота сэмплирования будет равна 1125 Гц.
Поскольку не все поддерживаемые IMU могут работать строго на частоте 1 кГц, в библиотеке FlixPeriph существует возможность приближенной настройки частоты сэмплирования. Например, у IMU ICM-20948 при такой настройке реальная частота сэмплирования будет равна 1125 Гц.
Другие доступные для установки в библиотеке FlixPeriph частоты сэмплирования:
* `RATE_MIN` — минимальная частота сэмплов для конкретного IMU.
* `RATE_MIN` — минимальная частота для конкретного IMU.
* `RATE_50HZ_APPROX` — значение, близкое к 50 Гц.
* `RATE_1KHZ_APPROX` — значение, близкое к 1 кГц.
* `RATE_8KHZ_APPROX` — значение, близкое к 8 кГц.
* `RATE_MAX` — максимальная частота сэмплов для конкретного IMU.
* `RATE_MAX` — максимальная частота для конкретного IMU.
#### Диапазон измерений
Большинство MEMS-гироскопов поддерживают несколько диапазонов измерений угловой скорости. Главное преимущество выбора меньшего диапазона — бо́льшая чувствительность. В полетных контроллерах обычно выбирается максимальный диапазон измерений от 2000 до 2000 градусов в секунду, чтобы обеспечить возможность динамичных маневров.
Большинство MEMS-гироскопов поддерживают несколько диапазонов измерений угловой скорости. Главное преимущество выбора меньшего диапазона — бо́льшая чувствительность. В полетных контроллерах обычно выбирается максимальный диапазон измерений от 2000 до 2000 градусов в секунду, чтобы обеспечить возможность быстрых маневров.
В библиотеке FlixPeriph диапазон измерений гироскопа устанавливается методом `setGyroRange()`:
```cpp
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
imu.setGyroRange(imu.GYRO_RANGE_2000DPS);
```
### LPF-фильтр
@@ -172,7 +172,7 @@ IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
IMU InvenSense могут фильтровать измерения на аппаратном уровне при помощи фильтра нижних частот (LPF). Flix реализует собственный фильтр для гироскопа, чтобы иметь больше гибкости при поддержке разных IMU. Поэтому для встроенного LPF устанавливается максимальная частота среза:
```cpp
IMU.setDLPF(IMU.DLPF_MAX);
imu.setDLPF(imu.DLPF_MAX);
```
## Калибровка гироскопа
@@ -181,7 +181,7 @@ IMU.setDLPF(IMU.DLPF_MAX);
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]
Для качественной работы подсистемы оценки ориентации и управления дроном необходимо оценить *bias* гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции `calibrateGyro()`. Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются *bias* гироскопа и в дальнейшем вычитаются из измерений.
Для точной работы подсистемы оценки ориентации и управления дроном необходимо оценить *bias* гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции `calibrateGyro()`. Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются *bias* гироскопа и в дальнейшем вычитаются из измерений.
Программа для вывода данных с гироскопа с калибровкой:
@@ -189,23 +189,23 @@ IMU.setDLPF(IMU.DLPF_MAX);
#include <FlixPeriph.h>
#include <SPI.h>
MPU9250 IMU(SPI);
MPU9250 imu(SPI);
float gyroBiasX, gyroBiasY, gyroBiasZ; // bias гироскопа
void setup() {
Serial.begin(115200);
bool success = IMU.begin();
bool success = imu.begin();
if (!success) {
Serial.println("Failed to initialize IMU");
Serial.println("Failed to initialize the IMU");
}
calibrateGyro();
}
void loop() {
float gx, gy, gz;
IMU.waitForData();
IMU.getGyro(gx, gy, gz);
imu.waitForData();
imu.getGyro(gx, gy, gz);
// Устранение bias гироскопа
gx -= gyroBiasX;
@@ -226,9 +226,9 @@ void calibrateGyro() {
// Получение 1000 измерений гироскопа
for (int i = 0; i < samples; i++) {
IMU.waitForData();
imu.waitForData();
float gx, gy, gz;
IMU.getGyro(gx, gy, gz);
imu.getGyro(gx, gy, gz);
gyroBiasX += gx;
gyroBiasY += gy;
gyroBiasZ += gz;

View File

@@ -42,7 +42,7 @@ Pilot inputs are interpreted in `interpretControls()`, and then converted to the
* `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*.
* `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 motor thrust target, range [0, 1].

View File

@@ -1,4 +1,4 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 718.86 362.46">
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 734.86 378.46">
<defs>
<style>
.a {
@@ -23,16 +23,16 @@
</defs>
<g>
<g>
<line class="a" x1="443.12" y1="283.88" x2="641.43" y2="84.58"/>
<line class="a" x1="444.12" y1="85.58" x2="642.42" y2="284.87"/>
<circle class="b" cx="542.77" cy="184.23" r="41.15"/>
<circle class="c" cx="443.69" cy="85.08" r="77.29"/>
<circle class="c" cx="641.55" cy="84.87" r="77.29"/>
<circle class="c" cx="640.56" cy="284.16" r="77.29"/>
<circle class="c" cx="443.25" cy="284.16" r="77.29"/>
<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="M0,153.93q0-17.85,22.36-17.85h4.81V92.57Q27.17.48,123.23,0h1q36.87,0,47.31,7.48L173,9.41l1,2.41V42q0,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.74H93.64V336.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.93H49.08q-10.47,0-15.7-4.71t-5.73-8.44a77.31,77.31,0,0,1-.48-9.53V172.27H21.4Q0,172.27,0,153.93Z"/>
<path class="d" d="M193.21,340.2V29q0-23.16,20.86-23.4h22.81q22.8,0,22.8,22.44V338.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.17H217q-11.4,0-17.58-4.47T193.21,340.2Z"/>
<path class="d" d="M276.9,54.08V29.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.22V55.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.48H299.7q-10.43,0-16.61-4.7T276.9,54.08Zm1.94,284.71V159.28q0-22.2,21.83-22.2h20.38q10.92,0,16.62,4t6.67,8.45a60.47,60.47,0,0,1,1,12.18V341.2q0,22.2-21.83,22.2H300.67q-10.43,0-15.64-4.95t-5.7-8.81A90.93,90.93,0,0,1,278.84,338.79Z"/>
<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>

Before

Width:  |  Height:  |  Size: 2.2 KiB

After

Width:  |  Height:  |  Size: 2.2 KiB

View File

@@ -16,7 +16,7 @@ Do the following:
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button to make sure you see the whole ESP32 output.
* **Check the baudrate is correct**. If you see garbage characters in the Serial Monitor, make sure the baudrate is set to 115200.
* **Make sure correct IMU model is chosen**. If using ICM-20948/MPU-6050 board, change `MPU9250` to `ICM20948`/`MPU6050` in the `imu.ino` file.
* **Check if the CLI is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the CLI using QGroundControl (*Vehicle Setup* ⇒ *Analyze Tools**MAVLink Console*).
* **Check if the console is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the console using QGroundControl (*Vehicle Setup* ⇒ *Analyze Tools**MAVLink Console*).
* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
* **If QGroundControl doesn't connect**, you might need to disable the firewall and/or VPN on your computer.
* **Check the IMU is working**. Perform `imu` command and check its output:

View File

@@ -20,10 +20,10 @@ You can build and upload the firmware using either **Arduino IDE** (easier for b
1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended).
2. *Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).*
3. Install ESP32 core, version 3.2.0. See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
3. Install ESP32 core, version 3.3.6. See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
* `FlixPeriph`, the latest version.
* `MAVLink`, version 2.0.16.
* `MAVLink`, version 2.0.25.
5. Open the `flix/flix.ino` sketch from downloaded firmware sources in Arduino IDE.
6. Connect your ESP32 board to the computer and choose correct board type in Arduino IDE (*WEMOS D1 MINI ESP32* for ESP32 Mini) and the port.
7. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
@@ -108,7 +108,7 @@ The drone is configured using parameters. To access and modify them, go to the Q
<img src="img/parameters.png" width="400">
You can also work with parameters using `p` command in the console.
You can also work with parameters using `p` command in the console. Parameter names are case-insensitive.
### Define IMU orientation
@@ -143,9 +143,9 @@ Before flight you need to calibrate the accelerometer:
* The `accel` and `gyro` fields should change as you move the drone.
* 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. Attitude indicator in QGroundControl is shown below:
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:
<img src="img/qgc-attitude.png" height="200">
<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 in the console. Use the following commands **— remove the propellers before running the tests!**
@@ -243,9 +243,43 @@ 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.
## Wi-Fi configuration
You can configure the Wi-Fi using parameters and console commands.
The Wi-Fi mode is chosen using `WIFI_MODE` parameter in QGroundControl or in the console:
* `0` — Wi-Fi is disabled.
* `1` — Access Point mode (*AP*) — the drone creates a Wi-Fi network.
* `2` — Client mode (*STA*) — the drone connects to an existing Wi-Fi network.
* `3` — *ESP-NOW (not implemented yet)*.
> [!WARNING]
> Tests showed that Client mode may cause **additional delays** in remote control (due to retranslations), so it's generally not recommended.
The SSID and password are configured using the `ap` and `sta` console commands:
```
ap <ssid> <password>
sta <ssid> <password>
```
Example of configuring the Access Point mode:
```
ap my-flix-ssid mypassword123
p WIFI_MODE 1
```
Disabling Wi-Fi:
```
p WIFI_MODE 0
```
## Flight log
After the flight, you can download the flight log for analysis wirelessly. Use the following for that:
After the flight, you can download the flight log for analysis wirelessly. Use the following command on your computer for that:
```bash
make log

View File

@@ -6,6 +6,7 @@
#include "pid.h"
#include "vector.h"
#include "util.h"
#include "lpf.h"
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern const int RAW, ACRO, STAB, AUTO;
@@ -14,6 +15,7 @@ extern uint16_t channels[16];
extern float controlTime;
extern int mode;
extern bool armed;
extern LowPassFilter<Vector> gyroBiasFilter;
const char* motd =
"\nWelcome to\n"
@@ -38,6 +40,8 @@ const char* motd =
"raw/stab/acro/auto - set mode\n"
"rc - show RC data\n"
"wifi - show Wi-Fi info\n"
"ap <ssid> <password> - setup Wi-Fi access point\n"
"sta <ssid> <password> - setup Wi-Fi client mode\n"
"mot - show motor output\n"
"log [dump] - print log header [and data]\n"
"cr - calibrate RC\n"
@@ -54,9 +58,7 @@ void print(const char* format, ...) {
vsnprintf(buf, sizeof(buf), format, args);
va_end(args);
Serial.print(buf);
#if WIFI_ENABLED
mavlinkPrint(buf);
#endif
}
void pause(float duration) {
@@ -64,9 +66,7 @@ void pause(float duration) {
while (t - start < duration) {
step();
handleInput();
#if WIFI_ENABLED
processMavlink();
#endif
delay(50);
}
}
@@ -136,9 +136,11 @@ void doCommand(String str, bool echo = false) {
print("mode: %s\n", getModeName());
print("armed: %d\n", armed);
} else if (command == "wifi") {
#if WIFI_ENABLED
printWiFiInfo();
#endif
} else if (command == "ap") {
configWiFi(true, arg0.c_str(), arg1.c_str());
} else if (command == "sta") {
configWiFi(false, arg0.c_str(), arg1.c_str());
} 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]);
@@ -178,6 +180,7 @@ void doCommand(String str, bool echo = false) {
#endif
} else if (command == "reset") {
attitude = Quaternion();
gyroBiasFilter.reset();
} else if (command == "reboot") {
ESP.restart();
} else {

View File

@@ -38,6 +38,12 @@ const int RAW = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
int mode = STAB;
bool armed = false;
Quaternion attitudeTarget;
Vector ratesTarget;
Vector ratesExtra; // feedforward rates
Vector torqueTarget;
float thrustTarget;
PID rollRatePID(ROLLRATE_P, ROLLRATE_I, ROLLRATE_D, ROLLRATE_I_LIM, RATES_D_LPF_ALPHA);
PID pitchRatePID(PITCHRATE_P, PITCHRATE_I, PITCHRATE_D, PITCHRATE_I_LIM, RATES_D_LPF_ALPHA);
PID yawRatePID(YAWRATE_P, YAWRATE_I, YAWRATE_D);
@@ -47,12 +53,6 @@ PID yawPID(YAW_P, 0, 0);
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
float tiltMax = TILT_MAX;
Quaternion attitudeTarget;
Vector ratesTarget;
Vector ratesExtra; // feedforward rates
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, controlMode;

View File

@@ -7,8 +7,6 @@
#include "quaternion.h"
#include "util.h"
#define WIFI_ENABLED 1
extern float t, dt;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
extern Vector gyro, acc;
@@ -25,9 +23,7 @@ void setup() {
setupLED();
setupMotors();
setLED(true);
#if WIFI_ENABLED
setupWiFi();
#endif
setupIMU();
setupRC();
setLED(false);
@@ -42,9 +38,7 @@ void loop() {
control();
sendMotors();
handleInput();
#if WIFI_ENABLED
processMavlink();
#endif
logData();
syncParameters();
}

View File

@@ -19,6 +19,8 @@ Vector acc; // accelerometer output, m/s/s
Vector accBias;
Vector accScale(1, 1, 1);
LowPassFilter<Vector> gyroBiasFilter(0.001);
void setupIMU() {
print("Setup IMU\n");
imu.begin();
@@ -50,8 +52,6 @@ void readIMU() {
void calibrateGyroOnce() {
static Delay landedDelay(2);
if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary
static LowPassFilter<Vector> gyroBiasFilter(0.001);
gyroBias = gyroBiasFilter.update(gyro);
}

View File

@@ -14,15 +14,6 @@ public:
LowPassFilter(float alpha): alpha(alpha) {};
T update(const T input) {
if (alpha == 1) { // filter disabled
return input;
}
if (!initialized) {
output = input;
initialized = true;
}
return output += alpha * (input - output);
}
@@ -31,9 +22,6 @@ public:
}
void reset() {
initialized = false;
output = T(); // set to zero
}
private:
bool initialized = false;
};

View File

@@ -3,19 +3,16 @@
// MAVLink communication
#if WIFI_ENABLED
#include <MAVLink.h>
#include "util.h"
#define SYSTEM_ID 1
#define MAVLINK_RATE_SLOW 1
#define MAVLINK_RATE_FAST 10
extern float controlTime;
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
int mavlinkSysId = 1;
Rate telemetryFast(10);
Rate telemetrySlow(2);
void processMavlink() {
sendMavlink();
@@ -28,10 +25,8 @@ void sendMavlink() {
mavlink_message_t msg;
uint32_t time = t * 1000;
static Rate slow(MAVLINK_RATE_SLOW), fast(MAVLINK_RATE_FAST);
if (slow) {
mavlink_msg_heartbeat_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
if (telemetrySlow) {
mavlink_msg_heartbeat_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
(armed ? MAV_MODE_FLAG_SAFETY_ARMED : 0) |
((mode == STAB) ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0) |
((mode == AUTO) ? MAV_MODE_FLAG_AUTO_ENABLED : MAV_MODE_FLAG_MANUAL_INPUT_ENABLED),
@@ -40,27 +35,27 @@ void sendMavlink() {
if (!mavlinkConnected) return; // send only heartbeat until connected
mavlink_msg_extended_sys_state_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
mavlink_msg_extended_sys_state_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
MAV_VTOL_STATE_UNDEFINED, landed ? MAV_LANDED_STATE_ON_GROUND : MAV_LANDED_STATE_IN_AIR);
sendMessage(&msg);
}
if (fast && mavlinkConnected) {
if (telemetryFast && mavlinkConnected) {
const float zeroQuat[] = {0, 0, 0, 0};
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, 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, zeroQuat); // convert to frd
sendMessage(&msg);
mavlink_msg_rc_channels_raw_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,
mavlink_msg_rc_channels_raw_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,
channels[0], channels[1], channels[2], channels[3], channels[4], channels[5], channels[6], channels[7], UINT8_MAX);
if (channels[0] != 0) sendMessage(&msg); // 0 means no RC input
float controls[8];
memcpy(controls, motors, sizeof(motors));
mavlink_msg_actuator_control_target_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0, controls);
mavlink_msg_actuator_control_target_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0, controls);
sendMessage(&msg);
mavlink_msg_scaled_imu_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time,
mavlink_msg_scaled_imu_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, time,
acc.x * 1000, -acc.y * 1000, -acc.z * 1000, // convert to frd
gyro.x * 1000, -gyro.y * 1000, -gyro.z * 1000,
0, 0, 0, 0);
@@ -95,7 +90,7 @@ void handleMavlink(const void *_msg) {
if (msg.msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
mavlink_manual_control_t m;
mavlink_msg_manual_control_decode(&msg, &m);
if (m.target && m.target != SYSTEM_ID) return; // 0 is broadcast
if (m.target && m.target != mavlinkSysId) return; // 0 is broadcast
controlThrottle = m.z / 1000.0f;
controlPitch = m.x / 1000.0f;
@@ -108,11 +103,11 @@ void handleMavlink(const void *_msg) {
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
mavlink_param_request_list_t m;
mavlink_msg_param_request_list_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
if (m.target_system && m.target_system != mavlinkSysId) return;
mavlink_message_t msg;
for (int i = 0; i < parametersCount(); i++) {
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
mavlink_msg_param_value_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
getParameterName(i), getParameter(i), MAV_PARAM_TYPE_REAL32, parametersCount(), i);
sendMessage(&msg);
}
@@ -121,7 +116,7 @@ void handleMavlink(const void *_msg) {
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_READ) {
mavlink_param_request_read_t m;
mavlink_msg_param_request_read_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
if (m.target_system && m.target_system != mavlinkSysId) return;
char name[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
@@ -130,7 +125,7 @@ void handleMavlink(const void *_msg) {
memcpy(name, getParameterName(m.param_index), 16);
}
mavlink_message_t msg;
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
mavlink_msg_param_value_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
name, value, MAV_PARAM_TYPE_REAL32, parametersCount(), m.param_index);
sendMessage(&msg);
}
@@ -138,32 +133,33 @@ void handleMavlink(const void *_msg) {
if (msg.msgid == MAVLINK_MSG_ID_PARAM_SET) {
mavlink_param_set_t m;
mavlink_msg_param_set_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
if (m.target_system && m.target_system != mavlinkSysId) return;
char name[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN + 1];
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
setParameter(name, m.param_value);
bool success = setParameter(name, m.param_value);
if (!success) return;
// send ack
mavlink_message_t msg;
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
m.param_id, m.param_value, MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
mavlink_msg_param_value_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
m.param_id, getParameter(name), MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
sendMessage(&msg);
}
if (msg.msgid == MAVLINK_MSG_ID_MISSION_REQUEST_LIST) { // handle to make qgc happy
mavlink_mission_request_list_t m;
mavlink_msg_mission_request_list_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
if (m.target_system && m.target_system != mavlinkSysId) return;
mavlink_message_t msg;
mavlink_msg_mission_count_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, 0, 0, 0, MAV_MISSION_TYPE_MISSION, 0);
mavlink_msg_mission_count_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, 0, 0, 0, MAV_MISSION_TYPE_MISSION, 0);
sendMessage(&msg);
}
if (msg.msgid == MAVLINK_MSG_ID_SERIAL_CONTROL) {
mavlink_serial_control_t m;
mavlink_msg_serial_control_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
if (m.target_system && m.target_system != mavlinkSysId) return;
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
strlcpy(data, (const char *)m.data, m.count); // data might be not null-terminated
@@ -175,7 +171,7 @@ void handleMavlink(const void *_msg) {
mavlink_set_attitude_target_t m;
mavlink_msg_set_attitude_target_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
if (m.target_system && m.target_system != mavlinkSysId) return;
// copy attitude, rates and thrust targets
ratesTarget.x = m.body_roll_rate;
@@ -197,7 +193,7 @@ void handleMavlink(const void *_msg) {
mavlink_set_actuator_control_target_t m;
mavlink_msg_set_actuator_control_target_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
if (m.target_system && m.target_system != mavlinkSysId) return;
attitudeTarget.invalidate();
ratesTarget.invalidate();
@@ -209,12 +205,12 @@ void handleMavlink(const void *_msg) {
if (msg.msgid == MAVLINK_MSG_ID_LOG_REQUEST_DATA) {
mavlink_log_request_data_t m;
mavlink_msg_log_request_data_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
if (m.target_system && m.target_system != mavlinkSysId) return;
// Send all log records
for (int i = 0; i < sizeof(logBuffer) / sizeof(logBuffer[0]); i++) {
mavlink_message_t msg;
mavlink_msg_log_data_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, 0, i,
mavlink_msg_log_data_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, 0, i,
sizeof(logBuffer[0]), (uint8_t *)logBuffer[i]);
sendMessage(&msg);
}
@@ -224,13 +220,13 @@ void handleMavlink(const void *_msg) {
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
mavlink_command_long_t m;
mavlink_msg_command_long_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
if (m.target_system && m.target_system != mavlinkSysId) return;
mavlink_message_t response;
bool accepted = false;
if (m.command == MAV_CMD_REQUEST_MESSAGE && m.param1 == MAVLINK_MSG_ID_AUTOPILOT_VERSION) {
accepted = true;
mavlink_msg_autopilot_version_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &response,
mavlink_msg_autopilot_version_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &response,
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MAVLINK2, 1, 0, 1, 1, 0, 0, 0, 0, 0, 0, 0);
sendMessage(&response);
}
@@ -249,7 +245,7 @@ void handleMavlink(const void *_msg) {
// send command ack
mavlink_message_t ack;
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_UNSUPPORTED, UINT8_MAX, 0, msg.sysid, msg.compid);
mavlink_msg_command_ack_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_UNSUPPORTED, UINT8_MAX, 0, msg.sysid, msg.compid);
sendMessage(&ack);
}
}
@@ -266,7 +262,7 @@ void sendMavlinkPrint() {
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
strlcpy(data, str + i, sizeof(data));
mavlink_message_t msg;
mavlink_msg_serial_control_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
mavlink_msg_serial_control_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
SERIAL_CONTROL_DEV_SHELL,
i + MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN < strlen(str) ? SERIAL_CONTROL_FLAG_MULTI : 0, // more chunks to go
0, 0, strlen(data), (uint8_t *)data, 0, 0);
@@ -274,5 +270,3 @@ void sendMavlinkPrint() {
}
mavlinkPrintBuffer.clear();
}
#endif

View File

@@ -9,13 +9,20 @@
extern float channelZero[16];
extern float channelMax[16];
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern int wifiMode, udpLocalPort, udpRemotePort;
extern float rcLossTimeout, descendTime;
Preferences storage;
struct Parameter {
const char *name; // max length is 15 (Preferences key limit)
float *variable;
float value; // cache
bool integer;
union { float *f; int *i; }; // pointer to variable
float cache; // what's stored in flash
Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {};
Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {};
float getValue() const { return integer ? *i : *f; };
void setValue(const float value) { if (integer) *i = value; else *f = value; };
};
Parameter parameters[] = {
@@ -52,6 +59,7 @@ Parameter parameters[] = {
{"IMU_ACC_SCALE_X", &accScale.x},
{"IMU_ACC_SCALE_Y", &accScale.y},
{"IMU_ACC_SCALE_Z", &accScale.z},
{"IMU_GYRO_BIAS_A", &gyroBiasFilter.alpha},
// estimate
{"EST_ACC_WEIGHT", &accWeight},
{"EST_RATES_LPF_A", &ratesFilter.alpha},
@@ -77,6 +85,17 @@ Parameter parameters[] = {
{"RC_THROTTLE", &throttleChannel},
{"RC_YAW", &yawChannel},
{"RC_MODE", &modeChannel},
// wifi
{"WIFI_MODE", &wifiMode},
{"WIFI_LOC_PORT", &udpLocalPort},
{"WIFI_REM_PORT", &udpRemotePort},
// mavlink
{"MAV_SYS_ID", &mavlinkSysId},
{"MAV_RATE_SLOW", &telemetrySlow.rate},
{"MAV_RATE_FAST", &telemetryFast.rate},
// safety
{"SF_RC_LOSS_TIME", &rcLossTimeout},
{"SF_DESCEND_TIME", &descendTime},
};
void setupParameters() {
@@ -84,10 +103,10 @@ void setupParameters() {
// Read parameters from storage
for (auto &parameter : parameters) {
if (!storage.isKey(parameter.name)) {
storage.putFloat(parameter.name, *parameter.variable);
storage.putFloat(parameter.name, parameter.getValue()); // store default value
}
*parameter.variable = storage.getFloat(parameter.name, *parameter.variable);
parameter.value = *parameter.variable;
parameter.setValue(storage.getFloat(parameter.name, 0));
parameter.cache = parameter.getValue();
}
}
@@ -102,13 +121,13 @@ const char *getParameterName(int index) {
float getParameter(int index) {
if (index < 0 || index >= parametersCount()) return NAN;
return *parameters[index].variable;
return parameters[index].getValue();
}
float getParameter(const char *name) {
for (auto &parameter : parameters) {
if (strcmp(parameter.name, name) == 0) {
return *parameter.variable;
if (strcasecmp(parameter.name, name) == 0) {
return parameter.getValue();
}
}
return NAN;
@@ -116,8 +135,9 @@ float getParameter(const char *name) {
bool setParameter(const char *name, const float value) {
for (auto &parameter : parameters) {
if (strcmp(parameter.name, name) == 0) {
*parameter.variable = value;
if (strcasecmp(parameter.name, name) == 0) {
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
parameter.setValue(value);
return true;
}
}
@@ -130,16 +150,18 @@ void syncParameters() {
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
for (auto &parameter : parameters) {
if (parameter.value == *parameter.variable) continue;
if (isnan(parameter.value) && isnan(*parameter.variable)) continue; // handle NAN != NAN
storage.putFloat(parameter.name, *parameter.variable);
parameter.value = *parameter.variable;
if (parameter.getValue() == parameter.cache) continue; // no change
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());
parameter.cache = parameter.getValue(); // update cache
}
}
void printParameters() {
for (auto &parameter : parameters) {
print("%s = %g\n", parameter.name, *parameter.variable);
print("%s = %g\n", parameter.name, parameter.getValue());
}
}

View File

@@ -13,10 +13,10 @@ 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)
float controlMode = NAN;
float controlTime = NAN; // time of the last controls update
// Channels mapping (using float to store in parameters):
// Channels mapping (nan means not assigned):
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
void setupRC() {

View File

@@ -3,12 +3,12 @@
// Fail-safe functions
#define RC_LOSS_TIMEOUT 1
#define DESCEND_TIME 10
extern float controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
float rcLossTimeout = 1;
float descendTime = 10;
void failsafe() {
rcLossFailsafe();
autoFailsafe();
@@ -16,9 +16,8 @@ void failsafe() {
// RC loss failsafe
void rcLossFailsafe() {
if (controlTime == 0) return; // no RC at all
if (!armed) return;
if (t - controlTime > RC_LOSS_TIMEOUT) {
if (t - controlTime > rcLossTimeout) {
descend();
}
}
@@ -27,7 +26,7 @@ void rcLossFailsafe() {
void descend() {
mode = AUTO;
attitudeTarget = Quaternion();
thrustTarget -= dt / DESCEND_TIME;
thrustTarget -= dt / descendTime;
if (thrustTarget < 0) {
thrustTarget = 0;
armed = false;

View File

@@ -1,49 +1,76 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Wi-Fi support
#if WIFI_ENABLED
// Wi-Fi communication
#include <WiFi.h>
#include <WiFiAP.h>
#include <WiFiUdp.h>
#include "Preferences.h"
#define WIFI_SSID "flix"
#define WIFI_PASSWORD "flixwifi"
#define WIFI_UDP_PORT 14550
#define WIFI_UDP_REMOTE_PORT 14550
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
extern Preferences storage; // use the main preferences storage
const int W_DISABLED = 0, W_AP = 1, W_STA = 2;
int wifiMode = W_AP;
int udpLocalPort = 14550;
int udpRemotePort = 14550;
IPAddress udpRemoteIP = "255.255.255.255";
WiFiUDP udp;
void setupWiFi() {
print("Setup Wi-Fi\n");
WiFi.softAP(WIFI_SSID, WIFI_PASSWORD);
udp.begin(WIFI_UDP_PORT);
if (wifiMode == W_AP) {
WiFi.softAP(storage.getString("WIFI_AP_SSID", "flix").c_str(), storage.getString("WIFI_AP_PASS", "flixwifi").c_str());
} else if (wifiMode == W_STA) {
WiFi.begin(storage.getString("WIFI_STA_SSID", "").c_str(), storage.getString("WIFI_STA_PASS", "").c_str());
}
udp.begin(udpLocalPort);
}
void sendWiFi(const uint8_t *buf, int len) {
if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return;
udp.beginPacket(udp.remoteIP() ? udp.remoteIP() : WIFI_UDP_REMOTE_ADDR, WIFI_UDP_REMOTE_PORT);
if (WiFi.softAPgetStationNum() == 0 && !WiFi.isConnected()) return;
udp.beginPacket(udpRemoteIP, udpRemotePort);
udp.write(buf, len);
udp.endPacket();
}
int receiveWiFi(uint8_t *buf, int len) {
udp.parsePacket();
if (udp.remoteIP()) udpRemoteIP = udp.remoteIP();
return udp.read(buf, len);
}
void printWiFiInfo() {
if (WiFi.getMode() == WIFI_MODE_AP) {
print("Mode: Access Point (AP)\n");
print("MAC: %s\n", WiFi.softAPmacAddress().c_str());
print("SSID: %s\n", WiFi.softAPSSID().c_str());
print("Password: %s\n", WIFI_PASSWORD);
print("Password: ***\n");
print("Clients: %d\n", WiFi.softAPgetStationNum());
print("Status: %d\n", WiFi.status());
print("IP: %s\n", WiFi.softAPIP().toString().c_str());
print("Remote IP: %s\n", udp.remoteIP().toString().c_str());
} else if (WiFi.getMode() == WIFI_MODE_STA) {
print("Mode: Client (STA)\n");
print("Connected: %d\n", WiFi.isConnected());
print("MAC: %s\n", WiFi.macAddress().c_str());
print("SSID: %s\n", WiFi.SSID().c_str());
print("Password: ***\n");
print("IP: %s\n", WiFi.localIP().toString().c_str());
} else {
print("Mode: Disabled\n");
return;
}
print("Remote IP: %s\n", udpRemoteIP.toString().c_str());
print("MAVLink connected: %d\n", mavlinkConnected);
}
#endif
void configWiFi(bool ap, const char *ssid, const char *password) {
if (ap) {
storage.putString("WIFI_AP_SSID", ssid);
storage.putString("WIFI_AP_PASS", password);
} else {
storage.putString("WIFI_STA_SSID", ssid);
storage.putString("WIFI_STA_PASS", password);
}
print("✓ Reboot to apply new settings\n");
}

View File

@@ -10,8 +10,6 @@
#include "Arduino.h"
#include "wifi.h"
#define WIFI_ENABLED 1
extern float t, dt;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
extern Vector rates;
@@ -73,3 +71,4 @@ void calibrateAccel() { print("Skip accel calibrating\n"); };
void printIMUCalibration() { print("cal: N/A\n"); };
void printIMUInfo() {};
void printWiFiInfo() {};
void configWiFi(bool, const char*, const char*) { print("Skip WiFi config\n"); };

View File

@@ -13,7 +13,7 @@ lines = []
print('Downloading log...')
count = 0
dev.write('log\n'.encode())
dev.write('log dump\n'.encode())
while True:
line = dev.readline()
if not line:

View File

@@ -43,6 +43,7 @@ records = [record for record in records if record[0] != 0]
print(f'Received records: {len(records)}')
os.makedirs(f'{DIR}/log', exist_ok=True)
log = open(f'{DIR}/log/{datetime.datetime.now().isoformat()}.csv', 'wb')
log.write(header.encode() + b'\n')
for record in records: