Compare commits
34 Commits
master
...
school-548
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
3104410bb9 | ||
|
|
1551d096fc | ||
|
|
80f23ab016 | ||
|
|
e6fb264499 | ||
|
|
4d0871b00b | ||
|
|
f1b993d719 | ||
|
|
2e7330d2f5 | ||
|
|
e22df3ab01 | ||
|
|
8484854576 | ||
|
|
b9d5624f30 | ||
|
|
205270b8ec | ||
|
|
f1bedb2b10 | ||
|
|
46d1749a8c | ||
|
|
66fb7a13c3 | ||
|
|
cfef3b9c36 | ||
|
|
1338a9ea79 | ||
|
|
b60757ec1d | ||
|
|
491e054534 | ||
|
|
3eaf24f89d | ||
|
|
dc09459613 | ||
|
|
59c9ea8cb3 | ||
|
|
5bdd46c6ad | ||
|
|
5b37c87166 | ||
|
|
48ba55aa7e | ||
|
|
2708c1eafd | ||
|
|
b2c9dfe6ef | ||
|
|
0579118dd5 | ||
|
|
05818349d8 | ||
|
|
6c1d651caa | ||
|
|
49a0aa7036 | ||
|
|
bf9eeb90a4 | ||
|
|
96836b2e3e | ||
|
|
82d9d3570d | ||
|
|
d7f8c8d934 |
2
.github/workflows/build.yml
vendored
@@ -25,6 +25,8 @@ 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
|
||||
|
||||
|
||||
11
.github/workflows/tools.yml
vendored
@@ -46,3 +46,14 @@ jobs:
|
||||
echo -e "t,x,y,z\n0,1,2,3\n1,4,5,6" > log.csv
|
||||
./csv_to_mcap.py log.csv
|
||||
test $(stat -c %s log.mcap) -eq 883
|
||||
|
||||
sloc:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install cloc
|
||||
run: sudo apt-get install -y cloc
|
||||
- name: Firmware source lines count
|
||||
run: cloc --by-file-by-lang flix
|
||||
- name: Overall source lines count
|
||||
run: cloc --by-file-by-lang --exclude-ext=svg,dae,css,hbs,md,json,yaml,yml,toml .
|
||||
|
||||
@@ -7,8 +7,6 @@
|
||||
"MD024": false,
|
||||
"MD033": false,
|
||||
"MD034": false,
|
||||
"MD040": false,
|
||||
"MD059": false,
|
||||
"MD044": {
|
||||
"html_elements": false,
|
||||
"code_blocks": false,
|
||||
@@ -66,6 +64,5 @@
|
||||
"PX4"
|
||||
]
|
||||
},
|
||||
"MD045": false,
|
||||
"MD060": false
|
||||
"MD045": false
|
||||
}
|
||||
|
||||
54
.vscode/c_cpp_properties.json
vendored
@@ -6,18 +6,19 @@
|
||||
"${workspaceFolder}/flix",
|
||||
"${workspaceFolder}/gazebo",
|
||||
"${workspaceFolder}/tools/**",
|
||||
"~/.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/**",
|
||||
"~/.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",
|
||||
"~/Arduino/libraries/**",
|
||||
"/usr/include/gazebo-11/",
|
||||
"/usr/include/ignition/math6/"
|
||||
],
|
||||
"forcedInclude": [
|
||||
"${workspaceFolder}/.vscode/intellisense.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",
|
||||
"~/.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",
|
||||
"${workspaceFolder}/flix/cli.ino",
|
||||
"${workspaceFolder}/flix/control.ino",
|
||||
"${workspaceFolder}/flix/estimate.ino",
|
||||
@@ -30,10 +31,9 @@
|
||||
"${workspaceFolder}/flix/rc.ino",
|
||||
"${workspaceFolder}/flix/time.ino",
|
||||
"${workspaceFolder}/flix/wifi.ino",
|
||||
"${workspaceFolder}/flix/parameters.ino",
|
||||
"${workspaceFolder}/flix/safety.ino"
|
||||
"${workspaceFolder}/flix/parameters.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",
|
||||
"cppStandard": "c++17",
|
||||
"defines": [
|
||||
@@ -53,18 +53,19 @@
|
||||
"name": "Mac",
|
||||
"includePath": [
|
||||
"${workspaceFolder}/flix",
|
||||
"~/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/**",
|
||||
"~/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",
|
||||
"~/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.3.6/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/cores/esp32/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",
|
||||
@@ -77,10 +78,9 @@
|
||||
"${workspaceFolder}/flix/rc.ino",
|
||||
"${workspaceFolder}/flix/time.ino",
|
||||
"${workspaceFolder}/flix/wifi.ino",
|
||||
"${workspaceFolder}/flix/parameters.ino",
|
||||
"${workspaceFolder}/flix/safety.ino"
|
||||
"${workspaceFolder}/flix/parameters.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",
|
||||
"cppStandard": "c++17",
|
||||
"defines": [
|
||||
@@ -103,16 +103,17 @@
|
||||
"${workspaceFolder}/flix",
|
||||
"${workspaceFolder}/gazebo",
|
||||
"${workspaceFolder}/tools/**",
|
||||
"~/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/**",
|
||||
"~/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",
|
||||
"~/Documents/Arduino/libraries/**"
|
||||
],
|
||||
"forcedInclude": [
|
||||
"${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.3.6/variants/d1_mini32/pins_arduino.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",
|
||||
"${workspaceFolder}/flix/cli.ino",
|
||||
"${workspaceFolder}/flix/control.ino",
|
||||
"${workspaceFolder}/flix/estimate.ino",
|
||||
@@ -125,10 +126,9 @@
|
||||
"${workspaceFolder}/flix/rc.ino",
|
||||
"${workspaceFolder}/flix/time.ino",
|
||||
"${workspaceFolder}/flix/wifi.ino",
|
||||
"${workspaceFolder}/flix/parameters.ino",
|
||||
"${workspaceFolder}/flix/safety.ino"
|
||||
"${workspaceFolder}/flix/parameters.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",
|
||||
"cppStandard": "c++17",
|
||||
"defines": [
|
||||
|
||||
4
Makefile
@@ -13,10 +13,10 @@ monitor:
|
||||
|
||||
dependencies .dependencies:
|
||||
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 install "FlixPeriph"
|
||||
arduino-cli lib install "MAVLink"@2.0.25
|
||||
arduino-cli lib install "MAVLink"@2.0.16
|
||||
touch .dependencies
|
||||
|
||||
gazebo/build cmake: gazebo/CMakeLists.txt
|
||||
|
||||
23
README.md
@@ -1,9 +1,6 @@
|
||||
<!-- markdownlint-disable MD041 -->
|
||||
# Flix
|
||||
|
||||
<p align="center">
|
||||
<img src="docs/img/flix.svg" width=180 alt="Flix logo"><br>
|
||||
<b>Flix</b> (<i>flight + X</i>) — open source ESP32-based quadcopter made from scratch.
|
||||
</p>
|
||||
**Flix** (*flight + X*) — open source ESP32-based quadcopter made from scratch.
|
||||
|
||||
<table>
|
||||
<tr>
|
||||
@@ -21,13 +18,15 @@
|
||||
* 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 for scripting and automatic flights.
|
||||
* Python library.
|
||||
* 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
|
||||
|
||||
@@ -138,10 +137,10 @@ You can see a user-contributed [variant of complete circuit diagram](https://mir
|
||||
|
||||
|Motor|Position|Direction|Prop type|Motor wires|GPIO|
|
||||
|-|-|-|-|-|-|
|
||||
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 *(TDI)*|
|
||||
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 *(TCK)*|
|
||||
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 *(TMS)*|
|
||||
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 *(TD0)*|
|
||||
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 (*TDI*)|
|
||||
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 (*TCK*)|
|
||||
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 (*TMS*)|
|
||||
|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).
|
||||
Counter-clockwise motors have black & white wires correspond to propeller type B.
|
||||
|
||||
@@ -41,10 +41,10 @@ Motors connection table:
|
||||
|
||||
|Motor|Position|Direction|Prop type|Motor wires|GPIO|
|
||||
|-|-|-|-|-|-|
|
||||
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 *(TDI)*|
|
||||
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 *(TCK)*|
|
||||
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 *(TMS)*|
|
||||
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 *(TD0)*|
|
||||
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 (*TDI*)|
|
||||
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 (*TCK*)|
|
||||
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 (*TMS*)|
|
||||
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 (*TD0*)|
|
||||
|
||||
## Motors tightening
|
||||
|
||||
|
||||
@@ -35,7 +35,7 @@
|
||||
|
||||
### Подсистема управления
|
||||
|
||||
Состояние органов управления обрабатывается в функции `interpretControls()` и преобразуется в **команду управления**, которая включает следующее:
|
||||
Состояние органов управления обрабатывается в функции `interpretControls()` и преобразуется в *команду управления*, которая включает следующее:
|
||||
|
||||
* `attitudeTarget` *(Quaternion)* — целевая ориентация дрона.
|
||||
* `ratesTarget` *(Vector)* — целевые угловые скорости, *рад/с*.
|
||||
|
||||
@@ -110,7 +110,7 @@ float angle = Vector::angleBetween(a, b); // 1.57 (90 градусов)
|
||||
|
||||
#### Скалярное произведение
|
||||
|
||||
Скалярное произведение векторов *(dot product)* — это произведение длин двух векторов на косинус угла между ними. В математике оно обозначается знаком `·` или слитным написанием векторов. Интуитивно, результат скалярного произведения показывает, насколько два вектора *сонаправлены*.
|
||||
Скалярное произведение векторов (*dot product*) — это произведение длин двух векторов на косинус угла между ними. В математике оно обозначается знаком `·` или слитным написанием векторов. Интуитивно, результат скалярного произведения показывает, насколько два вектора *сонаправлены*.
|
||||
|
||||
В Flix используется статический метод `Vector::dot()`:
|
||||
|
||||
@@ -124,7 +124,7 @@ float dotProduct = Vector::dot(a, b); // 32
|
||||
|
||||
#### Векторное произведение
|
||||
|
||||
Векторное произведение *(cross product)* позволяет найти вектор, перпендикулярный двум другим векторам. В математике оно обозначается знаком `×`, а в прошивке используется статический метод `Vector::cross()`:
|
||||
Векторное произведение (*cross product*) позволяет найти вектор, перпендикулярный двум другим векторам. В математике оно обозначается знаком `×`, а в прошивке используется статический метод `Vector::cross()`:
|
||||
|
||||
```cpp
|
||||
Vector a(1, 2, 3);
|
||||
@@ -144,9 +144,9 @@ Vector crossProduct = Vector::cross(a, b); // -3, 6, -3
|
||||
|
||||
В прошивке углы Эйлера сохраняются в обычный объект `Vector` (хоть и, строго говоря, не являются вектором):
|
||||
|
||||
* Угол по крену *(roll)* — `vector.x`.
|
||||
* Угол по тангажу *(pitch)* — `vector.y`.
|
||||
* Угол по рысканию *(yaw)* — `vector.z`.
|
||||
* Угол по крену (*roll*) — `vector.x`.
|
||||
* Угол по тангажу (*pitch*) — `vector.y`.
|
||||
* Угол по рысканию (*yaw*) — `vector.z`.
|
||||
|
||||
Особенности углов Эйлера:
|
||||
|
||||
@@ -162,8 +162,8 @@ Vector crossProduct = Vector::cross(a, b); // -3, 6, -3
|
||||
|
||||
Помимо углов Эйлера, любую ориентацию в трехмерном пространстве можно представить в виде вращения вокруг некоторой оси на некоторый угол. В геометрии это доказывается, как **теорема вращения Эйлера**. В таком представлении ориентация задается двумя величинами:
|
||||
|
||||
* **Ось вращения** *(axis)* — единичный вектор, определяющий ось вращения.
|
||||
* **Угол поворота** *(angle* или *θ)* — угол, на который нужно повернуть объект вокруг этой оси.
|
||||
* **Ось вращения** (*axis*) — единичный вектор, определяющий ось вращения.
|
||||
* **Угол поворота** (*angle* или *θ*) — угол, на который нужно повернуть объект вокруг этой оси.
|
||||
|
||||
В 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>
|
||||
</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) \\]
|
||||
|
||||
|
||||
@@ -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 the IMU");
|
||||
Serial.println("Failed to initialize 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 the IMU");
|
||||
Serial.println("Failed to initialize 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,16 +172,16 @@ imu.setGyroRange(imu.GYRO_RANGE_2000DPS);
|
||||
IMU InvenSense могут фильтровать измерения на аппаратном уровне при помощи фильтра нижних частот (LPF). Flix реализует собственный фильтр для гироскопа, чтобы иметь больше гибкости при поддержке разных IMU. Поэтому для встроенного LPF устанавливается максимальная частота среза:
|
||||
|
||||
```cpp
|
||||
imu.setDLPF(imu.DLPF_MAX);
|
||||
IMU.setDLPF(IMU.DLPF_MAX);
|
||||
```
|
||||
|
||||
## Калибровка гироскопа
|
||||
|
||||
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения *(bias)* и случайный шум *(noise)*:
|
||||
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения (*bias*) и случайный шум (*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 <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 the IMU");
|
||||
Serial.println("Failed to initialize 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;
|
||||
|
||||
@@ -38,13 +38,13 @@ Utility files:
|
||||
|
||||
### Control subsystem
|
||||
|
||||
Pilot inputs are interpreted in `interpretControls()`, and then converted to the **control command**, which consists of the following:
|
||||
Pilot inputs are interpreted in `interpretControls()`, and then converted to the *control command*, which consists of the following:
|
||||
|
||||
* `attitudeTarget` *(Quaternion)* — target attitude of the drone.
|
||||
* `ratesTarget` *(Vector)* — target angular rates, *rad/s*.
|
||||
* `ratesExtra` *(Vector)* — additional (feed-forward) angular rates, used for yaw rate control in STAB mode, *rad/s*.
|
||||
* `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].
|
||||
* `thrustTarget` *(float)* — collective thrust target, range [0, 1].
|
||||
|
||||
Control command is handled in `controlAttitude()`, `controlRates()`, `controlTorque()` functions. Each function may be skipped if the corresponding control target is set to `NAN`.
|
||||
|
||||
@@ -62,11 +62,6 @@ print("Test value: %.2f\n", testValue);
|
||||
|
||||
In order to add a console command, modify the `doCommand()` function in `cli.ino` file.
|
||||
|
||||
> [!IMPORTANT]
|
||||
> Avoid using delays in in-flight commands, it will **crash** the drone! (The design is one-threaded.)
|
||||
>
|
||||
> For on-the-ground commands, use `pause()` function, instead of `delay()`. This function allows to pause in a way that MAVLink connection will continue working.
|
||||
|
||||
## Building the firmware
|
||||
|
||||
See build instructions in [usage.md](usage.md).
|
||||
|
||||
@@ -1,38 +0,0 @@
|
||||
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 734.86 378.46">
|
||||
<defs>
|
||||
<style>
|
||||
.a {
|
||||
fill: none;
|
||||
stroke: #d5d5d5;
|
||||
stroke-miterlimit: 10;
|
||||
stroke-width: 31px;
|
||||
}
|
||||
|
||||
.b {
|
||||
fill: #c1c1c1;
|
||||
}
|
||||
|
||||
.c {
|
||||
fill: #ff9400;
|
||||
}
|
||||
|
||||
.d {
|
||||
fill: #d5d5d5;
|
||||
}
|
||||
</style>
|
||||
</defs>
|
||||
<g>
|
||||
<g>
|
||||
<line class="a" x1="448.78" y1="294.23" x2="648.77" y2="93.24"/>
|
||||
<line class="a" x1="449.78" y1="94.24" x2="649.77" y2="295.23"/>
|
||||
<circle class="b" cx="549.27" cy="193.73" r="41.5"/>
|
||||
<circle class="c" cx="449.35" cy="93.74" r="77.95"/>
|
||||
<circle class="c" cx="648.89" cy="93.53" r="77.95"/>
|
||||
<circle class="c" cx="647.89" cy="294.51" r="77.95"/>
|
||||
<circle class="c" cx="448.9" cy="294.51" r="77.95"/>
|
||||
</g>
|
||||
<path class="d" d="M8,161.93q0-17.85,22.36-17.85h4.81V100.57Q35.17,8.49,131.23,8h1q36.87,0,47.31,7.48L181,17.41l1,2.41V50q0,12.32-5.82,12.31-2.43,0-7.4-4.64t-14.19-9a48.63,48.63,0,0,0-21.22-4.41q-12,0-19.17,3.5a18.85,18.85,0,0,0-9.82,10.62,67.35,67.35,0,0,0-3.52,12.06,82.52,82.52,0,0,0-.85,13.39v60.32h27.28q10.86,0,16.05,5.43a17.52,17.52,0,0,1,5.19,12.42,22.5,22.5,0,0,1-1.21,7.36q-1.22,3.51-6.64,7.24t-14.36,3.74H101.64V344.82a56,56,0,0,1-.61,9.65,37.8,37.8,0,0,1-2.56,7.6,11.83,11.83,0,0,1-6.94,6.4q-5,1.93-13.51,1.93H57.08q-10.47,0-15.7-4.71t-5.73-8.44a77.31,77.31,0,0,1-.48-9.53V180.27H29.4Q8,180.27,8,161.93Z"/>
|
||||
<path class="d" d="M201.21,348.2V37q0-23.16,20.86-23.4h22.81q22.8,0,22.8,22.44V346.27a68.92,68.92,0,0,1-.49,9.41,22.59,22.59,0,0,1-2.42,7.12,11.48,11.48,0,0,1-6.67,5.43,47.78,47.78,0,0,1-12.74,2.17H225q-11.4,0-17.58-4.47T201.21,348.2Z"/>
|
||||
<path class="d" d="M284.9,61.08V36.47a40.39,40.39,0,0,1,1.7-12.91,11.36,11.36,0,0,1,6.18-7,25.27,25.27,0,0,1,6.68-2.3c1.45-.15,4-.4,7.76-.72h25.23q10.43,0,16.73,4.7t6.31,18.22V62.05a27.94,27.94,0,0,1-.85,7.11,23,23,0,0,1-2.06,5.43,20,20,0,0,1-2.91,4,10,10,0,0,1-3.52,2.54c-1.21.48-2.54,1-4,1.44a11.53,11.53,0,0,1-3.4.73,13.71,13.71,0,0,0-3.15.48H307.7q-10.43,0-16.61-4.7T284.9,61.08Zm1.94,284.71V166.28q0-22.2,21.83-22.2h20.38q10.92,0,16.62,4t6.67,8.45a60.47,60.47,0,0,1,1,12.18V348.2q0,22.2-21.83,22.2H308.67q-10.43,0-15.64-4.95t-5.7-8.81A90.93,90.93,0,0,1,286.84,345.79Z"/>
|
||||
</g>
|
||||
</svg>
|
||||
|
Before Width: | Height: | Size: 2.2 KiB |
|
Before Width: | Height: | Size: 23 KiB |
|
Before Width: | Height: | Size: 18 KiB |
|
Before Width: | Height: | Size: 18 KiB |
|
Before Width: | Height: | Size: 17 KiB |
|
Before Width: | Height: | Size: 17 KiB |
|
Before Width: | Height: | Size: 10 KiB |
|
Before Width: | Height: | Size: 9.6 KiB |
|
Before Width: | Height: | Size: 10 KiB |
|
Before Width: | Height: | Size: 10 KiB |
|
Before Width: | Height: | Size: 62 KiB |
|
Before Width: | Height: | Size: 48 KiB |
|
Before Width: | Height: | Size: 50 KiB |
|
Before Width: | Height: | Size: 17 KiB |
|
Before Width: | Height: | Size: 44 KiB |
|
Before Width: | Height: | Size: 55 KiB |
|
Before Width: | Height: | Size: 68 KiB |
|
Before Width: | Height: | Size: 35 KiB |
|
Before Width: | Height: | Size: 32 KiB |
|
Before Width: | Height: | Size: 105 KiB |
|
Before Width: | Height: | Size: 34 KiB |
|
Before Width: | Height: | Size: 36 KiB |
|
Before Width: | Height: | Size: 108 KiB |
|
Before Width: | Height: | Size: 93 KiB |
|
Before Width: | Height: | Size: 65 KiB |
|
Before Width: | Height: | Size: 28 KiB |
|
Before Width: | Height: | Size: 31 KiB |
|
Before Width: | Height: | Size: 42 KiB |
|
Before Width: | Height: | Size: 43 KiB |
|
Before Width: | Height: | Size: 76 KiB |
|
Before Width: | Height: | Size: 28 KiB |
|
Before Width: | Height: | Size: 44 KiB |
|
Before Width: | Height: | Size: 32 KiB |
@@ -4,7 +4,7 @@
|
||||
|
||||
Do the following:
|
||||
|
||||
* **Check ESP32 core is installed**. Check if the version matches the one used in the [tutorial](usage.md#building-the-firmware).
|
||||
* **Check ESP32 core is installed**. Check if the version matches the one used in the [tutorial](usage.md#firmware).
|
||||
* **Check libraries**. Install all the required libraries from the tutorial. Make sure there are no MPU9250 or other peripherals libraries that may conflict with the ones used in the tutorial.
|
||||
* **Check the chosen board**. The correct board to choose in Arduino IDE for ESP32 Mini is *WEMOS D1 MINI ESP32*.
|
||||
|
||||
@@ -13,10 +13,10 @@ 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 if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button or `reboot` command to see the whole 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.
|
||||
* **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**.
|
||||
* **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:
|
||||
@@ -25,7 +25,7 @@ Do the following:
|
||||
* The `accel` and `gyro` fields should change as you move the drone.
|
||||
* **Calibrate the accelerometer.** if is wasn't done before. Type `ca` command in Serial Monitor and follow the instructions.
|
||||
* **Check the attitude estimation**. Connect to the drone using QGroundControl. Rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct.
|
||||
* **Check the IMU orientation is set correctly**. If the attitude estimation is rotated, set the correct IMU orientation as described in the [tutorial](usage.md#define-imu-orientation).
|
||||
* **Check the IMU orientation is set correctly**. If the attitude estimation is rotated, make sure `rotateIMU` function is defined correctly in `imu.ino` file.
|
||||
* **Check the motors type**. Motors with exact 3.7V voltage are needed, not ranged working voltage (3.7V — 6V).
|
||||
* **Check the motors**. Perform the following commands using Serial Monitor:
|
||||
* `mfr` — should rotate front right motor (counter-clockwise).
|
||||
@@ -35,7 +35,5 @@ Do the following:
|
||||
* **Check the propeller directions are correct**. Make sure your propeller types (A or B) are installed as on the picture:
|
||||
<img src="img/user/peter_ukhov-2/1.jpg" width="200">
|
||||
* **Check the remote control**. Using `rc` command, check the control values reflect your sticks movement. All the controls should change between -1 and 1, and throttle between 0 and 1.
|
||||
* **If using SBUS receiver**:
|
||||
* **Define the used GPIO pin** in `RC_RX_PIN` parameter.
|
||||
* **Calibrate the RC** using `cr` command in the console.
|
||||
* If using SBUS receiver, **calibrate the RC**. Type `cr` command in Serial Monitor and follow the instructions.
|
||||
* **Check the IMU output using QGroundControl**. Connect to the drone using QGroundControl on your computer. Go to the *Analyze* tab, *MAVLINK Inspector*. Plot the data from the `SCALED_IMU` message. The gyroscope and accelerometer data should change according to the drone movement.
|
||||
|
||||
144
docs/usage.md
@@ -12,7 +12,7 @@ Beginners can [download the source code as a ZIP archive](https://github.com/oka
|
||||
|
||||
## Building the firmware
|
||||
|
||||
You can build and upload the firmware using either **Arduino IDE** (easier for beginners) or **command line**.
|
||||
You can build and upload the firmware using either **Arduino IDE** (easier for beginners) or a **command line**.
|
||||
|
||||
### Arduino IDE (Windows, Linux, macOS)
|
||||
|
||||
@@ -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.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):
|
||||
* `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.
|
||||
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.
|
||||
@@ -73,6 +73,14 @@ ICM20948 imu(SPI); // For ICM-20948
|
||||
MPU6050 imu(Wire); // For MPU-6050
|
||||
```
|
||||
|
||||
### Setup the IMU orientation
|
||||
|
||||
The IMU orientation is defined in `rotateIMU` function in the `imu.ino` file. Change it so it converts the IMU axes to the drone's axes correctly. **Drone axes are X forward, Y left, Z up**:
|
||||
|
||||
<img src="img/drone-axes.svg" width="200">
|
||||
|
||||
See various [IMU boards axes orientations table](https://github.com/okalachev/flixperiph/?tab=readme-ov-file#imu-axes-orientation) to help you set up the correct orientation.
|
||||
|
||||
### Connect using QGroundControl
|
||||
|
||||
QGroundControl is a ground control station software that can be used to monitor and control the drone.
|
||||
@@ -80,7 +88,7 @@ QGroundControl is a ground control station software that can be used to monitor
|
||||
1. Install mobile or desktop version of [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html).
|
||||
2. Power up the drone.
|
||||
3. Connect your computer or smartphone to the appeared `flix` Wi-Fi network (password: `flixwifi`).
|
||||
4. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
|
||||
4. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically
|
||||
|
||||
### Access console
|
||||
|
||||
@@ -96,37 +104,11 @@ To access the console using QGroundControl:
|
||||
|
||||
1. Connect to the drone using QGroundControl app.
|
||||
2. Go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*.
|
||||
|
||||
<img src="img/cli.png" width="400">
|
||||
<img src="img/cli.png" width="400">
|
||||
|
||||
> [!TIP]
|
||||
> Use `help` command to see the list of available commands.
|
||||
|
||||
### Access parameters
|
||||
|
||||
The drone is configured using parameters. To access and modify them, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*:
|
||||
|
||||
<img src="img/parameters.png" width="400">
|
||||
|
||||
You can also work with parameters using `p` command in the console. Parameter names are case-insensitive.
|
||||
|
||||
### Define IMU orientation
|
||||
|
||||
Use parameters, to define the IMU board axes orientation relative to the drone's axes: `IMU_ROT_ROLL`, `IMU_ROT_PITCH`, and `IMU_ROT_YAW`.
|
||||
|
||||
The drone has *X* axis pointing forward, *Y* axis pointing left, and *Z* axis pointing up, and the supported IMU boards have *X* axis pointing to the pins side and *Z* axis pointing up from the component side:
|
||||
|
||||
<img src="img/imu-axes.png" width="200">
|
||||
|
||||
Use the following table to set the parameters for common IMU orientations:
|
||||
|
||||
|Orientation|Parameters|Orientation|Parameters|
|
||||
|:-:|-|-|-|
|
||||
|<img src="img/imu-rot-1.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0 |<img src="img/imu-rot-5.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0|
|
||||
|<img src="img/imu-rot-2.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|<img src="img/imu-rot-6.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|
|
||||
|<img src="img/imu-rot-3.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|<img src="img/imu-rot-7.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|
|
||||
|<img src="img/imu-rot-4.png" width="180"><br>☑️ **Default**|<br>`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|<img src="img/imu-rot-8.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|
|
||||
|
||||
### Calibrate accelerometer
|
||||
|
||||
Before flight you need to calibrate the accelerometer:
|
||||
@@ -134,43 +116,25 @@ Before flight you need to calibrate the accelerometer:
|
||||
1. Access the console using QGroundControl (recommended) or Serial Monitor.
|
||||
2. Type `ca` command there and follow the instructions.
|
||||
|
||||
### Setup motors
|
||||
### Check everything works
|
||||
|
||||
If using non-default motor pins, set the pin numbers using the parameters: `MOTOR_PIN_FL`, `MOTOR_PIN_FR`, `MOTOR_PIN_RL`, `MOTOR_PIN_RR` (front-left, front-right, rear-left, rear-right respectively).
|
||||
|
||||
If using brushless motors and ESCs:
|
||||
|
||||
1. Set the appropriate PWM using the parameters: `MOT_PWM_STOP`, `MOT_PWM_MIN`, and `MOT_PWM_MAX` (1000, 1000, and 2000 is typical).
|
||||
2. Decrease the PWM frequency using the `MOT_PWM_FREQ` parameter (400 is typical).
|
||||
|
||||
> [!CAUTION]
|
||||
> **Remove the props when configuring the motors!** If improperly configured, you may not be able to stop them.
|
||||
|
||||
### Important: check everything works
|
||||
|
||||
1. Check the IMU is working: perform `imu` command in the console and check the output:
|
||||
1. Check the IMU is working: perform `imu` command and check its output:
|
||||
|
||||
* The `status` field should be `OK`.
|
||||
* The `rate` field should be about 1000 (Hz).
|
||||
* The `accel` and `gyro` fields should change as you move the drone.
|
||||
* The `accel bias` and `accel scale` fields should contain calibration parameters (not zeros and ones).
|
||||
* The `gyro bias` field should contain estimated gyro bias (not zeros).
|
||||
* The `landed` field should be `1` when the drone is still on the ground and `0` when you lift it up.
|
||||
|
||||
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. Use the following commands **— remove the propellers before running the tests!**
|
||||
3. Perform motor tests in the console. Use the following commands **— remove the propellers before running the tests!**
|
||||
|
||||
* `mfr` — rotate front right motor (counter-clockwise).
|
||||
* `mfl` — rotate front left motor (clockwise).
|
||||
* `mrl` — rotate rear left motor (counter-clockwise).
|
||||
* `mrr` — rotate rear right motor (clockwise).
|
||||
|
||||
Make sure rotation directions and propeller types match the following diagram:
|
||||
|
||||
<img src="img/motors.svg" width=200>
|
||||
* `mfr` — should rotate front right motor (counter-clockwise).
|
||||
* `mfl` — should rotate front left motor (clockwise).
|
||||
* `mrl` — should rotate rear left motor (counter-clockwise).
|
||||
* `mrr` — should rotate rear right motor (clockwise).
|
||||
|
||||
> [!WARNING]
|
||||
> Never run the motors when powering the drone from USB, always use the battery for that.
|
||||
@@ -179,7 +143,7 @@ If using brushless motors and ESCs:
|
||||
|
||||
There are several ways to control the drone's flight: using **smartphone** (Wi-Fi), using **SBUS remote control**, or using **USB remote control** (Wi-Fi).
|
||||
|
||||
### Control with a smartphone
|
||||
### Control with smartphone
|
||||
|
||||
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone.
|
||||
2. Power the drone using the battery.
|
||||
@@ -189,19 +153,17 @@ There are several ways to control the drone's flight: using **smartphone** (Wi-F
|
||||
6. Use the virtual joystick to fly the drone!
|
||||
|
||||
> [!TIP]
|
||||
> Decrease `CTL_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
|
||||
> Decrease `CNT_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
|
||||
|
||||
### Control with a remote control
|
||||
### Control with remote control
|
||||
|
||||
Before using SBUS-connected remote control you need to enable SBUS and calibrate it:
|
||||
Before using remote SBUS-connected remote control, you need to calibrate it:
|
||||
|
||||
1. Connect to the drone using QGroundControl.
|
||||
2. In parameters, set the `RC_RX_PIN` parameter to the GPIO pin number where the SBUS signal is connected, for example: 4. Negative value disables SBUS.
|
||||
3. Reboot the drone to apply changes.
|
||||
4. Open the console, type `cr` command and follow the instructions to calibrate the remote control.
|
||||
5. Use the remote control to fly the drone!
|
||||
1. Access the console using QGroundControl (recommended) or Serial Monitor.
|
||||
2. Type `cr` command and follow the instructions.
|
||||
3. Use the remote control to fly the drone!
|
||||
|
||||
### Control with a USB remote control
|
||||
### Control with USB remote control
|
||||
|
||||
If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it.
|
||||
|
||||
@@ -236,11 +198,11 @@ When finished flying, **disarm** the drone, moving the left stick to the bottom
|
||||
|
||||
### Flight modes
|
||||
|
||||
Flight mode is changed using mode switch on the remote control (if configured) or using the console commands. The main flight mode is *STAB*.
|
||||
Flight mode is changed using mode switch on the remote control or using the command line.
|
||||
|
||||
#### STAB
|
||||
|
||||
In this mode, the drone stabilizes its attitude (orientation). The left stick controls throttle and yaw rate, the right stick controls pitch and roll angles.
|
||||
The default mode is *STAB*. In this mode, the drone stabilizes its attitude (orientation). The left stick controls throttle and yaw rate, the right stick controls pitch and roll angles.
|
||||
|
||||
> [!IMPORTANT]
|
||||
> The drone doesn't stabilize its position, so slight drift is possible. The pilot should compensate it manually.
|
||||
@@ -249,53 +211,25 @@ In this mode, the drone stabilizes its attitude (orientation). The left stick co
|
||||
|
||||
In this mode, the pilot controls the angular rates. This control method is difficult to fly and mostly used in FPV racing.
|
||||
|
||||
#### RAW
|
||||
#### MANUAL
|
||||
|
||||
*RAW* mode disables all the stabilization, and the pilot inputs are mixed directly to the motors. The IMU sensor is not involved. This mode is intended for testing and demonstration purposes only, and basically the drone **cannot fly in this mode**.
|
||||
Manual mode disables all the stabilization, and the pilot inputs are passed directly to the motors. This mode is intended for testing and demonstration purposes only, and basically the drone **cannot fly in this mode**.
|
||||
|
||||
#### AUTO
|
||||
|
||||
In this mode, the pilot inputs are ignored (except the mode switch). The drone can be controlled using [pyflix](../tools/pyflix/) Python library, or by modifying the firmware to implement the needed behavior.
|
||||
In this mode, the pilot inputs are ignored (except the mode switch, if configured). The drone can be controlled using [pyflix](../tools/pyflix/) Python library, or by modifying the firmware to implement the needed autonomous behavior.
|
||||
|
||||
If the pilot moves the control sticks, the drone will switch back to *STAB* mode.
|
||||
|
||||
## Wi-Fi configuration
|
||||
## Adjusting parameters
|
||||
|
||||
You can configure the Wi-Fi using parameters and console commands.
|
||||
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*.
|
||||
|
||||
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
|
||||
```
|
||||
<img src="img/parameters.png" width="400">
|
||||
|
||||
## 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
|
||||
make log
|
||||
|
||||
84
docs/user.md
@@ -4,94 +4,12 @@ This page contains user-built drones based on the Flix project. Publish your pro
|
||||
|
||||
---
|
||||
|
||||
Author: [FanBy0ru](https://https://github.com/FanBy0ru).<br>
|
||||
Description: custom 3D-printed frame.<br>
|
||||
Frame STLs and flight validation: https://cults3d.com/en/3d-model/gadget/armature-pour-flix-drone.
|
||||
|
||||
<img src="img/user/fanby0ru/1.jpg" height=200> <img src="img/user/fanby0ru/2.jpg" height=200>
|
||||
|
||||
---
|
||||
|
||||
Author: Ivan44 Phalko.<br>
|
||||
Description: custom PCB, cusom test bench.<br>
|
||||
[Flight validation](https://drive.google.com/file/d/17DNDJ1gPmCmDRAwjedCbJ9RXAyqMqqcX/view?usp=sharing).
|
||||
|
||||
<img src="img/user/phalko/1.jpg" height=200> <img src="img/user/phalko/2.jpg" height=200> <img src="img/user/phalko/3.jpg" height=200>
|
||||
|
||||
---
|
||||
|
||||
Author: **Arkadiy "Arky" Matsekh**, Foucault Dynamics, Gold Coast, Australia.<br>
|
||||
The drone was built for the University of Queensland industry-led Master's capstone project.
|
||||
|
||||
**Flight video:**
|
||||
|
||||
<a href="https://drive.google.com/file/d/1NNYSVXBY-w0JjCo07D8-PgnVq3ca9plj/view?usp=sharing"><img height=300 src="img/user/arkymatsekh/video.jpg"></a>
|
||||
|
||||
<img src="img/user/arkymatsekh/1.jpg" height=150> <img src="img/user/arkymatsekh/2.jpg" height=150> <img src="img/user/arkymatsekh/3.jpg" height=150>
|
||||
|
||||
---
|
||||
|
||||
Author: [goldarte](https://t.me/goldarte).<br>
|
||||
|
||||
<img src="img/user/goldarte/1.jpg" height=150> <img src="img/user/goldarte/2.jpg" height=150>
|
||||
|
||||
**Flight video:**
|
||||
|
||||
<a href="https://drive.google.com/file/d/1nQtFjEcGGLx-l4xkL5ko9ZpOTVU-WDjL/view?usp=sharing"><img height=200 src="img/user/goldarte/video.jpg"></a>
|
||||
|
||||
---
|
||||
|
||||
## School 548 course
|
||||
|
||||
Special course on quadcopter design and engineering took place in october-november 2025 in School 548, Moscow. The course included UAV control theory, electronics, drone assembly and setup practice, using the Flix project.
|
||||
|
||||
<img height=200 src="img/user/school548/1.jpg"> <img height=200 src="img/user/school548/2.jpg"> <img height=200 src="img/user/school548/3.jpg">
|
||||
|
||||
STL files and other materials: see [here](https://drive.google.com/drive/folders/1wTUzj087LjKQQl3Lz5CjHCuobxoykhyp?usp=share_link).
|
||||
|
||||
### Selected works
|
||||
|
||||
Author: [KiraFlux](https://t.me/@kiraflux_0XC0000005).<br>
|
||||
Description: **custom ESPNOW remote control** was implemented, modified firmware to support ESPNOW protocol.<br>
|
||||
Telegram posts: [1](https://t.me/opensourcequadcopter/106), [2](https://t.me/opensourcequadcopter/114).<br>
|
||||
Modified Flix firmware: https://github.com/KiraFlux/flix/tree/klyax.<br>
|
||||
Remote control project: https://github.com/KiraFlux/ESP32-DJC.<br>
|
||||
Drone design: https://github.com/KiraFlux/Klyax.<br>
|
||||
|
||||
<img src="img/user/school548/kiraflux1.jpg" height=150> <img src="img/user/school548/kiraflux2.jpg" height=150>
|
||||
|
||||
**ESPNOW remote control demonstration**:
|
||||
|
||||
<img height=200 src="img/user/school548/kiraflux-video.jpg"><a href="https://drive.google.com/file/d/1soHDAeHQWnm97Y4dg4nWevJuMiTdJJXW/view?usp=sharing"></a>
|
||||
|
||||
Author: [tolyan4krut](https://t.me/tolyan4krut).<br>
|
||||
Description: the first drone based on ESP32-S3-CAM board **with a camera**, implementing Wi-Fi video streaming. Runs HTTP server and HTTP video stream.<br>
|
||||
Modified Flix firmware: https://github.com/CatRey/Flix-Camera-Streaming.<br>
|
||||
[Telegram post](https://t.me/opensourcequadcopter/117).
|
||||
|
||||
<img src="img/user/school548/tolyan4krut.jpg" height=150>
|
||||
|
||||
**Video streaming and flight demonstration**:
|
||||
|
||||
<a href="https://drive.google.com/file/d/1KuOBsujLsk7q8FoqKD8u7uoq4ptS5onp/view?usp=sharing"><img height=200 src="img/user/school548/tolyan4krut-video.jpg"></a>
|
||||
|
||||
Author: [Vlad Tolshinov](https://t.me/Vlad_Tolshinov).<br>
|
||||
Description: custom frame with enlarged arm length, which provides very high flight stability, 65 mm props.
|
||||
|
||||
<img src="img/user/school548/vlad_tolshinov1.jpg" height=150> <img src="img/user/school548/vlad_tolshinov2.jpg" height=150>
|
||||
|
||||
**Flight video**:
|
||||
|
||||
<a href="https://drive.google.com/file/d/1zu00DZxhC7DJ9Z2mYjtxdNQqOOLAyYbp/view?usp=sharing"><img height=200 src="img/user/school548/vlad_tolshinov-video.jpg"></a>
|
||||
|
||||
---
|
||||
|
||||
## RoboCamp
|
||||
|
||||
Author: RoboCamp participants.<br>
|
||||
Description: 3D-printed and wooden frames, ESP32 Mini, DC-DC buck-boost converters. BetaFPV LiteRadio 3 to control the drones via Wi-Fi connection.<br>
|
||||
Features: altitude hold, obstacle avoidance, autonomous flight elements.<br>
|
||||
Some of the designed model files: see [here](https://drive.google.com/drive/folders/18YHWGquKeIevzrMH4-OUT-zKXMETTEUu?usp=share_link).
|
||||
Some of the designed model files: https://drive.google.com/drive/folders/18YHWGquKeIevzrMH4-OUT-zKXMETTEUu?usp=share_link.
|
||||
|
||||
RoboCamp took place in July 2025, Saint Petersburg, where 9 participants designed and built their own drones using the Flix project, and then modified the firmware to complete specific flight tasks.
|
||||
|
||||
|
||||
27
flix/cli.ino
@@ -6,16 +6,14 @@
|
||||
#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;
|
||||
extern const int ACRO, STAB, AUTO;
|
||||
extern float t, dt, loopRate;
|
||||
extern uint16_t channels[16];
|
||||
extern float controlTime;
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
||||
extern int mode;
|
||||
extern bool armed;
|
||||
extern LowPassFilter<Vector> gyroBiasFilter;
|
||||
|
||||
const char* motd =
|
||||
"\nWelcome to\n"
|
||||
@@ -37,11 +35,8 @@ const char* motd =
|
||||
"imu - show IMU data\n"
|
||||
"arm - arm the drone\n"
|
||||
"disarm - disarm the drone\n"
|
||||
"raw/stab/acro/auto - set mode\n"
|
||||
"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"
|
||||
@@ -58,7 +53,9 @@ 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) {
|
||||
@@ -66,7 +63,9 @@ void pause(float duration) {
|
||||
while (t - start < duration) {
|
||||
step();
|
||||
handleInput();
|
||||
#if WIFI_ENABLED
|
||||
processMavlink();
|
||||
#endif
|
||||
delay(50);
|
||||
}
|
||||
}
|
||||
@@ -94,7 +93,7 @@ void doCommand(String str, bool echo = false) {
|
||||
} else if (command == "p") {
|
||||
bool success = setParameter(arg0.c_str(), arg1.toFloat());
|
||||
if (success) {
|
||||
print("%s = %g\n", arg0.c_str(), getParameter(arg0.c_str()));
|
||||
print("%s = %g\n", arg0.c_str(), arg1.toFloat());
|
||||
} else {
|
||||
print("Parameter not found: %s\n", arg0.c_str());
|
||||
}
|
||||
@@ -117,8 +116,6 @@ void doCommand(String str, bool echo = false) {
|
||||
armed = true;
|
||||
} else if (command == "disarm") {
|
||||
armed = false;
|
||||
} else if (command == "raw") {
|
||||
mode = RAW;
|
||||
} else if (command == "stab") {
|
||||
mode = STAB;
|
||||
} else if (command == "acro") {
|
||||
@@ -132,15 +129,8 @@ void doCommand(String str, bool echo = false) {
|
||||
}
|
||||
print("\nroll: %g pitch: %g yaw: %g throttle: %g mode: %g\n",
|
||||
controlRoll, controlPitch, controlYaw, controlThrottle, controlMode);
|
||||
print("time: %.1f\n", controlTime);
|
||||
print("mode: %s\n", getModeName());
|
||||
print("armed: %d\n", armed);
|
||||
} else if (command == "wifi") {
|
||||
printWiFiInfo();
|
||||
} 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]);
|
||||
@@ -180,7 +170,6 @@ void doCommand(String str, bool echo = false) {
|
||||
#endif
|
||||
} else if (command == "reset") {
|
||||
attitude = Quaternion();
|
||||
gyroBiasFilter.reset();
|
||||
} else if (command == "reboot") {
|
||||
ESP.restart();
|
||||
} else {
|
||||
|
||||
@@ -34,16 +34,10 @@
|
||||
#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
|
||||
const int MANUAL = 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);
|
||||
@@ -52,7 +46,12 @@ PID pitchPID(PITCH_P, PITCH_I, PITCH_D);
|
||||
PID yawPID(YAW_P, 0, 0);
|
||||
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
|
||||
float tiltMax = TILT_MAX;
|
||||
int flightModes[] = {STAB, STAB, STAB}; // map for rc mode switch
|
||||
|
||||
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;
|
||||
@@ -66,17 +65,16 @@ void control() {
|
||||
}
|
||||
|
||||
void interpretControls() {
|
||||
if (controlMode < 0.25) mode = flightModes[0];
|
||||
else if (controlMode < 0.75) mode = flightModes[1];
|
||||
else if (controlMode > 0.75) mode = flightModes[2];
|
||||
// NOTE: put ACRO or MANUAL modes there if you want to use them
|
||||
if (controlMode < 0.25) mode = STAB;
|
||||
if (controlMode < 0.75) mode = STAB;
|
||||
if (controlMode > 0.75) mode = STAB;
|
||||
|
||||
if (mode == AUTO) return; // pilot is not effective in AUTO mode
|
||||
|
||||
if (controlThrottle < 0.05 && controlYaw > 0.95) armed = true; // arm gesture
|
||||
if (controlThrottle < 0.05 && controlYaw < -0.95) armed = false; // disarm gesture
|
||||
|
||||
if (abs(controlYaw) < 0.1) controlYaw = 0; // yaw dead zone
|
||||
|
||||
thrustTarget = controlThrottle;
|
||||
|
||||
if (mode == STAB) {
|
||||
@@ -93,10 +91,10 @@ void interpretControls() {
|
||||
ratesTarget.z = -controlYaw * maxRate.z; // positive yaw stick means clockwise rotation in FLU
|
||||
}
|
||||
|
||||
if (mode == RAW) { // direct torque control
|
||||
if (mode == MANUAL) { // passthrough mode
|
||||
attitudeTarget.invalidate(); // skip attitude control
|
||||
ratesTarget.invalidate(); // skip rate control
|
||||
torqueTarget = Vector(controlRoll, controlPitch, -controlYaw) * 0.1;
|
||||
torqueTarget = Vector(controlRoll, controlPitch, -controlYaw) * 0.01;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -157,7 +155,7 @@ void controlTorque() {
|
||||
|
||||
const char* getModeName() {
|
||||
switch (mode) {
|
||||
case RAW: return "RAW";
|
||||
case MANUAL: return "MANUAL";
|
||||
case ACRO: return "ACRO";
|
||||
case STAB: return "STAB";
|
||||
case AUTO: return "AUTO";
|
||||
|
||||
@@ -1,19 +1,15 @@
|
||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// Attitude estimation using gyro and accelerometer
|
||||
// Attitude estimation from gyro and accelerometer
|
||||
|
||||
#include "quaternion.h"
|
||||
#include "vector.h"
|
||||
#include "lpf.h"
|
||||
#include "util.h"
|
||||
|
||||
Vector rates; // estimated angular rates, rad/s
|
||||
Quaternion attitude; // estimated attitude
|
||||
bool landed;
|
||||
|
||||
float accWeight = 0.003;
|
||||
LowPassFilter<Vector> ratesFilter(0.2); // cutoff frequency ~ 40 Hz
|
||||
#define WEIGHT_ACC 0.003
|
||||
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||
|
||||
void estimate() {
|
||||
applyGyro();
|
||||
@@ -22,6 +18,7 @@ void estimate() {
|
||||
|
||||
void applyGyro() {
|
||||
// filter gyro to get angular rates
|
||||
static LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
|
||||
rates = ratesFilter.update(gyro);
|
||||
|
||||
// apply rates to attitude
|
||||
@@ -37,7 +34,7 @@ void applyAcc() {
|
||||
|
||||
// calculate accelerometer correction
|
||||
Vector up = Quaternion::rotateVector(Vector(0, 0, 1), attitude);
|
||||
Vector correction = Vector::rotationVectorBetween(acc, up) * accWeight;
|
||||
Vector correction = Vector::rotationVectorBetween(acc, up) * WEIGHT_ACC;
|
||||
|
||||
// apply correction
|
||||
attitude = Quaternion::rotate(attitude, Quaternion::fromRotationVector(correction));
|
||||
|
||||
@@ -7,13 +7,18 @@
|
||||
#include "quaternion.h"
|
||||
#include "util.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];
|
||||
#define WIFI_ENABLED 1
|
||||
|
||||
float t = NAN; // current step time, s
|
||||
float dt; // time delta from previous step, s
|
||||
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
|
||||
float controlMode = NAN;
|
||||
Vector gyro; // gyroscope data
|
||||
Vector acc; // accelerometer data, m/s/s
|
||||
Vector rates; // filtered angular rates, rad/s
|
||||
Quaternion attitude; // estimated attitude
|
||||
bool landed; // are we landed and stationary
|
||||
float motors[4]; // normalized motors thrust in range [0..1]
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
@@ -21,9 +26,11 @@ void setup() {
|
||||
disableBrownOut();
|
||||
setupParameters();
|
||||
setupLED();
|
||||
setLED(true);
|
||||
setupMotors();
|
||||
setLED(true);
|
||||
#if WIFI_ENABLED
|
||||
setupWiFi();
|
||||
#endif
|
||||
setupIMU();
|
||||
setupRC();
|
||||
setLED(false);
|
||||
@@ -38,7 +45,9 @@ void loop() {
|
||||
control();
|
||||
sendMotors();
|
||||
handleInput();
|
||||
#if WIFI_ENABLED
|
||||
processMavlink();
|
||||
#endif
|
||||
logData();
|
||||
syncParameters();
|
||||
}
|
||||
|
||||
26
flix/imu.ino
@@ -10,16 +10,10 @@
|
||||
#include "util.h"
|
||||
|
||||
MPU9250 imu(SPI);
|
||||
Vector imuRotation(0, 0, -PI / 2); // imu orientation as Euler angles
|
||||
|
||||
Vector gyro; // gyroscope output, rad/s
|
||||
Vector gyroBias;
|
||||
|
||||
Vector acc; // accelerometer output, m/s/s
|
||||
Vector accBias;
|
||||
Vector accScale(1, 1, 1);
|
||||
|
||||
LowPassFilter<Vector> gyroBiasFilter(0.001);
|
||||
Vector gyroBias;
|
||||
|
||||
void setupIMU() {
|
||||
print("Setup IMU\n");
|
||||
@@ -43,16 +37,24 @@ void readIMU() {
|
||||
// apply scale and bias
|
||||
acc = (acc - accBias) / accScale;
|
||||
gyro = gyro - gyroBias;
|
||||
// rotate to body frame
|
||||
Quaternion rotation = Quaternion::fromEuler(imuRotation);
|
||||
acc = Quaternion::rotateVector(acc, rotation.inversed());
|
||||
gyro = Quaternion::rotateVector(gyro, rotation.inversed());
|
||||
// rotate
|
||||
rotateIMU(acc);
|
||||
rotateIMU(gyro);
|
||||
}
|
||||
|
||||
void rotateIMU(Vector& data) {
|
||||
// Rotate from LFD to FLU
|
||||
// NOTE: In case of using other IMU orientation, change this line:
|
||||
data = Vector(data.y, data.x, -data.z);
|
||||
// Axes orientation for various boards: https://github.com/okalachev/flixperiph#imu-axes-orientation
|
||||
}
|
||||
|
||||
void calibrateGyroOnce() {
|
||||
static Delay landedDelay(2);
|
||||
if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary
|
||||
gyroBias = gyroBiasFilter.update(gyro);
|
||||
|
||||
static LowPassFilter<Vector> gyroCalibrationFilter(0.001);
|
||||
gyroBias = gyroCalibrationFilter.update(gyro);
|
||||
}
|
||||
|
||||
void calibrateAccel() {
|
||||
|
||||
14
flix/lpf.h
@@ -14,6 +14,15 @@ 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);
|
||||
}
|
||||
|
||||
@@ -22,6 +31,9 @@ public:
|
||||
}
|
||||
|
||||
void reset() {
|
||||
output = T(); // set to zero
|
||||
initialized = false;
|
||||
}
|
||||
|
||||
private:
|
||||
bool initialized = false;
|
||||
};
|
||||
|
||||
@@ -3,18 +3,22 @@
|
||||
|
||||
// MAVLink communication
|
||||
|
||||
#if WIFI_ENABLED
|
||||
|
||||
#include <MAVLink.h>
|
||||
#include "util.h"
|
||||
|
||||
extern float controlTime;
|
||||
|
||||
int mavlinkSysId = 1;
|
||||
Rate telemetryFast(10);
|
||||
Rate telemetrySlow(2);
|
||||
#define SYSTEM_ID 1
|
||||
#define MAVLINK_RATE_SLOW 1
|
||||
#define MAVLINK_RATE_FAST 10
|
||||
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
||||
|
||||
bool mavlinkConnected = false;
|
||||
String mavlinkPrintBuffer;
|
||||
|
||||
extern float controlTime;
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
||||
|
||||
void processMavlink() {
|
||||
sendMavlink();
|
||||
receiveMavlink();
|
||||
@@ -26,8 +30,10 @@ void sendMavlink() {
|
||||
mavlink_message_t msg;
|
||||
uint32_t time = t * 1000;
|
||||
|
||||
if (telemetrySlow) {
|
||||
mavlink_msg_heartbeat_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
|
||||
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,
|
||||
(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),
|
||||
@@ -36,27 +42,27 @@ void sendMavlink() {
|
||||
|
||||
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);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
|
||||
if (telemetryFast && mavlinkConnected) {
|
||||
const float offset[] = {0, 0, 0, 0};
|
||||
mavlink_msg_attitude_quaternion_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, offset); // convert to frd
|
||||
if (fast && mavlinkConnected) {
|
||||
const float zeroQuat[] = {0, 0, 0, 0};
|
||||
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
|
||||
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);
|
||||
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(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);
|
||||
|
||||
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
|
||||
gyro.x * 1000, -gyro.y * 1000, -gyro.z * 1000,
|
||||
0, 0, 0, 0);
|
||||
@@ -91,7 +97,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 != mavlinkSysId) return; // 0 is broadcast
|
||||
if (m.target && m.target != SYSTEM_ID) return; // 0 is broadcast
|
||||
|
||||
controlThrottle = m.z / 1000.0f;
|
||||
controlPitch = m.x / 1000.0f;
|
||||
@@ -99,16 +105,18 @@ void handleMavlink(const void *_msg) {
|
||||
controlYaw = m.r / 1000.0f;
|
||||
controlMode = NAN;
|
||||
controlTime = t;
|
||||
|
||||
if (abs(controlYaw) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controlYaw = 0;
|
||||
}
|
||||
|
||||
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 != mavlinkSysId) return;
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
|
||||
mavlink_message_t msg;
|
||||
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);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
@@ -117,7 +125,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 != mavlinkSysId) return;
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) 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
|
||||
@@ -126,7 +134,7 @@ void handleMavlink(const void *_msg) {
|
||||
memcpy(name, getParameterName(m.param_index), 16);
|
||||
}
|
||||
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);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
@@ -134,33 +142,32 @@ 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 != mavlinkSysId) return;
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) 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
|
||||
bool success = setParameter(name, m.param_value);
|
||||
if (!success) return;
|
||||
setParameter(name, m.param_value);
|
||||
// send ack
|
||||
mavlink_message_t msg;
|
||||
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
|
||||
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
|
||||
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 != mavlinkSysId) return;
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
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 != mavlinkSysId) return;
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) 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
|
||||
@@ -172,7 +179,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 != mavlinkSysId) return;
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
|
||||
// copy attitude, rates and thrust targets
|
||||
ratesTarget.x = m.body_roll_rate;
|
||||
@@ -194,7 +201,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 != mavlinkSysId) return;
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
|
||||
attitudeTarget.invalidate();
|
||||
ratesTarget.invalidate();
|
||||
@@ -206,12 +213,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 != mavlinkSysId) return;
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) 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(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]);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
@@ -221,13 +228,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 != mavlinkSysId) return;
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) 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(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);
|
||||
sendMessage(&response);
|
||||
}
|
||||
@@ -246,7 +253,7 @@ void handleMavlink(const void *_msg) {
|
||||
|
||||
// send command 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);
|
||||
}
|
||||
}
|
||||
@@ -263,7 +270,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(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
mavlink_msg_serial_control_pack(SYSTEM_ID, 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);
|
||||
@@ -271,3 +278,5 @@ void sendMavlinkPrint() {
|
||||
}
|
||||
mavlinkPrintBuffer.clear();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
@@ -1,19 +1,23 @@
|
||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// PWM control for motors
|
||||
// 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)
|
||||
|
||||
#include "util.h"
|
||||
|
||||
float motors[4]; // normalized motor thrusts in range [0..1]
|
||||
#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
|
||||
|
||||
int motorPins[4] = {12, 13, 14, 15}; // default pin numbers
|
||||
int pwmFrequency = 78000;
|
||||
int pwmResolution = 10;
|
||||
int pwmStop = 0;
|
||||
int pwmMin = 0;
|
||||
int pwmMax = -1; // -1 means duty cycle mode
|
||||
#define PWM_FREQUENCY 78000
|
||||
#define PWM_RESOLUTION 10
|
||||
#define PWM_STOP 0
|
||||
#define PWM_MIN 0
|
||||
#define PWM_MAX 1000000 / PWM_FREQUENCY
|
||||
|
||||
// Motors array indexes:
|
||||
const int MOTOR_REAR_LEFT = 0;
|
||||
const int MOTOR_REAR_RIGHT = 1;
|
||||
const int MOTOR_FRONT_RIGHT = 2;
|
||||
@@ -21,31 +25,30 @@ const int MOTOR_FRONT_LEFT = 3;
|
||||
|
||||
void setupMotors() {
|
||||
print("Setup Motors\n");
|
||||
|
||||
// configure pins
|
||||
for (int i = 0; i < 4; i++) {
|
||||
ledcAttach(motorPins[i], pwmFrequency, pwmResolution);
|
||||
pwmFrequency = ledcChangeFrequency(motorPins[i], pwmFrequency, pwmResolution); // when reconfiguring
|
||||
}
|
||||
ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
||||
ledcAttach(MOTOR_1_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
||||
ledcAttach(MOTOR_2_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
||||
ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
||||
|
||||
sendMotors();
|
||||
print("Motors initialized\n");
|
||||
}
|
||||
|
||||
void sendMotors() {
|
||||
for (int i = 0; i < 4; i++) {
|
||||
ledcWrite(motorPins[i], getDutyCycle(motors[i]));
|
||||
}
|
||||
}
|
||||
|
||||
int getDutyCycle(float value) {
|
||||
value = constrain(value, 0, 1);
|
||||
if (pwmMax >= 0) { // pwm mode
|
||||
float pwm = mapf(value, 0, 1, pwmMin, pwmMax);
|
||||
if (value == 0) pwm = pwmStop;
|
||||
float duty = mapf(pwm, 0, 1000000 / pwmFrequency, 0, (1 << pwmResolution) - 1);
|
||||
return round(duty);
|
||||
} else { // duty cycle mode
|
||||
return round(value * ((1 << pwmResolution) - 1));
|
||||
}
|
||||
float pwm = mapf(value, 0, 1, PWM_MIN, PWM_MAX);
|
||||
if (value == 0) pwm = PWM_STOP;
|
||||
float duty = mapf(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
|
||||
return round(duty);
|
||||
}
|
||||
|
||||
void sendMotors() {
|
||||
ledcWrite(MOTOR_0_PIN, getDutyCycle(motors[0]));
|
||||
ledcWrite(MOTOR_1_PIN, getDutyCycle(motors[1]));
|
||||
ledcWrite(MOTOR_2_PIN, getDutyCycle(motors[2]));
|
||||
ledcWrite(MOTOR_3_PIN, getDutyCycle(motors[3]));
|
||||
}
|
||||
|
||||
bool motorsActive() {
|
||||
|
||||
@@ -6,25 +6,16 @@
|
||||
#include <Preferences.h>
|
||||
#include "util.h"
|
||||
|
||||
extern int channelZero[16];
|
||||
extern int channelMax[16];
|
||||
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
||||
extern int rcRxPin;
|
||||
extern int wifiMode, udpLocalPort, udpRemotePort;
|
||||
extern float rcLossTimeout, descendTime;
|
||||
extern float channelZero[16];
|
||||
extern float channelMax[16];
|
||||
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
||||
|
||||
Preferences storage;
|
||||
|
||||
struct Parameter {
|
||||
const char *name; // max length is 15
|
||||
bool integer;
|
||||
union { float *f; int *i; }; // pointer to the variable
|
||||
float cache; // what's stored in flash
|
||||
void (*callback)(); // called after parameter change
|
||||
Parameter(const char *name, float *variable, void (*callback)() = nullptr) : name(name), integer(false), f(variable), callback(callback) {};
|
||||
Parameter(const char *name, int *variable, void (*callback)() = nullptr) : name(name), integer(true), i(variable), callback(callback) {};
|
||||
float getValue() const { return integer ? *i : *f; };
|
||||
void setValue(const float value) { if (integer) *i = value; else *f = value; };
|
||||
const char *name; // max length is 15 (Preferences key limit)
|
||||
float *variable;
|
||||
float value; // cache
|
||||
};
|
||||
|
||||
Parameter parameters[] = {
|
||||
@@ -51,35 +42,14 @@ Parameter parameters[] = {
|
||||
{"CTL_R_RATE_MAX", &maxRate.x},
|
||||
{"CTL_Y_RATE_MAX", &maxRate.z},
|
||||
{"CTL_TILT_MAX", &tiltMax},
|
||||
{"CTL_FLT_MODE_0", &flightModes[0]},
|
||||
{"CTL_FLT_MODE_1", &flightModes[1]},
|
||||
{"CTL_FLT_MODE_2", &flightModes[2]},
|
||||
// imu
|
||||
{"IMU_ROT_ROLL", &imuRotation.x},
|
||||
{"IMU_ROT_PITCH", &imuRotation.y},
|
||||
{"IMU_ROT_YAW", &imuRotation.z},
|
||||
{"IMU_ACC_BIAS_X", &accBias.x},
|
||||
{"IMU_ACC_BIAS_Y", &accBias.y},
|
||||
{"IMU_ACC_BIAS_Z", &accBias.z},
|
||||
{"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},
|
||||
// motors
|
||||
{"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT], setupMotors},
|
||||
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT], setupMotors},
|
||||
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT], setupMotors},
|
||||
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT], setupMotors},
|
||||
{"MOT_PWM_FREQ", &pwmFrequency, setupMotors},
|
||||
{"MOT_PWM_RES", &pwmResolution, setupMotors},
|
||||
{"MOT_PWM_STOP", &pwmStop},
|
||||
{"MOT_PWM_MIN", &pwmMin},
|
||||
{"MOT_PWM_MAX", &pwmMax},
|
||||
// rc
|
||||
{"RC_RX_PIN", &rcRxPin},
|
||||
{"RC_ZERO_0", &channelZero[0]},
|
||||
{"RC_ZERO_1", &channelZero[1]},
|
||||
{"RC_ZERO_2", &channelZero[2]},
|
||||
@@ -101,29 +71,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() {
|
||||
print("Setup parameters\n");
|
||||
storage.begin("flix");
|
||||
storage.begin("flix", false);
|
||||
// Read parameters from storage
|
||||
for (auto ¶meter : parameters) {
|
||||
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.cache = parameter.getValue();
|
||||
*parameter.variable = storage.getFloat(parameter.name, *parameter.variable);
|
||||
parameter.value = *parameter.variable;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -138,13 +96,13 @@ const char *getParameterName(int index) {
|
||||
|
||||
float getParameter(int index) {
|
||||
if (index < 0 || index >= parametersCount()) return NAN;
|
||||
return parameters[index].getValue();
|
||||
return *parameters[index].variable;
|
||||
}
|
||||
|
||||
float getParameter(const char *name) {
|
||||
for (auto ¶meter : parameters) {
|
||||
if (strcasecmp(parameter.name, name) == 0) {
|
||||
return parameter.getValue();
|
||||
if (strcmp(parameter.name, name) == 0) {
|
||||
return *parameter.variable;
|
||||
}
|
||||
}
|
||||
return NAN;
|
||||
@@ -152,10 +110,8 @@ float getParameter(const char *name) {
|
||||
|
||||
bool setParameter(const char *name, const float value) {
|
||||
for (auto ¶meter : parameters) {
|
||||
if (strcasecmp(parameter.name, name) == 0) {
|
||||
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
|
||||
parameter.setValue(value);
|
||||
if (parameter.callback) parameter.callback();
|
||||
if (strcmp(parameter.name, name) == 0) {
|
||||
*parameter.variable = value;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
@@ -168,17 +124,16 @@ void syncParameters() {
|
||||
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
|
||||
|
||||
for (auto ¶meter : parameters) {
|
||||
if (parameter.getValue() == parameter.cache) continue; // no change
|
||||
if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NAN
|
||||
|
||||
storage.putFloat(parameter.name, parameter.getValue());
|
||||
parameter.cache = parameter.getValue(); // update cache
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
void printParameters() {
|
||||
for (auto ¶meter : parameters) {
|
||||
print("%s = %g\n", parameter.name, parameter.getValue());
|
||||
print("%s = %g\n", parameter.name, *parameter.variable);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
47
flix/rc.ino
@@ -6,27 +6,22 @@
|
||||
#include <SBUS.h>
|
||||
#include "util.h"
|
||||
|
||||
SBUS rc(Serial2);
|
||||
int rcRxPin = -1; // -1 means disabled
|
||||
SBUS rc(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
|
||||
|
||||
uint16_t channels[16]; // raw rc channels
|
||||
int channelZero[16]; // calibration zero values
|
||||
int channelMax[16]; // calibration max values
|
||||
float controlTime; // time of the last controls update
|
||||
float channelZero[16]; // calibration zero values
|
||||
float channelMax[16]; // calibration max values
|
||||
|
||||
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
|
||||
float controlMode = NAN;
|
||||
float controlTime = NAN; // time of the last controls update
|
||||
|
||||
int rollChannel = -1, pitchChannel = -1, throttleChannel = -1, yawChannel = -1, modeChannel = -1; // channel mapping
|
||||
// Channels mapping (using float to store in parameters):
|
||||
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
|
||||
|
||||
void setupRC() {
|
||||
if (rcRxPin < 0) return;
|
||||
print("Setup RC\n");
|
||||
rc.begin(rcRxPin);
|
||||
rc.begin();
|
||||
}
|
||||
|
||||
bool readRC() {
|
||||
if (rcRxPin < 0) return false;
|
||||
if (rc.read()) {
|
||||
SBUSData data = rc.data();
|
||||
for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data
|
||||
@@ -43,18 +38,14 @@ void normalizeRC() {
|
||||
controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1);
|
||||
}
|
||||
// Update control values
|
||||
controlRoll = rollChannel < 0 ? 0 : controls[rollChannel];
|
||||
controlPitch = pitchChannel < 0 ? 0 : controls[pitchChannel];
|
||||
controlYaw = yawChannel < 0 ? 0 : controls[yawChannel];
|
||||
controlThrottle = throttleChannel < 0 ? 0 : controls[throttleChannel];
|
||||
controlMode = modeChannel < 0 ? NAN : controls[modeChannel]; // mode control is ineffective if not mapped
|
||||
controlRoll = rollChannel >= 0 ? controls[(int)rollChannel] : NAN;
|
||||
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN;
|
||||
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN;
|
||||
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN;
|
||||
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN;
|
||||
}
|
||||
|
||||
void calibrateRC() {
|
||||
if (rcRxPin < 0) {
|
||||
print("RC_RX_PIN = %d, set the RC pin!\n", rcRxPin);
|
||||
return;
|
||||
}
|
||||
uint16_t zero[16];
|
||||
uint16_t center[16];
|
||||
uint16_t max[16];
|
||||
@@ -70,7 +61,7 @@ void calibrateRC() {
|
||||
printRCCalibration();
|
||||
}
|
||||
|
||||
void calibrateRCChannel(int *channel, uint16_t in[16], uint16_t out[16], const char *str) {
|
||||
void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const char *str) {
|
||||
print("%s", str);
|
||||
pause(3);
|
||||
for (int i = 0; i < 30; i++) readRC(); // try update 30 times max
|
||||
@@ -91,15 +82,15 @@ void calibrateRCChannel(int *channel, uint16_t in[16], uint16_t out[16], const c
|
||||
channelZero[ch] = in[ch];
|
||||
channelMax[ch] = out[ch];
|
||||
} else {
|
||||
*channel = -1;
|
||||
*channel = NAN;
|
||||
}
|
||||
}
|
||||
|
||||
void printRCCalibration() {
|
||||
print("Control Ch Zero Max\n");
|
||||
print("Roll %-7d%-7d%-7d\n", rollChannel, rollChannel < 0 ? 0 : channelZero[rollChannel], rollChannel < 0 ? 0 : channelMax[rollChannel]);
|
||||
print("Pitch %-7d%-7d%-7d\n", pitchChannel, pitchChannel < 0 ? 0 : channelZero[pitchChannel], pitchChannel < 0 ? 0 : channelMax[pitchChannel]);
|
||||
print("Yaw %-7d%-7d%-7d\n", yawChannel, yawChannel < 0 ? 0 : channelZero[yawChannel], yawChannel < 0 ? 0 : channelMax[yawChannel]);
|
||||
print("Throttle %-7d%-7d%-7d\n", throttleChannel, throttleChannel < 0 ? 0 : channelZero[throttleChannel], throttleChannel < 0 ? 0 : channelMax[throttleChannel]);
|
||||
print("Mode %-7d%-7d%-7d\n", modeChannel, modeChannel < 0 ? 0 : channelZero[modeChannel], modeChannel < 0 ? 0 : channelMax[modeChannel]);
|
||||
print("Roll %-7g%-7g%-7g\n", rollChannel, rollChannel >= 0 ? channelZero[(int)rollChannel] : NAN, rollChannel >= 0 ? channelMax[(int)rollChannel] : NAN);
|
||||
print("Pitch %-7g%-7g%-7g\n", pitchChannel, pitchChannel >= 0 ? channelZero[(int)pitchChannel] : NAN, pitchChannel >= 0 ? channelMax[(int)pitchChannel] : NAN);
|
||||
print("Yaw %-7g%-7g%-7g\n", yawChannel, yawChannel >= 0 ? channelZero[(int)yawChannel] : NAN, yawChannel >= 0 ? channelMax[(int)yawChannel] : NAN);
|
||||
print("Throttle %-7g%-7g%-7g\n", throttleChannel, throttleChannel >= 0 ? channelZero[(int)throttleChannel] : NAN, throttleChannel >= 0 ? channelMax[(int)throttleChannel] : NAN);
|
||||
print("Mode %-7g%-7g%-7g\n", modeChannel, modeChannel >= 0 ? channelZero[(int)modeChannel] : NAN, modeChannel >= 0 ? channelMax[(int)modeChannel] : NAN);
|
||||
}
|
||||
|
||||
@@ -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,8 +16,9 @@ void failsafe() {
|
||||
|
||||
// RC loss failsafe
|
||||
void rcLossFailsafe() {
|
||||
if (controlTime == 0) return; // no RC at all
|
||||
if (!armed) return;
|
||||
if (t - controlTime > rcLossTimeout) {
|
||||
if (t - controlTime > RC_LOSS_TIMEOUT) {
|
||||
descend();
|
||||
}
|
||||
}
|
||||
@@ -26,7 +27,7 @@ void rcLossFailsafe() {
|
||||
void descend() {
|
||||
mode = AUTO;
|
||||
attitudeTarget = Quaternion();
|
||||
thrustTarget -= dt / descendTime;
|
||||
thrustTarget -= dt / DESCEND_TIME;
|
||||
if (thrustTarget < 0) {
|
||||
thrustTarget = 0;
|
||||
armed = false;
|
||||
|
||||
@@ -3,8 +3,6 @@
|
||||
|
||||
// Time related functions
|
||||
|
||||
float t = NAN; // current time, s
|
||||
float dt; // time delta with the previous step, s
|
||||
float loopRate; // Hz
|
||||
|
||||
void step() {
|
||||
|
||||
@@ -35,6 +35,7 @@ public:
|
||||
z = NAN;
|
||||
}
|
||||
|
||||
|
||||
float norm() const {
|
||||
return sqrt(x * x + y * y + z * z);
|
||||
}
|
||||
|
||||
@@ -1,76 +1,45 @@
|
||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// Wi-Fi communication
|
||||
// Wi-Fi support
|
||||
|
||||
#if WIFI_ENABLED
|
||||
|
||||
#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";
|
||||
#define WIFI_AP_MODE 1
|
||||
#define WIFI_AP_SSID "flix"
|
||||
#define WIFI_AP_PASSWORD "flixwifi"
|
||||
#define WIFI_SSID ""
|
||||
#define WIFI_PASSWORD ""
|
||||
#define WIFI_UDP_PORT 14550
|
||||
#define WIFI_UDP_REMOTE_PORT 14550
|
||||
#define WIFI_UDP_REMOTE_ADDR "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());
|
||||
if (WIFI_AP_MODE) {
|
||||
WiFi.softAP(WIFI_AP_SSID, WIFI_AP_PASSWORD);
|
||||
} else {
|
||||
WiFi.begin(WIFI_SSID, WIFI_PASSWORD);
|
||||
}
|
||||
udp.begin(udpLocalPort);
|
||||
udp.begin(WIFI_UDP_PORT);
|
||||
}
|
||||
|
||||
void sendWiFi(const uint8_t *buf, int len) {
|
||||
if (WiFi.softAPgetStationNum() == 0 && !WiFi.isConnected()) return;
|
||||
udp.beginPacket(udpRemoteIP, udpRemotePort);
|
||||
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();
|
||||
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");
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -165,7 +165,6 @@ void delay(uint32_t ms) {
|
||||
|
||||
bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { return true; }
|
||||
bool ledcWrite(uint8_t pin, uint32_t duty) { return true; }
|
||||
uint32_t ledcChangeFrequency(uint8_t pin, uint32_t freq, uint8_t resolution) { return freq; }
|
||||
|
||||
unsigned long __micros;
|
||||
unsigned long __resetTime = 0;
|
||||
|
||||
@@ -68,9 +68,6 @@ Just like the real drone, the simulator can be controlled using a USB remote con
|
||||
6. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
|
||||
7. Use the virtual joystick to fly the drone!
|
||||
|
||||
> [!TIP]
|
||||
> Decrease `CTL_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
|
||||
|
||||
### Control with USB remote control
|
||||
|
||||
1. Connect your USB remote control to the machine running the simulator.
|
||||
|
||||
@@ -13,7 +13,7 @@ class SBUS {
|
||||
public:
|
||||
SBUS(HardwareSerial& bus, const bool inv = true) {};
|
||||
SBUS(HardwareSerial& bus, const int8_t rxpin, const int8_t txpin, const bool inv = true) {};
|
||||
void begin(int rxpin = -1, int txpin = -1, bool inv = true, bool fast = false) {};
|
||||
void begin() {};
|
||||
bool read() { return joystickInit(); };
|
||||
SBUSData data() {
|
||||
SBUSData data;
|
||||
|
||||
@@ -9,18 +9,19 @@
|
||||
#include "quaternion.h"
|
||||
#include "Arduino.h"
|
||||
#include "wifi.h"
|
||||
#include "lpf.h"
|
||||
|
||||
extern float t, dt;
|
||||
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
||||
extern Vector rates;
|
||||
extern Quaternion attitude;
|
||||
extern bool landed;
|
||||
extern float motors[4];
|
||||
#define WIFI_ENABLED 1
|
||||
|
||||
Vector gyro, acc, imuRotation;
|
||||
Vector accBias, gyroBias, accScale(1, 1, 1);
|
||||
LowPassFilter<Vector> gyroBiasFilter(0);
|
||||
float t = NAN;
|
||||
float dt;
|
||||
float motors[4];
|
||||
float controlRoll, controlPitch, controlYaw, controlThrottle = NAN;
|
||||
float controlMode = NAN;
|
||||
Vector acc;
|
||||
Vector gyro;
|
||||
Vector rates;
|
||||
Quaternion attitude;
|
||||
bool landed;
|
||||
|
||||
// declarations
|
||||
void step();
|
||||
@@ -34,7 +35,6 @@ void controlRates();
|
||||
void controlTorque();
|
||||
const char* getModeName();
|
||||
void sendMotors();
|
||||
int getDutyCycle(float value);
|
||||
bool motorsActive();
|
||||
void testMotor(int n);
|
||||
void print(const char* format, ...);
|
||||
@@ -43,7 +43,7 @@ void doCommand(String str, bool echo);
|
||||
void handleInput();
|
||||
void normalizeRC();
|
||||
void calibrateRC();
|
||||
void calibrateRCChannel(int *channel, uint16_t zero[16], uint16_t max[16], const char *str);
|
||||
void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str);
|
||||
void printRCCalibration();
|
||||
void printLogHeader();
|
||||
void printLogData();
|
||||
@@ -73,5 +73,4 @@ void calibrateGyro() { print("Skip gyro calibrating\n"); };
|
||||
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"); };
|
||||
Vector accBias, gyroBias, accScale(1, 1, 1);
|
||||
|
||||
@@ -11,10 +11,9 @@
|
||||
#include <sys/poll.h>
|
||||
#include <gazebo/gazebo.hh>
|
||||
|
||||
int wifiMode = 1; // mock
|
||||
int udpLocalPort = 14580;
|
||||
int udpRemotePort = 14550;
|
||||
const char *udpRemoteIP = "255.255.255.255";
|
||||
#define WIFI_UDP_PORT 14580
|
||||
#define WIFI_UDP_REMOTE_PORT 14550
|
||||
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
|
||||
|
||||
int wifiSocket;
|
||||
|
||||
@@ -23,22 +22,22 @@ void setupWiFi() {
|
||||
sockaddr_in addr; // local address
|
||||
addr.sin_family = AF_INET;
|
||||
addr.sin_addr.s_addr = INADDR_ANY;
|
||||
addr.sin_port = htons(udpLocalPort);
|
||||
addr.sin_port = htons(WIFI_UDP_PORT);
|
||||
if (bind(wifiSocket, (sockaddr *)&addr, sizeof(addr))) {
|
||||
gzerr << "Failed to bind WiFi UDP socket on port " << udpLocalPort << std::endl;
|
||||
gzerr << "Failed to bind WiFi UDP socket on port " << WIFI_UDP_PORT << std::endl;
|
||||
return;
|
||||
}
|
||||
int broadcast = 1;
|
||||
setsockopt(wifiSocket, SOL_SOCKET, SO_BROADCAST, &broadcast, sizeof(broadcast)); // enable broadcast
|
||||
gzmsg << "WiFi UDP socket initialized on port " << udpLocalPort << " (remote port " << udpRemotePort << ")" << std::endl;
|
||||
gzmsg << "WiFi UDP socket initialized on port " << WIFI_UDP_PORT << " (remote port " << WIFI_UDP_REMOTE_PORT << ")" << std::endl;
|
||||
}
|
||||
|
||||
void sendWiFi(const uint8_t *buf, int len) {
|
||||
if (wifiSocket == 0) setupWiFi();
|
||||
sockaddr_in addr; // remote address
|
||||
addr.sin_family = AF_INET;
|
||||
addr.sin_addr.s_addr = inet_addr(udpRemoteIP);
|
||||
addr.sin_port = htons(udpRemotePort);
|
||||
addr.sin_addr.s_addr = inet_addr(WIFI_UDP_REMOTE_ADDR);
|
||||
addr.sin_port = htons(WIFI_UDP_REMOTE_PORT);
|
||||
sendto(wifiSocket, buf, len, 0, (sockaddr *)&addr, sizeof(addr));
|
||||
}
|
||||
|
||||
|
||||
@@ -13,7 +13,7 @@ lines = []
|
||||
|
||||
print('Downloading log...')
|
||||
count = 0
|
||||
dev.write('log dump\n'.encode())
|
||||
dev.write('log\n'.encode())
|
||||
while True:
|
||||
line = dev.readline()
|
||||
if not line:
|
||||
|
||||
@@ -43,7 +43,6 @@ 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:
|
||||
|
||||
@@ -1,8 +1,8 @@
|
||||
# Flix Python library
|
||||
|
||||
The Flix Python library allows you to remotely connect to a Flix quadcopter. It provides access to telemetry data, supports executing console commands, and controlling the drone's flight.
|
||||
The Flix Python library allows you to remotely connect to a Flix quadcopter. It provides access to telemetry data, supports executing CLI commands, and controlling the drone's flight.
|
||||
|
||||
To use the library, connect to the drone's Wi-Fi. To use it with the simulator, ensure the script runs on the same network as the simulator.
|
||||
To use the library, connect to the drone's Wi-Fi. To use it with the simulator, ensure the script runs on the same local network as the simulator.
|
||||
|
||||
## Installation
|
||||
|
||||
@@ -30,7 +30,7 @@ flix = Flix() # create a Flix object and wait for connection
|
||||
|
||||
### Telemetry
|
||||
|
||||
Basic telemetry is available through object properties. The property names generally match the corresponding variables in the firmware itself:
|
||||
Basic telemetry is available through object properties. The properties names generally match the corresponding variables in the firmware itself:
|
||||
|
||||
```python
|
||||
print(flix.connected) # True if connected to the drone
|
||||
@@ -41,7 +41,7 @@ print(flix.attitude) # attitude quaternion [w, x, y, z]
|
||||
print(flix.attitude_euler) # attitude as Euler angles [roll, pitch, yaw]
|
||||
print(flix.rates) # angular rates [roll_rate, pitch_rate, yaw_rate]
|
||||
print(flix.channels) # raw RC channels (list)
|
||||
print(flix.motors) # motor outputs (list)
|
||||
print(flix.motors) # motors outputs (list)
|
||||
print(flix.acc) # accelerometer output (list)
|
||||
print(flix.gyro) # gyroscope output (list)
|
||||
```
|
||||
@@ -92,27 +92,27 @@ Full list of events:
|
||||
|-----|-----------|----------------|
|
||||
|`connected`|Connected to the drone||
|
||||
|`disconnected`|Connection is lost||
|
||||
|`armed`|Armed state update|Armed state *(bool)*|
|
||||
|`mode`|Flight mode update|Flight mode *(str)*|
|
||||
|`landed`|Landed state update|Landed state *(bool)*|
|
||||
|`print`|The drone prints text to the console|Text|
|
||||
|`attitude`|Attitude update|Attitude quaternion *(list)*|
|
||||
|`attitude_euler`|Attitude update|Euler angles *(list)*|
|
||||
|`rates`|Angular rates update|Angular rates *(list)*|
|
||||
|`channels`|Raw RC channels update|Raw RC channels *(list)*|
|
||||
|`motors`|Motor outputs update|Motor outputs *(list)*|
|
||||
|`acc`|Accelerometer update|Accelerometer output *(list)*|
|
||||
|`gyro`|Gyroscope update|Gyroscope output *(list)*|
|
||||
|`armed`|Armed state update|Armed state (*bool*)|
|
||||
|`mode`|Flight mode update|Flight mode (*str*)|
|
||||
|`landed`|Landed state update|Landed state (*bool*)|
|
||||
|`print`|The drone sends text to the console|Text|
|
||||
|`attitude`|Attitude update|Attitude quaternion (*list*)|
|
||||
|`attitude_euler`|Attitude update|Euler angles (*list*)|
|
||||
|`rates`|Angular rates update|Angular rates (*list*)|
|
||||
|`channels`|Raw RC channels update|Raw RC channels (*list*)|
|
||||
|`motors`|Motors outputs update|Motors outputs (*list*)|
|
||||
|`acc`|Accelerometer update|Accelerometer output (*list*)|
|
||||
|`gyro`|Gyroscope update|Gyroscope output (*list*)|
|
||||
|`mavlink`|Received MAVLink message|Message object|
|
||||
|`mavlink.<message_name>`|Received specific MAVLink message|Message object|
|
||||
|`mavlink.<message_id>`|Received specific MAVLink message|Message object|
|
||||
|`value`|Named value update (see below)|Name, value|
|
||||
|`value.<name>`|Specific named value update (see below)|Value|
|
||||
|`value.<name>`|Specific named value update (see bellow)|Value|
|
||||
|
||||
> [!NOTE]
|
||||
> Update events trigger on every new piece of data from the drone, and do not mean the value has changed.
|
||||
> Update events trigger on every new data from the drone, and do not mean the value has changed.
|
||||
|
||||
### Basic methods
|
||||
### Common methods
|
||||
|
||||
Get and set firmware parameters using `get_param` and `set_param` methods:
|
||||
|
||||
@@ -121,7 +121,7 @@ pitch_p = flix.get_param('PITCH_P') # get parameter value
|
||||
flix.set_param('PITCH_P', 5) # set parameter value
|
||||
```
|
||||
|
||||
Execute console commands using `cli` method. This method returns the command response:
|
||||
Execute console commands using `cli` method. This method returns command response:
|
||||
|
||||
```python
|
||||
imu = flix.cli('imu') # get detailed IMU data
|
||||
@@ -169,10 +169,10 @@ Setting angular rates target:
|
||||
flix.set_rates([0.1, 0.2, 0.3], 0.6) # set target roll rate, pitch rate, yaw rate and thrust
|
||||
```
|
||||
|
||||
You also can control raw motor outputs directly:
|
||||
You also can control raw motors outputs directly:
|
||||
|
||||
```python
|
||||
flix.set_motors([0.5, 0.5, 0.5, 0.5]) # set motor outputs in range [0, 1]
|
||||
flix.set_motors([0.5, 0.5, 0.5, 0.5]) # set motors outputs in range [0, 1]
|
||||
```
|
||||
|
||||
In *AUTO* mode, the drone will arm automatically if the thrust is greater than zero, and disarm if thrust is zero. Therefore, to disarm the drone, set thrust to zero:
|
||||
@@ -186,7 +186,7 @@ The following methods are in development and are not functional yet:
|
||||
* `set_position` — set target position.
|
||||
* `set_velocity` — set target velocity.
|
||||
|
||||
To exit *AUTO* mode move control sticks and the drone will switch to *STAB* mode.
|
||||
To exit from *AUTO* mode move control sticks and the drone will switch to *STAB* mode.
|
||||
|
||||
## Usage alongside QGroundControl
|
||||
|
||||
@@ -277,3 +277,7 @@ logger = logging.getLogger('flix')
|
||||
logger.setLevel(logging.DEBUG) # be more verbose
|
||||
logger.setLevel(logging.WARNING) # be less verbose
|
||||
```
|
||||
|
||||
## Stability
|
||||
|
||||
The library is in development stage. The API is not stable.
|
||||
|
||||
@@ -17,7 +17,7 @@ from pymavlink.dialects.v20 import common as mavlink
|
||||
logger = logging.getLogger('flix')
|
||||
if not logger.hasHandlers():
|
||||
handler = logging.StreamHandler()
|
||||
handler.setFormatter(logging.Formatter('%(name)s: %(message)s'))
|
||||
handler.setFormatter(logging.Formatter('%(name)s - %(levelname)s - %(message)s'))
|
||||
logger.addHandler(handler)
|
||||
logger.setLevel(logging.INFO)
|
||||
|
||||
@@ -40,7 +40,7 @@ class Flix:
|
||||
|
||||
_connection_timeout = 3
|
||||
_print_buffer: str = ''
|
||||
_modes = ['RAW', 'ACRO', 'STAB', 'AUTO']
|
||||
_modes = ['MANUAL', 'ACRO', 'STAB', 'AUTO']
|
||||
|
||||
def __init__(self, system_id: int=1, wait_connection: bool=True):
|
||||
if not (0 <= system_id < 256):
|
||||
@@ -138,7 +138,7 @@ class Flix:
|
||||
while True:
|
||||
try:
|
||||
msg: Optional[mavlink.MAVLink_message] = self.connection.recv_match(blocking=True)
|
||||
if msg is None or msg.get_srcSystem() != self.system_id:
|
||||
if msg is None:
|
||||
continue
|
||||
self._connected()
|
||||
msg_dict = msg.to_dict()
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
[project]
|
||||
name = "pyflix"
|
||||
version = "0.11"
|
||||
version = "0.9"
|
||||
description = "Python API for Flix drone"
|
||||
authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }]
|
||||
license = "MIT"
|
||||
|
||||