8 Commits

Author SHA1 Message Date
Oleg Kalachev
385226bc97 Add sources to the simulator using cmake instead of include 2026-01-09 17:01:14 +03:00
Oleg Kalachev
e7e57d1020 Fix 2026-01-09 09:46:56 +03:00
Oleg Kalachev
213b9788a9 Fixes 2026-01-09 09:45:23 +03:00
Oleg Kalachev
69fb5d30f6 Merge branch 'master' into cpp 2026-01-09 09:41:31 +03:00
Oleg Kalachev
e59a190c1c Fix 2025-10-21 18:41:58 +03:00
Oleg Kalachev
207c0e41f7 Add parameters to config.h 2025-10-21 18:38:51 +03:00
Oleg Kalachev
d7d79ff03f Make .cpp style version compile 2025-10-21 18:31:54 +03:00
Oleg Kalachev
6725f1d3de Change source files type from ino to cpp 2025-10-20 23:06:13 +03:00
39 changed files with 457 additions and 406 deletions

View File

@@ -25,6 +25,8 @@ jobs:
path: flix/build path: flix/build
- name: Build firmware for ESP32-S3 - name: Build firmware for ESP32-S3
run: make BOARD=esp32:esp32:esp32s3 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 - name: Check c_cpp_properties.json
run: tools/check_c_cpp_properties.py run: tools/check_c_cpp_properties.py

View File

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

View File

@@ -6,34 +6,21 @@
"${workspaceFolder}/flix", "${workspaceFolder}/flix",
"${workspaceFolder}/gazebo", "${workspaceFolder}/gazebo",
"${workspaceFolder}/tools/**", "${workspaceFolder}/tools/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32", "~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**", "~/.arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32", "~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
"~/.arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**", "~/.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",
"~/Arduino/libraries/**", "~/Arduino/libraries/**",
"/usr/include/gazebo-11/", "/usr/include/gazebo-11/",
"/usr/include/ignition/math6/" "/usr/include/ignition/math6/"
], ],
"forcedInclude": [ "forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h", "${workspaceFolder}/.vscode/intellisense.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32/Arduino.h", "~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32/pins_arduino.h", "~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h"
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",
"${workspaceFolder}/flix/flix.ino",
"${workspaceFolder}/flix/imu.ino",
"${workspaceFolder}/flix/led.ino",
"${workspaceFolder}/flix/log.ino",
"${workspaceFolder}/flix/mavlink.ino",
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino",
"${workspaceFolder}/flix/safety.ino"
], ],
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2511/bin/xtensa-esp32-elf-g++", "compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
"cStandard": "c11", "cStandard": "c11",
"cppStandard": "c++17", "cppStandard": "c++17",
"defines": [ "defines": [
@@ -53,34 +40,21 @@
"name": "Mac", "name": "Mac",
"includePath": [ "includePath": [
"${workspaceFolder}/flix", "${workspaceFolder}/flix",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32", "~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**", "~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32", "~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
"~/Library/Arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**", "~/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",
"~/Documents/Arduino/libraries/**", "~/Documents/Arduino/libraries/**",
"/opt/homebrew/include/gazebo-11/", "/opt/homebrew/include/gazebo-11/",
"/opt/homebrew/include/ignition/math6/" "/opt/homebrew/include/ignition/math6/"
], ],
"forcedInclude": [ "forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h", "${workspaceFolder}/.vscode/intellisense.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32/Arduino.h", "~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32/pins_arduino.h", "~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h"
"${workspaceFolder}/flix/flix.ino",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",
"${workspaceFolder}/flix/imu.ino",
"${workspaceFolder}/flix/led.ino",
"${workspaceFolder}/flix/log.ino",
"${workspaceFolder}/flix/mavlink.ino",
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino",
"${workspaceFolder}/flix/safety.ino"
], ],
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2511/bin/xtensa-esp32-elf-g++", "compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
"cStandard": "c11", "cStandard": "c11",
"cppStandard": "c++17", "cppStandard": "c++17",
"defines": [ "defines": [
@@ -103,32 +77,19 @@
"${workspaceFolder}/flix", "${workspaceFolder}/flix",
"${workspaceFolder}/gazebo", "${workspaceFolder}/gazebo",
"${workspaceFolder}/tools/**", "${workspaceFolder}/tools/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32", "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**", "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32", "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**", "~/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",
"~/Documents/Arduino/libraries/**" "~/Documents/Arduino/libraries/**"
], ],
"forcedInclude": [ "forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h", "${workspaceFolder}/.vscode/intellisense.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32/Arduino.h", "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32/pins_arduino.h", "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h"
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",
"${workspaceFolder}/flix/flix.ino",
"${workspaceFolder}/flix/imu.ino",
"${workspaceFolder}/flix/led.ino",
"${workspaceFolder}/flix/log.ino",
"${workspaceFolder}/flix/mavlink.ino",
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino",
"${workspaceFolder}/flix/safety.ino"
], ],
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2511/bin/xtensa-esp32-elf-g++.exe", "compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++.exe",
"cStandard": "c11", "cStandard": "c11",
"cppStandard": "c++17", "cppStandard": "c++17",
"defines": [ "defines": [

View File

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

View File

@@ -21,13 +21,15 @@
* Dedicated for education and research. * Dedicated for education and research.
* Made from general-purpose components. * Made from general-purpose components.
* Simple and clean source code in Arduino (<2k lines firmware). * 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. * Control using USB gamepad, remote control or smartphone.
* Wi-Fi and MAVLink support.
* Wireless command line interface and analyzing. * Wireless command line interface and analyzing.
* Precise simulation with Gazebo. * Precise simulation with Gazebo.
* Python library for scripting and automatic flights. * Python library.
* Textbook on flight control theory and practice ([in development](https://quadcopter.dev)). * Textbook on flight control theory and practice ([in development](https://quadcopter.dev)).
* *Position control (planned)*. * *Position control (using external camera) and autonomous flights¹*.
*¹ — planned.*
## It actually flies ## It actually flies
@@ -138,10 +140,10 @@ You can see a user-contributed [variant of complete circuit diagram](https://mir
|Motor|Position|Direction|Prop type|Motor wires|GPIO| |Motor|Position|Direction|Prop type|Motor wires|GPIO|
|-|-|-|-|-|-| |-|-|-|-|-|-|
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 *(TDI)*| |Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 (*TDI*)|
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 *(TCK)*| |Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 (*TCK*)|
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 *(TMS)*| |Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 (*TMS*)|
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 *(TD0)*| |Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 (*TD0*)|
Clockwise motors have blue & red wires and correspond to propeller type A (marked on the propeller). Clockwise motors have blue & red wires and correspond to propeller type A (marked on the propeller).
Counter-clockwise motors have black & white wires correspond to propeller type B. Counter-clockwise motors have black & white wires correspond to propeller type B.

View File

@@ -41,10 +41,10 @@ Motors connection table:
|Motor|Position|Direction|Prop type|Motor wires|GPIO| |Motor|Position|Direction|Prop type|Motor wires|GPIO|
|-|-|-|-|-|-| |-|-|-|-|-|-|
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 *(TDI)*| |Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 (*TDI*)|
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 *(TCK)*| |Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 (*TCK*)|
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 *(TMS)*| |Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 (*TMS*)|
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 *(TD0)*| |Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 (*TD0*)|
## Motors tightening ## Motors tightening

View File

@@ -110,7 +110,7 @@ float angle = Vector::angleBetween(a, b); // 1.57 (90 градусов)
#### Скалярное произведение #### Скалярное произведение
Скалярное произведение векторов *(dot product)* — это произведение длин двух векторов на косинус угла между ними. В математике оно обозначается знаком `·` или слитным написанием векторов. Интуитивно, результат скалярного произведения показывает, насколько два вектора *сонаправлены*. Скалярное произведение векторов (*dot product*) — это произведение длин двух векторов на косинус угла между ними. В математике оно обозначается знаком `·` или слитным написанием векторов. Интуитивно, результат скалярного произведения показывает, насколько два вектора *сонаправлены*.
В Flix используется статический метод `Vector::dot()`: В Flix используется статический метод `Vector::dot()`:
@@ -124,7 +124,7 @@ float dotProduct = Vector::dot(a, b); // 32
#### Векторное произведение #### Векторное произведение
Векторное произведение *(cross product)* позволяет найти вектор, перпендикулярный двум другим векторам. В математике оно обозначается знаком `×`, а в прошивке используется статический метод `Vector::cross()`: Векторное произведение (*cross product*) позволяет найти вектор, перпендикулярный двум другим векторам. В математике оно обозначается знаком `×`, а в прошивке используется статический метод `Vector::cross()`:
```cpp ```cpp
Vector a(1, 2, 3); Vector a(1, 2, 3);
@@ -144,9 +144,9 @@ Vector crossProduct = Vector::cross(a, b); // -3, 6, -3
В прошивке углы Эйлера сохраняются в обычный объект `Vector` (хоть и, строго говоря, не являются вектором): В прошивке углы Эйлера сохраняются в обычный объект `Vector` (хоть и, строго говоря, не являются вектором):
* Угол по крену *(roll)* — `vector.x`. * Угол по крену (*roll*) — `vector.x`.
* Угол по тангажу *(pitch)* — `vector.y`. * Угол по тангажу (*pitch*) — `vector.y`.
* Угол по рысканию *(yaw)* — `vector.z`. * Угол по рысканию (*yaw*) — `vector.z`.
Особенности углов Эйлера: Особенности углов Эйлера:
@@ -162,8 +162,8 @@ Vector crossProduct = Vector::cross(a, b); // -3, 6, -3
Помимо углов Эйлера, любую ориентацию в трехмерном пространстве можно представить в виде вращения вокруг некоторой оси на некоторый угол. В геометрии это доказывается, как **теорема вращения Эйлера**. В таком представлении ориентация задается двумя величинами: Помимо углов Эйлера, любую ориентацию в трехмерном пространстве можно представить в виде вращения вокруг некоторой оси на некоторый угол. В геометрии это доказывается, как **теорема вращения Эйлера**. В таком представлении ориентация задается двумя величинами:
* **Ось вращения** *(axis)* — единичный вектор, определяющий ось вращения. * **Ось вращения** (*axis*) — единичный вектор, определяющий ось вращения.
* **Угол поворота** *(angle* или *θ)* — угол, на который нужно повернуть объект вокруг этой оси. * **Угол поворота** (*angle* или *θ*) — угол, на который нужно повернуть объект вокруг этой оси.
В Flix ось вращения задается объектом `Vector`, а угол поворота — числом типа `float` в радианах: В Flix ось вращения задается объектом `Vector`, а угол поворота — числом типа `float` в радианах:
@@ -177,7 +177,7 @@ float angle = radians(45);
### Вектор вращения ### Вектор вращения
Если умножить вектор *axis* на угол поворота *θ*, то получится **вектор вращения** *(rotation vector)*. Этот вектор играет важную роль в алгоритмах управления ориентацией летательного аппарата. Если умножить вектор *axis* на угол поворота *θ*, то получится **вектор вращения** (*rotation vector*). Этот вектор играет важную роль в алгоритмах управления ориентацией летательного аппарата.
Вектор вращения обладает замечательным свойством: если угловые скорости объекта (в собственной системе координат) в каждый момент времени совпадают с компонентами этого вектора, то за единичное время объект придет к заданной этим вектором ориентации. Это свойство позволяет использовать вектор вращения для управления ориентацией объекта посредством управления угловыми скоростями. Вектор вращения обладает замечательным свойством: если угловые скорости объекта (в собственной системе координат) в каждый момент времени совпадают с компонентами этого вектора, то за единичное время объект придет к заданной этим вектором ориентации. Это свойство позволяет использовать вектор вращения для управления ориентацией объекта посредством управления угловыми скоростями.
@@ -198,7 +198,7 @@ Vector rotation = radians(45) * Vector(1, 2, 3);
<a href="https://github.com/okalachev/flix/blob/master/flix/quaternion.h"><code>quaternion.h</code></a>.<br> <a href="https://github.com/okalachev/flix/blob/master/flix/quaternion.h"><code>quaternion.h</code></a>.<br>
</div> </div>
Вектор вращения удобен, но еще удобнее использовать **кватернион**. В Flix кватернионы задаются объектами `Quaternion` из библиотеки `quaternion.h`. Кватернион состоит из четырех значений: *w*, *x*, *y*, *z* и рассчитывается из вектора оси вращения *(axis)* и угла поворота *(θ)* по формуле: Вектор вращения удобен, но еще удобнее использовать **кватернион**. В Flix кватернионы задаются объектами `Quaternion` из библиотеки `quaternion.h`. Кватернион состоит из четырех значений: *w*, *x*, *y*, *z* и рассчитывается из вектора оси вращения (*axis*) и угла поворота (*θ*) по формуле:
\\[ q = \left( \begin{array}{c} w \\\\ x \\\\ y \\\\ z \end{array} \right) = \left( \begin{array}{c} \cos\left(\frac{\theta}{2}\right) \\\\ axis\_x \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_y \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_z \cdot \sin\left(\frac{\theta}{2}\right) \end{array} \right) \\] \\[ q = \left( \begin{array}{c} w \\\\ x \\\\ y \\\\ z \end{array} \right) = \left( \begin{array}{c} \cos\left(\frac{\theta}{2}\right) \\\\ axis\_x \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_y \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_z \cdot \sin\left(\frac{\theta}{2}\right) \end{array} \right) \\]

View File

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

View File

@@ -13,10 +13,10 @@ Do the following:
Do the following: Do the following:
* **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V. * **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V.
* **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 startup output. * **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. * **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. * **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 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)*. * **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*).
* **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**. * **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. * **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: * **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). 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).* 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.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. 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.
4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library): 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. * `FlixPeriph`, the latest version.
* `MAVLink`, version 2.0.25. * `MAVLink`, version 2.0.16.
5. Open the `flix/flix.ino` sketch from downloaded firmware sources in Arduino IDE. 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. 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. 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"> <img src="img/parameters.png" width="400">
You can also work with parameters using `p` command in the console. Parameter names are case-insensitive. You can also work with parameters using `p` command in the console.
### Define IMU orientation ### 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 `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. * 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. Attitude indicator in QGroundControl is shown below:
<a href="https://youtu.be/yVRN23-GISU"><img width=300 src="https://i3.ytimg.com/vi/yVRN23-GISU/maxresdefault.jpg"></a> <img src="img/qgc-attitude.png" height="200">
3. Perform motor tests in the console. 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!**
@@ -243,43 +243,9 @@ 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. 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 ## Flight log
After the flight, you can download the flight log for analysis wirelessly. Use the following command on your computer for that: After the flight, you can download the flight log for analysis wirelessly. Use the following for that:
```bash ```bash
make log make log

View File

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

55
flix/config.h Normal file
View File

@@ -0,0 +1,55 @@
// Wi-Fi
#define WIFI_ENABLED 1
#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"
// Motors
#define MOTOR_0_PIN 12 // rear left
#define MOTOR_1_PIN 13 // rear right
#define MOTOR_2_PIN 14 // front right
#define MOTOR_3_PIN 15 // front left
#define PWM_FREQUENCY 78000
#define PWM_RESOLUTION 10
#define PWM_STOP 0
#define PWM_MIN 0
#define PWM_MAX 1000000 / PWM_FREQUENCY
// Control
#define PITCHRATE_P 0.05
#define PITCHRATE_I 0.2
#define PITCHRATE_D 0.001
#define PITCHRATE_I_LIM 0.3
#define ROLLRATE_P PITCHRATE_P
#define ROLLRATE_I PITCHRATE_I
#define ROLLRATE_D PITCHRATE_D
#define ROLLRATE_I_LIM PITCHRATE_I_LIM
#define YAWRATE_P 0.3
#define YAWRATE_I 0.0
#define YAWRATE_D 0.0
#define YAWRATE_I_LIM 0.3
#define ROLL_P 6
#define ROLL_I 0
#define ROLL_D 0
#define PITCH_P ROLL_P
#define PITCH_I ROLL_I
#define PITCH_D ROLL_D
#define YAW_P 3
#define PITCHRATE_MAX radians(360)
#define ROLLRATE_MAX radians(360)
#define YAWRATE_MAX radians(300)
#define TILT_MAX radians(30)
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
// Estimation
#define WEIGHT_ACC 0.003
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
// MAVLink
#define SYSTEM_ID 1
// Safety
#define RC_LOSS_TIMEOUT 1
#define DESCEND_TIME 10

View File

@@ -3,38 +3,16 @@
// Flight control // Flight control
#include "config.h"
#include "flix.h"
#include "vector.h" #include "vector.h"
#include "quaternion.h" #include "quaternion.h"
#include "pid.h" #include "pid.h"
#include "lpf.h" #include "lpf.h"
#include "util.h" #include "util.h"
#define PITCHRATE_P 0.05 extern const int RAW = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
#define PITCHRATE_I 0.2
#define PITCHRATE_D 0.001
#define PITCHRATE_I_LIM 0.3
#define ROLLRATE_P PITCHRATE_P
#define ROLLRATE_I PITCHRATE_I
#define ROLLRATE_D PITCHRATE_D
#define ROLLRATE_I_LIM PITCHRATE_I_LIM
#define YAWRATE_P 0.3
#define YAWRATE_I 0.0
#define YAWRATE_D 0.0
#define YAWRATE_I_LIM 0.3
#define ROLL_P 6
#define ROLL_I 0
#define ROLL_D 0
#define PITCH_P ROLL_P
#define PITCH_I ROLL_I
#define PITCH_D ROLL_D
#define YAW_P 3
#define PITCHRATE_MAX radians(360)
#define ROLLRATE_MAX radians(360)
#define YAWRATE_MAX radians(300)
#define TILT_MAX radians(30)
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
const int RAW = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
int mode = STAB; int mode = STAB;
bool armed = false; bool armed = false;

View File

@@ -3,6 +3,8 @@
// Attitude estimation from gyro and accelerometer // Attitude estimation from gyro and accelerometer
#include "config.h"
#include "flix.h"
#include "quaternion.h" #include "quaternion.h"
#include "vector.h" #include "vector.h"
#include "lpf.h" #include "lpf.h"

90
flix/flix.h Normal file
View File

@@ -0,0 +1,90 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// All-in-one header file
#pragma once
#include <Arduino.h>
#include "vector.h"
#include "quaternion.h"
extern float t, dt;
extern float loopRate;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
extern Vector gyro, acc;
extern Vector rates;
extern Quaternion attitude;
extern bool landed;
extern int mode;
extern bool armed;
extern Quaternion attitudeTarget;
extern Vector ratesTarget, ratesExtra, torqueTarget;
extern float thrustTarget;
extern float motors[4];
void print(const char* format, ...);
void pause(float duration);
void doCommand(String str, bool echo = false);
void handleInput();
void control();
void interpretControls();
void controlAttitude();
void controlRates();
void controlTorque();
const char *getModeName();
void estimate();
void applyGyro();
void applyAcc();
void setupIMU();
void configureIMU();
void readIMU();
void rotateIMU(Vector& data);
void calibrateGyroOnce();
void calibrateAccel();
void calibrateAccelOnce();
void printIMUCalibration();
void printIMUInfo();
void setupLED();
void setLED(bool on);
void blinkLED();
void prepareLogData();
void logData();
void printLogHeader();
void printLogData();
void processMavlink();
void sendMavlink();
void sendMessage(const void *msg);
void receiveMavlink();
void handleMavlink(const void *_msg);
void mavlinkPrint(const char* str);
void sendMavlinkPrint();
void setupMotors();
int getDutyCycle(float value);
void sendMotors();
bool motorsActive();
void testMotor(int n);
void setupParameters();
int parametersCount();
const char *getParameterName(int index);
float getParameter(int index);
float getParameter(const char *name);
bool setParameter(const char *name, const float value);
void syncParameters();
void printParameters();
void resetParameters();
void setupRC();
bool readRC();
void normalizeRC();
void calibrateRC();
void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const char *str);
void printRCCalibration();
void failsafe();
void rcLossFailsafe();
void descend();
void autoFailsafe();
void step();
void computeLoopRate();
void setupWiFi();
void sendWiFi(const uint8_t *buf, int len);
int receiveWiFi(uint8_t *buf, int len);

View File

@@ -3,17 +3,11 @@
// Main firmware file // Main firmware file
#include "config.h"
#include "vector.h" #include "vector.h"
#include "quaternion.h" #include "quaternion.h"
#include "util.h" #include "util.h"
#include "flix.h"
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() { void setup() {
Serial.begin(115200); Serial.begin(115200);
@@ -23,7 +17,9 @@ void setup() {
setupLED(); setupLED();
setupMotors(); setupMotors();
setLED(true); setLED(true);
#if WIFI_ENABLED
setupWiFi(); setupWiFi();
#endif
setupIMU(); setupIMU();
setupRC(); setupRC();
setLED(false); setLED(false);
@@ -38,7 +34,9 @@ void loop() {
control(); control();
sendMotors(); sendMotors();
handleInput(); handleInput();
#if WIFI_ENABLED
processMavlink(); processMavlink();
#endif
logData(); logData();
syncParameters(); syncParameters();
} }

View File

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

View File

@@ -3,6 +3,8 @@
// Board's LED control // Board's LED control
#include <Arduino.h>
#define BLINK_PERIOD 500000 #define BLINK_PERIOD 500000
#ifndef LED_BUILTIN #ifndef LED_BUILTIN

View File

@@ -3,6 +3,7 @@
// In-RAM logging // In-RAM logging
#include "flix.h"
#include "vector.h" #include "vector.h"
#include "util.h" #include "util.h"

View File

@@ -5,6 +5,8 @@
#pragma once #pragma once
#include <Arduino.h>
template <typename T> // Using template to make the filter usable for scalar and vector values template <typename T> // Using template to make the filter usable for scalar and vector values
class LowPassFilter { class LowPassFilter {
public: public:
@@ -14,6 +16,15 @@ public:
LowPassFilter(float alpha): alpha(alpha) {}; LowPassFilter(float alpha): alpha(alpha) {};
T update(const T input) { T update(const T input) {
if (alpha == 1) { // filter disabled
return input;
}
if (!initialized) {
output = input;
initialized = true;
}
return output += alpha * (input - output); return output += alpha * (input - output);
} }
@@ -22,6 +33,9 @@ public:
} }
void reset() { void reset() {
output = T(); // set to zero initialized = false;
} }
private:
bool initialized = false;
}; };

View File

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

View File

@@ -4,25 +4,17 @@
// Motors output control using MOSFETs // Motors output control using MOSFETs
// In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400) // In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400)
#include <Arduino.h>
#include "config.h"
#include "flix.h"
#include "util.h" #include "util.h"
#define MOTOR_0_PIN 12 // rear left
#define MOTOR_1_PIN 13 // rear right
#define MOTOR_2_PIN 14 // front right
#define MOTOR_3_PIN 15 // front left
#define PWM_FREQUENCY 78000
#define PWM_RESOLUTION 10
#define PWM_STOP 0
#define PWM_MIN 0
#define PWM_MAX 1000000 / PWM_FREQUENCY
float motors[4]; // normalized motor thrusts in range [0..1] float motors[4]; // normalized motor thrusts in range [0..1]
const int MOTOR_REAR_LEFT = 0; extern const int MOTOR_REAR_LEFT = 0;
const int MOTOR_REAR_RIGHT = 1; extern const int MOTOR_REAR_RIGHT = 1;
const int MOTOR_FRONT_RIGHT = 2; extern const int MOTOR_FRONT_RIGHT = 2;
const int MOTOR_FRONT_LEFT = 3; extern const int MOTOR_FRONT_LEFT = 3;
void setupMotors() { void setupMotors() {
print("Setup Motors\n"); print("Setup Motors\n");

View File

@@ -4,25 +4,29 @@
// Parameters storage in flash memory // Parameters storage in flash memory
#include <Preferences.h> #include <Preferences.h>
#include "flix.h"
#include "pid.h"
#include "lpf.h"
#include "util.h" #include "util.h"
extern float channelZero[16]; extern float channelZero[16];
extern float channelMax[16]; extern float channelMax[16];
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel; extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern int wifiMode, udpLocalPort, udpRemotePort; extern float tiltMax;
extern float rcLossTimeout, descendTime; extern PID rollPID, pitchPID, yawPID;
extern PID rollRatePID, pitchRatePID, yawRatePID;
extern Vector maxRate;
extern Vector imuRotation;
extern Vector accBias, accScale;
extern float accWeight;
extern LowPassFilter<Vector> ratesFilter;
Preferences storage; Preferences storage;
struct Parameter { struct Parameter {
const char *name; // max length is 15 (Preferences key limit) const char *name; // max length is 15 (Preferences key limit)
bool integer; float *variable;
union { float *f; int *i; }; // pointer to variable float value; // cache
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[] = { Parameter parameters[] = {
@@ -59,7 +63,6 @@ Parameter parameters[] = {
{"IMU_ACC_SCALE_X", &accScale.x}, {"IMU_ACC_SCALE_X", &accScale.x},
{"IMU_ACC_SCALE_Y", &accScale.y}, {"IMU_ACC_SCALE_Y", &accScale.y},
{"IMU_ACC_SCALE_Z", &accScale.z}, {"IMU_ACC_SCALE_Z", &accScale.z},
{"IMU_GYRO_BIAS_A", &gyroBiasFilter.alpha},
// estimate // estimate
{"EST_ACC_WEIGHT", &accWeight}, {"EST_ACC_WEIGHT", &accWeight},
{"EST_RATES_LPF_A", &ratesFilter.alpha}, {"EST_RATES_LPF_A", &ratesFilter.alpha},
@@ -85,17 +88,6 @@ Parameter parameters[] = {
{"RC_THROTTLE", &throttleChannel}, {"RC_THROTTLE", &throttleChannel},
{"RC_YAW", &yawChannel}, {"RC_YAW", &yawChannel},
{"RC_MODE", &modeChannel}, {"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() { void setupParameters() {
@@ -103,10 +95,10 @@ void setupParameters() {
// 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)) {
storage.putFloat(parameter.name, parameter.getValue()); // store default value storage.putFloat(parameter.name, *parameter.variable);
} }
parameter.setValue(storage.getFloat(parameter.name, 0)); *parameter.variable = storage.getFloat(parameter.name, *parameter.variable);
parameter.cache = parameter.getValue(); parameter.value = *parameter.variable;
} }
} }
@@ -121,13 +113,13 @@ const char *getParameterName(int index) {
float getParameter(int index) { float getParameter(int index) {
if (index < 0 || index >= parametersCount()) return NAN; if (index < 0 || index >= parametersCount()) return NAN;
return parameters[index].getValue(); return *parameters[index].variable;
} }
float getParameter(const char *name) { float getParameter(const char *name) {
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
if (strcasecmp(parameter.name, name) == 0) { if (strcmp(parameter.name, name) == 0) {
return parameter.getValue(); return *parameter.variable;
} }
} }
return NAN; return NAN;
@@ -135,9 +127,8 @@ float getParameter(const char *name) {
bool setParameter(const char *name, const float value) { bool setParameter(const char *name, const float value) {
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
if (strcasecmp(parameter.name, name) == 0) { if (strcmp(parameter.name, name) == 0) {
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf *parameter.variable = value;
parameter.setValue(value);
return true; return true;
} }
} }
@@ -150,18 +141,16 @@ void syncParameters() {
if (motorsActive()) return; // don't use flash while flying, it may cause a delay if (motorsActive()) return; // don't use flash while flying, it may cause a delay
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
if (parameter.getValue() == parameter.cache) continue; // no change if (parameter.value == *parameter.variable) continue;
if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NaN if (isnan(parameter.value) && isnan(*parameter.variable)) continue; // handle NAN != NAN
if (isinf(parameter.getValue()) && isinf(parameter.cache)) continue; // both are Inf storage.putFloat(parameter.name, *parameter.variable);
parameter.value = *parameter.variable;
storage.putFloat(parameter.name, parameter.getValue());
parameter.cache = parameter.getValue(); // update cache
} }
} }
void printParameters() { void printParameters() {
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
print("%s = %g\n", parameter.name, parameter.getValue()); print("%s = %g\n", parameter.name, *parameter.variable);
} }
} }

View File

@@ -5,6 +5,8 @@
#pragma once #pragma once
#include "Arduino.h"
#include "flix.h"
#include "lpf.h" #include "lpf.h"
class PID { class PID {

View File

@@ -5,6 +5,7 @@
#pragma once #pragma once
#include <Arduino.h>
#include "vector.h" #include "vector.h"
class Quaternion : public Printable { class Quaternion : public Printable {

View File

@@ -13,10 +13,10 @@ float channelZero[16]; // calibration zero values
float 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; // time of the last controls update (0 when no RC)
// Channels mapping (nan means not assigned): // Channels mapping (using float to store in parameters):
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN; float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
void setupRC() { void setupRC() {

View File

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

View File

@@ -3,6 +3,9 @@
// Time related functions // Time related functions
#include "Arduino.h"
#include "flix.h"
float t = NAN; // current time, s float t = NAN; // current time, s
float dt; // time delta with the previous step, s float dt; // time delta with the previous step, s
float loopRate; // Hz float loopRate; // Hz

View File

@@ -8,24 +8,24 @@
#include <math.h> #include <math.h>
#include <soc/soc.h> #include <soc/soc.h>
#include <soc/rtc_cntl_reg.h> #include <soc/rtc_cntl_reg.h>
#include "flix.h"
const float ONE_G = 9.80665; const float ONE_G = 9.80665;
extern float t;
float mapf(float x, float in_min, float in_max, float out_min, float out_max) { inline float mapf(float x, float in_min, float in_max, float out_min, float out_max) {
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
} }
bool invalid(float x) { inline bool invalid(float x) {
return !isfinite(x); return !isfinite(x);
} }
bool valid(float x) { inline bool valid(float x) {
return isfinite(x); return isfinite(x);
} }
// Wrap angle to [-PI, PI) // Wrap angle to [-PI, PI)
float wrapAngle(float angle) { inline float wrapAngle(float angle) {
angle = fmodf(angle, 2 * PI); angle = fmodf(angle, 2 * PI);
if (angle > PI) { if (angle > PI) {
angle -= 2 * PI; angle -= 2 * PI;
@@ -36,12 +36,12 @@ float wrapAngle(float angle) {
} }
// Disable reset on low voltage // Disable reset on low voltage
void disableBrownOut() { inline void disableBrownOut() {
REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA); REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA);
} }
// Trim and split string by spaces // Trim and split string by spaces
void splitString(String& str, String& token0, String& token1, String& token2) { inline void splitString(String& str, String& token0, String& token1, String& token2) {
str.trim(); str.trim();
char chars[str.length() + 1]; char chars[str.length() + 1];
str.toCharArray(chars, str.length() + 1); str.toCharArray(chars, str.length() + 1);

View File

@@ -5,6 +5,8 @@
#pragma once #pragma once
#include <Arduino.h>
class Vector : public Printable { class Vector : public Printable {
public: public:
float x, y, z; float x, y, z;
@@ -123,5 +125,5 @@ public:
} }
}; };
Vector operator * (const float a, const Vector& b) { return b * a; } inline Vector operator * (const float a, const Vector& b) { return b * a; }
Vector operator + (const float a, const Vector& b) { return b + a; } inline Vector operator + (const float a, const Vector& b) { return b + a; }

48
flix/wifi.cpp Normal file
View File

@@ -0,0 +1,48 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Wi-Fi support
#include "config.h"
#include "flix.h"
#if WIFI_ENABLED
#include <WiFi.h>
#include <WiFiAP.h>
#include <WiFiUdp.h>
WiFiUDP udp;
extern bool mavlinkConnected;
void setupWiFi() {
print("Setup Wi-Fi\n");
WiFi.softAP(WIFI_SSID, WIFI_PASSWORD);
udp.begin(WIFI_UDP_PORT);
}
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);
udp.write(buf, len);
udp.endPacket();
}
int receiveWiFi(uint8_t *buf, int len) {
udp.parsePacket();
return udp.read(buf, len);
}
void printWiFiInfo() {
print("MAC: %s\n", WiFi.softAPmacAddress().c_str());
print("SSID: %s\n", WiFi.softAPSSID().c_str());
print("Password: %s\n", WIFI_PASSWORD);
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());
print("MAVLink connected: %d\n", mavlinkConnected);
}
#endif

View File

@@ -1,76 +0,0 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Wi-Fi communication
#include <WiFi.h>
#include <WiFiAP.h>
#include <WiFiUdp.h>
#include "Preferences.h"
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");
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.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: ***\n");
print("Clients: %d\n", WiFi.softAPgetStationNum());
print("IP: %s\n", WiFi.softAPIP().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);
}
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,9 +10,23 @@ list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}")
set(FLIX_SOURCE_DIR ../flix) set(FLIX_SOURCE_DIR ../flix)
include_directories(${FLIX_SOURCE_DIR}) include_directories(${FLIX_SOURCE_DIR})
set(FLIX_SOURCE_DIR ../flix)
include_directories(${FLIX_SOURCE_DIR})
set(FLIX_SOURCES
${FLIX_SOURCE_DIR}/cli.cpp
${FLIX_SOURCE_DIR}/control.cpp
${FLIX_SOURCE_DIR}/estimate.cpp
${FLIX_SOURCE_DIR}/safety.cpp
${FLIX_SOURCE_DIR}/log.cpp
${FLIX_SOURCE_DIR}/mavlink.cpp
${FLIX_SOURCE_DIR}/motors.cpp
${FLIX_SOURCE_DIR}/parameters.cpp
${FLIX_SOURCE_DIR}/rc.cpp
${FLIX_SOURCE_DIR}/time.cpp
)
set(CMAKE_BUILD_TYPE RelWithDebInfo) set(CMAKE_BUILD_TYPE RelWithDebInfo)
add_library(flix SHARED simulator.cpp) add_library(flix SHARED simulator.cpp ${FLIX_SOURCES})
target_link_libraries(flix ${GAZEBO_LIBRARIES} ${SDL2_LIBRARIES}) target_link_libraries(flix ${GAZEBO_LIBRARIES} ${SDL2_LIBRARIES})
target_include_directories(flix PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) target_include_directories(flix PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
target_compile_options(flix PRIVATE -Wno-address-of-packed-member) # disable unneeded mavlink warnings target_compile_options(flix PRIVATE -Wno-address-of-packed-member) # disable unneeded mavlink warnings

View File

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

View File

@@ -18,18 +18,6 @@
#include "Arduino.h" #include "Arduino.h"
#include "flix.h" #include "flix.h"
#include "cli.ino"
#include "control.ino"
#include "estimate.ino"
#include "safety.ino"
#include "log.ino"
#include "lpf.h"
#include "mavlink.ino"
#include "motors.ino"
#include "parameters.ino"
#include "rc.ino"
#include "time.ino"
using ignition::math::Vector3d; using ignition::math::Vector3d;
using namespace gazebo; using namespace gazebo;
using namespace std; using namespace std;

View File

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

View File

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

View File

@@ -92,17 +92,17 @@ Full list of events:
|-----|-----------|----------------| |-----|-----------|----------------|
|`connected`|Connected to the drone|| |`connected`|Connected to the drone||
|`disconnected`|Connection is lost|| |`disconnected`|Connection is lost||
|`armed`|Armed state update|Armed state *(bool)*| |`armed`|Armed state update|Armed state (*bool*)|
|`mode`|Flight mode update|Flight mode *(str)*| |`mode`|Flight mode update|Flight mode (*str*)|
|`landed`|Landed state update|Landed state *(bool)*| |`landed`|Landed state update|Landed state (*bool*)|
|`print`|The drone prints text to the console|Text| |`print`|The drone prints text to the console|Text|
|`attitude`|Attitude update|Attitude quaternion *(list)*| |`attitude`|Attitude update|Attitude quaternion (*list*)|
|`attitude_euler`|Attitude update|Euler angles *(list)*| |`attitude_euler`|Attitude update|Euler angles (*list*)|
|`rates`|Angular rates update|Angular rates *(list)*| |`rates`|Angular rates update|Angular rates (*list*)|
|`channels`|Raw RC channels update|Raw RC channels *(list)*| |`channels`|Raw RC channels update|Raw RC channels (*list*)|
|`motors`|Motor outputs update|Motor outputs *(list)*| |`motors`|Motor outputs update|Motor outputs (*list*)|
|`acc`|Accelerometer update|Accelerometer output *(list)*| |`acc`|Accelerometer update|Accelerometer output (*list*)|
|`gyro`|Gyroscope update|Gyroscope output *(list)*| |`gyro`|Gyroscope update|Gyroscope output (*list*)|
|`mavlink`|Received MAVLink message|Message object| |`mavlink`|Received MAVLink message|Message object|
|`mavlink.<message_name>`|Received specific MAVLink message|Message object| |`mavlink.<message_name>`|Received specific MAVLink message|Message object|
|`mavlink.<message_id>`|Received specific MAVLink message|Message object| |`mavlink.<message_id>`|Received specific MAVLink message|Message object|
@@ -277,3 +277,7 @@ logger = logging.getLogger('flix')
logger.setLevel(logging.DEBUG) # be more verbose logger.setLevel(logging.DEBUG) # be more verbose
logger.setLevel(logging.WARNING) # be less verbose logger.setLevel(logging.WARNING) # be less verbose
``` ```
## Stability
The library is in development stage. The API is not stable.