27 Commits

Author SHA1 Message Date
Oleg Kalachev
c434107eaf Add parameter for configuring sbus pin number, disable sbus by default 2026-03-27 00:56:34 +03:00
Oleg Kalachev
814427dbfd Minor docs change 2026-03-27 00:40:19 +03:00
Oleg Kalachev
0730ceeffa Add new user builds 2026-02-21 07:12:36 +03:00
Oleg Kalachev
a687303062 Make motor parameters apply without reboot
Add callback to parameter definition to call after parameter is changed.
2026-02-19 04:56:12 +03:00
Oleg Kalachev
b2daf2587f Minor parameters code simplifications
readOnly is false by default
INFINITY == INFINITY, so remove redundant check
2026-02-19 02:59:38 +03:00
Oleg Kalachev
a8c25d8ac0 Minor updates to usage article 2026-02-04 17:52:23 +03:00
Oleg Kalachev
3e49d41986 Make rc channel numbers and calibration params use int instead of float
As parameter subsystems supports int now, and int is much more natural here.
2026-02-02 20:36:22 +03:00
Oleg Kalachev
67430c7aac Several minor changes 2026-02-02 18:46:36 +03:00
Oleg Kalachev
3631743a29 Drop messages from another systems in pyflix
We shouldn't pass messages where system id != our system id. 
This change may be useful when there are many drones in one network.
2026-02-02 18:28:20 +03:00
Oleg Kalachev
3dde380bb7 Add parameters for list of modes bound to rc switch
Parameters: CTL_FLT_MODE_0, CTL_FLT_MODE_1, CTL_FLT_MODE_2.
Also fix a bug with incorrect choosing the mode from controlMode.
2026-01-27 16:38:20 +03:00
Oleg Kalachev
377b21429b Fix error when launching the sim
Also make the parameters WIFI_LOC_PORT and WIFI_REM_PORT work in the sim.
2026-01-27 16:32:52 +03:00
Oleg Kalachev
1ac443d6f8 Add a build by Arky Matsekh 2026-01-27 15:17:58 +03:00
Oleg Kalachev
964c0f7bc1 Make setting parameter in console printing actual parameter value.
In some cases, it would not be equal to the requested value.
2026-01-27 09:28:01 +03:00
Oleg Kalachev
40bdaacedb Make motor subsystem configurable using parameters
Motor pins: MOT_PIN_FL, MOT_PIN_FR, MOT_PIN_RL, MOT_PIN_RR.
PWM configuration: MOT_PWM_FREQ, MOT_PWM_RES, MOT_PWM_STOP, MOT_PWM_MIN, MOT_PWM_MAX.
MOT_PWM_MAX = -1 chooses duty cycle mode for brushed motors (default).
2026-01-27 08:40:52 +03:00
Oleg Kalachev
7d74f3d5cd Minor docs fixes 2026-01-27 07:21:21 +03:00
Oleg Kalachev
9fd35ba361 Simplify lpf filter code
Begin with zero instead of the initializing value, as the latter doesn't make much sense in practice, but complicates the code much.
2026-01-24 09:43:46 +03:00
Oleg Kalachev
ca50f75576 Various minor fixes 2026-01-24 09:34:16 +03:00
Oleg Kalachev
e47a31f981 Fix mavlink parameter set acknowledgement value
If the parameter is integer the acknowledgement should contain the rounded value.
2026-01-24 09:32:49 +03:00
Oleg Kalachev
7ad3022798 Add parameter for configuring gyro bias lpf
+ reset the filter on `reset` command
2026-01-24 09:31:32 +03:00
Oleg Kalachev
5b654e4d8e Update ESP32-Core to 3.3.6 2026-01-23 02:41:43 +03:00
Oleg Kalachev
cf10ec6161 Update MAVLink-Arduino to 2.0.16 2026-01-23 01:11:35 +03:00
Oleg Kalachev
6d01cd2e79 Make failsafe configurable using parameters
SF_RC_LOSS_TIME - time without rc to activate failsafe.
SD_DESCEND_TIME - total time to decrease the throttle to zero.
Make controlTime nan on the start to simplify the logic.
2026-01-22 23:57:52 +03:00
Oleg Kalachev
0abb18c616 Make parameter names case-insensitive
+ minor fix
2026-01-22 23:11:47 +03:00
Oleg Kalachev
30326a5662 Add parameters for configuring the mavlink subsystem
MAV_SYS_ID - mavlink system id.
MAV_RATE_SLOW - rate of slow telemetry (e. g. heartbeats).
MAV_RATE_FAST - rate of fast telemetry (e. g. attitude, imu data).
2026-01-22 23:04:45 +03:00
Oleg Kalachev
dd3575174b Add wifi configuration using parameters and cli
Add console commands to setup wifi.
Add a parameter for choosing between STA and AP mode.
Add parameters for udp ports.
Remove WIFI_ENABLED macro.
2026-01-22 22:58:43 +03:00
Oleg Kalachev
c0f3301da4 Support integer parameters in addition to floats
The variable pointer is stored as a union field.
If `.integer` field is true, then integer pointer should be used.
Interfaces to parameters (cli and mavlink) keep working using floats.
Setting a non-finite value to int parameter will cause an error.
`.value` field is renamed to `.cache`.
2026-01-22 22:54:05 +03:00
a.golubtsov
a6bad3a69b Add log dir creation before log writing 2026-01-22 17:56:23 +03:00
40 changed files with 394 additions and 267 deletions

View File

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

View File

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

View File

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

View File

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

View File

@@ -138,10 +138,10 @@ You can see a user-contributed [variant of complete circuit diagram](https://mir
|Motor|Position|Direction|Prop type|Motor wires|GPIO| |Motor|Position|Direction|Prop type|Motor wires|GPIO|
|-|-|-|-|-|-| |-|-|-|-|-|-|
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 (*TDI*)| |Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 *(TDI)*|
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 (*TCK*)| |Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 *(TCK)*|
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 (*TMS*)| |Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 *(TMS)*|
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 (*TD0*)| |Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 *(TD0)*|
Clockwise motors have blue & red wires and correspond to propeller type A (marked on the propeller). Clockwise motors have blue & red wires and correspond to propeller type A (marked on the propeller).
Counter-clockwise motors have black & white wires correspond to propeller type B. Counter-clockwise motors have black & white wires correspond to propeller type B.

View File

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

View File

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

View File

@@ -177,7 +177,7 @@ imu.setDLPF(imu.DLPF_MAX);
## Калибровка гироскопа ## Калибровка гироскопа
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения (*bias*) и случайный шум (*noise*): Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения *(bias)* и случайный шум *(noise)*:
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\] \\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]

Binary file not shown.

After

Width:  |  Height:  |  Size: 62 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 48 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 44 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 55 KiB

BIN
docs/img/user/phalko/1.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 105 KiB

BIN
docs/img/user/phalko/2.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 34 KiB

BIN
docs/img/user/phalko/3.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 36 KiB

View File

@@ -13,10 +13,10 @@ Do the following:
Do the following: Do the following:
* **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V. * **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V.
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button to make sure you see the whole ESP32 output. * **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 the baudrate is correct**. If you see garbage characters in the Serial Monitor, make sure the baudrate is set to 115200. * **Check the baudrate is correct**. If you see garbage characters in the Serial Monitor, make sure the baudrate is set to 115200.
* **Make sure correct IMU model is chosen**. If using ICM-20948/MPU-6050 board, change `MPU9250` to `ICM20948`/`MPU6050` in the `imu.ino` file. * **Make sure correct IMU model is chosen**. If using ICM-20948/MPU-6050 board, change `MPU9250` to `ICM20948`/`MPU6050` in the `imu.ino` file.
* **Check if the CLI is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the CLI using QGroundControl (*Vehicle Setup**Analyze Tools**MAVLink Console*). * **Check if the console is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the console using QGroundControl *(Vehicle Setup**Analyze Tools**MAVLink Console)*.
* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**. * **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
* **If QGroundControl doesn't connect**, you might need to disable the firewall and/or VPN on your computer. * **If QGroundControl doesn't connect**, you might need to disable the firewall and/or VPN on your computer.
* **Check the IMU is working**. Perform `imu` command and check its output: * **Check the IMU is working**. Perform `imu` command and check its output:
@@ -35,5 +35,7 @@ Do the following:
* **Check the propeller directions are correct**. Make sure your propeller types (A or B) are installed as on the picture: * **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"> <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. * **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, **calibrate the RC**. Type `cr` command in Serial Monitor and follow the instructions. * **If using SBUS receiver**:
* **Define the used GPIO pin** in `RC_RX_PIN` parameter.
* **Calibrate the RC** using `cr` command in the console.
* **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. * **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.

View File

@@ -20,10 +20,10 @@ You can build and upload the firmware using either **Arduino IDE** (easier for b
1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended). 1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended).
2. *Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).* 2. *Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).*
3. Install ESP32 core, version 3.2.0. See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE. 3. Install ESP32 core, version 3.3.6. See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library): 4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
* `FlixPeriph`, the latest version. * `FlixPeriph`, the latest version.
* `MAVLink`, version 2.0.16. * `MAVLink`, version 2.0.25.
5. Open the `flix/flix.ino` sketch from downloaded firmware sources in Arduino IDE. 5. Open the `flix/flix.ino` sketch from downloaded firmware sources in Arduino IDE.
6. Connect your ESP32 board to the computer and choose correct board type in Arduino IDE (*WEMOS D1 MINI ESP32* for ESP32 Mini) and the port. 6. Connect your ESP32 board to the computer and choose correct board type in Arduino IDE (*WEMOS D1 MINI ESP32* for ESP32 Mini) and the port.
7. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE. 7. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
@@ -108,7 +108,7 @@ The drone is configured using parameters. To access and modify them, go to the Q
<img src="img/parameters.png" width="400"> <img src="img/parameters.png" width="400">
You can also work with parameters using `p` command in the console. You can also work with parameters using `p` command in the console. Parameter names are case-insensitive.
### Define IMU orientation ### Define IMU orientation
@@ -134,27 +134,41 @@ Before flight you need to calibrate the accelerometer:
1. Access the console using QGroundControl (recommended) or Serial Monitor. 1. Access the console using QGroundControl (recommended) or Serial Monitor.
2. Type `ca` command there and follow the instructions. 2. Type `ca` command there and follow the instructions.
### Check everything works ### Setup motors
1. Check the IMU is working: perform `imu` command and check its output: 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:
* The `status` field should be `OK`. * The `status` field should be `OK`.
* The `rate` field should be about 1000 (Hz). * The `rate` field should be about 1000 (Hz).
* The `accel` and `gyro` fields should change as you move the drone. * The `accel` and `gyro` fields should change as you move the drone.
* The `accel bias` and `accel scale` fields should contain calibration parameters (not zeros and ones).
* The `gyro bias` field should contain estimated gyro bias (not zeros).
* The `landed` field should be `1` when the drone is still on the ground and `0` when you lift it up. * The `landed` field should be `1` when the drone is still on the ground and `0` when you lift it up.
2. Check the attitude estimation: connect to the drone using QGroundControl, rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. Compare your attitude indicator (in the *large vertical* mode) to the video: 2. Check the attitude estimation: connect to the drone using QGroundControl, rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. Compare your attitude indicator (in the *large vertical* mode) to the video:
<a href="https://youtu.be/yVRN23-GISU"><img width=300 src="https://i3.ytimg.com/vi/yVRN23-GISU/maxresdefault.jpg"></a> <a href="https://youtu.be/yVRN23-GISU"><img width=300 src="https://i3.ytimg.com/vi/yVRN23-GISU/maxresdefault.jpg"></a>
3. Perform motor tests in the console. Use the following commands **— remove the propellers before running the tests!** 3. Perform motor tests. Use the following commands **— remove the propellers before running the tests!**
* `mfr` — should rotate front right motor (counter-clockwise). * `mfr` — rotate front right motor (counter-clockwise).
* `mfl` — should rotate front left motor (clockwise). * `mfl` — rotate front left motor (clockwise).
* `mrl` — should rotate rear left motor (counter-clockwise). * `mrl` — rotate rear left motor (counter-clockwise).
* `mrr` — should rotate rear right motor (clockwise). * `mrr` — rotate rear right motor (clockwise).
Rotation diagram: Make sure rotation directions and propeller types match the following diagram:
<img src="img/motors.svg" width=200> <img src="img/motors.svg" width=200>
@@ -179,11 +193,13 @@ There are several ways to control the drone's flight: using **smartphone** (Wi-F
### Control with a remote control ### Control with a remote control
Before using remote SBUS-connected remote control, you need to calibrate it: Before using SBUS-connected remote control you need to enable SBUS and calibrate it:
1. Access the console using QGroundControl (recommended) or Serial Monitor. 1. Connect to the drone using QGroundControl.
2. Type `cr` command and follow the instructions. 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. Use the remote control to fly the drone! 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!
### Control with a USB remote control ### Control with a USB remote control
@@ -220,11 +236,11 @@ When finished flying, **disarm** the drone, moving the left stick to the bottom
### Flight modes ### Flight modes
Flight mode is changed using mode switch on the remote control or using the command line. Flight mode is changed using mode switch on the remote control (if configured) or using the console commands. The main flight mode is *STAB*.
#### STAB #### STAB
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. In this mode, the drone stabilizes its attitude (orientation). The left stick controls throttle and yaw rate, the right stick controls pitch and roll angles.
> [!IMPORTANT] > [!IMPORTANT]
> The drone doesn't stabilize its position, so slight drift is possible. The pilot should compensate it manually. > The drone doesn't stabilize its position, so slight drift is possible. The pilot should compensate it manually.
@@ -239,13 +255,47 @@ In this mode, the pilot controls the angular rates. This control method is diffi
#### AUTO #### AUTO
In this mode, the pilot inputs are ignored (except the mode switch, if configured). The drone can be controlled using [pyflix](../tools/pyflix/) Python library, or by modifying the firmware to implement the needed autonomous behavior. 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.
If the pilot moves the control sticks, the drone will switch back to *STAB* mode. If the pilot moves the control sticks, the drone will switch back to *STAB* mode.
## Wi-Fi configuration
You can configure the Wi-Fi using parameters and console commands.
The Wi-Fi mode is chosen using `WIFI_MODE` parameter in QGroundControl or in the console:
* `0` — Wi-Fi is disabled.
* `1` — Access Point mode *(AP)* — the drone creates a Wi-Fi network.
* `2` — Client mode *(STA)* — the drone connects to an existing Wi-Fi network.
* `3` — *ESP-NOW (not implemented yet)*.
> [!WARNING]
> Tests showed that Client mode may cause **additional delays** in remote control (due to retranslations), so it's generally not recommended.
The SSID and password are configured using the `ap` and `sta` console commands:
```
ap <ssid> <password>
sta <ssid> <password>
```
Example of configuring the Access Point mode:
```
ap my-flix-ssid mypassword123
p WIFI_MODE 1
```
Disabling Wi-Fi:
```
p WIFI_MODE 0
```
## Flight log ## Flight log
After the flight, you can download the flight log for analysis wirelessly. Use the following for that: After the flight, you can download the flight log for analysis wirelessly. Use the following command on your computer for that:
```bash ```bash
make log make log

View File

@@ -4,6 +4,33 @@ 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> 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> <img src="img/user/goldarte/1.jpg" height=150> <img src="img/user/goldarte/2.jpg" height=150>

View File

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

View File

@@ -52,6 +52,7 @@ PID pitchPID(PITCH_P, PITCH_I, PITCH_D);
PID yawPID(YAW_P, 0, 0); PID yawPID(YAW_P, 0, 0);
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX); Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
float tiltMax = TILT_MAX; float tiltMax = TILT_MAX;
int flightModes[] = {STAB, STAB, STAB}; // map for rc mode switch
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT; extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode; extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
@@ -65,9 +66,9 @@ void control() {
} }
void interpretControls() { void interpretControls() {
if (controlMode < 0.25) mode = STAB; if (controlMode < 0.25) mode = flightModes[0];
if (controlMode < 0.75) mode = STAB; else if (controlMode < 0.75) mode = flightModes[1];
if (controlMode > 0.75) mode = STAB; else if (controlMode > 0.75) mode = flightModes[2];
if (mode == AUTO) return; // pilot is not effective in AUTO mode if (mode == AUTO) return; // pilot is not effective in AUTO mode

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@@ -1,24 +1,19 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com> // Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix // Repository: https://github.com/okalachev/flix
// Motors output control using MOSFETs // PWM control for motors
// 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" #include "util.h"
#define MOTOR_0_PIN 12 // rear left
#define MOTOR_1_PIN 13 // rear right
#define MOTOR_2_PIN 14 // front right
#define MOTOR_3_PIN 15 // front left
#define PWM_FREQUENCY 78000
#define PWM_RESOLUTION 10
#define PWM_STOP 0
#define PWM_MIN 0
#define PWM_MAX 1000000 / PWM_FREQUENCY
float motors[4]; // normalized motor thrusts in range [0..1] float motors[4]; // normalized motor thrusts in range [0..1]
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
const int MOTOR_REAR_LEFT = 0; const int MOTOR_REAR_LEFT = 0;
const int MOTOR_REAR_RIGHT = 1; const int MOTOR_REAR_RIGHT = 1;
const int MOTOR_FRONT_RIGHT = 2; const int MOTOR_FRONT_RIGHT = 2;
@@ -26,30 +21,31 @@ const int MOTOR_FRONT_LEFT = 3;
void setupMotors() { void setupMotors() {
print("Setup Motors\n"); print("Setup Motors\n");
// configure pins // configure pins
ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION); for (int i = 0; i < 4; i++) {
ledcAttach(MOTOR_1_PIN, PWM_FREQUENCY, PWM_RESOLUTION); ledcAttach(motorPins[i], pwmFrequency, pwmResolution);
ledcAttach(MOTOR_2_PIN, PWM_FREQUENCY, PWM_RESOLUTION); pwmFrequency = ledcChangeFrequency(motorPins[i], pwmFrequency, pwmResolution); // when reconfiguring
ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION); }
sendMotors(); sendMotors();
print("Motors initialized\n"); print("Motors initialized\n");
} }
int getDutyCycle(float value) { void sendMotors() {
value = constrain(value, 0, 1); for (int i = 0; i < 4; i++) {
float pwm = mapf(value, 0, 1, PWM_MIN, PWM_MAX); ledcWrite(motorPins[i], getDutyCycle(motors[i]));
if (value == 0) pwm = PWM_STOP; }
float duty = mapf(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
return round(duty);
} }
void sendMotors() { int getDutyCycle(float value) {
ledcWrite(MOTOR_0_PIN, getDutyCycle(motors[0])); value = constrain(value, 0, 1);
ledcWrite(MOTOR_1_PIN, getDutyCycle(motors[1])); if (pwmMax >= 0) { // pwm mode
ledcWrite(MOTOR_2_PIN, getDutyCycle(motors[2])); float pwm = mapf(value, 0, 1, pwmMin, pwmMax);
ledcWrite(MOTOR_3_PIN, getDutyCycle(motors[3])); 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));
}
} }
bool motorsActive() { bool motorsActive() {

View File

@@ -6,16 +6,25 @@
#include <Preferences.h> #include <Preferences.h>
#include "util.h" #include "util.h"
extern float channelZero[16]; extern int channelZero[16];
extern float channelMax[16]; extern int channelMax[16];
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel; extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern int rcRxPin;
extern int wifiMode, udpLocalPort, udpRemotePort;
extern float rcLossTimeout, descendTime;
Preferences storage; Preferences storage;
struct Parameter { struct Parameter {
const char *name; // max length is 15 (Preferences key limit) const char *name; // max length is 15
float *variable; bool integer;
float value; // cache 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; };
}; };
Parameter parameters[] = { Parameter parameters[] = {
@@ -42,6 +51,9 @@ Parameter parameters[] = {
{"CTL_R_RATE_MAX", &maxRate.x}, {"CTL_R_RATE_MAX", &maxRate.x},
{"CTL_Y_RATE_MAX", &maxRate.z}, {"CTL_Y_RATE_MAX", &maxRate.z},
{"CTL_TILT_MAX", &tiltMax}, {"CTL_TILT_MAX", &tiltMax},
{"CTL_FLT_MODE_0", &flightModes[0]},
{"CTL_FLT_MODE_1", &flightModes[1]},
{"CTL_FLT_MODE_2", &flightModes[2]},
// imu // imu
{"IMU_ROT_ROLL", &imuRotation.x}, {"IMU_ROT_ROLL", &imuRotation.x},
{"IMU_ROT_PITCH", &imuRotation.y}, {"IMU_ROT_PITCH", &imuRotation.y},
@@ -52,10 +64,22 @@ Parameter parameters[] = {
{"IMU_ACC_SCALE_X", &accScale.x}, {"IMU_ACC_SCALE_X", &accScale.x},
{"IMU_ACC_SCALE_Y", &accScale.y}, {"IMU_ACC_SCALE_Y", &accScale.y},
{"IMU_ACC_SCALE_Z", &accScale.z}, {"IMU_ACC_SCALE_Z", &accScale.z},
{"IMU_GYRO_BIAS_A", &gyroBiasFilter.alpha},
// estimate // estimate
{"EST_ACC_WEIGHT", &accWeight}, {"EST_ACC_WEIGHT", &accWeight},
{"EST_RATES_LPF_A", &ratesFilter.alpha}, {"EST_RATES_LPF_A", &ratesFilter.alpha},
// 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
{"RC_RX_PIN", &rcRxPin},
{"RC_ZERO_0", &channelZero[0]}, {"RC_ZERO_0", &channelZero[0]},
{"RC_ZERO_1", &channelZero[1]}, {"RC_ZERO_1", &channelZero[1]},
{"RC_ZERO_2", &channelZero[2]}, {"RC_ZERO_2", &channelZero[2]},
@@ -77,17 +101,29 @@ Parameter parameters[] = {
{"RC_THROTTLE", &throttleChannel}, {"RC_THROTTLE", &throttleChannel},
{"RC_YAW", &yawChannel}, {"RC_YAW", &yawChannel},
{"RC_MODE", &modeChannel}, {"RC_MODE", &modeChannel},
// wifi
{"WIFI_MODE", &wifiMode},
{"WIFI_LOC_PORT", &udpLocalPort},
{"WIFI_REM_PORT", &udpRemotePort},
// mavlink
{"MAV_SYS_ID", &mavlinkSysId},
{"MAV_RATE_SLOW", &telemetrySlow.rate},
{"MAV_RATE_FAST", &telemetryFast.rate},
// safety
{"SF_RC_LOSS_TIME", &rcLossTimeout},
{"SF_DESCEND_TIME", &descendTime},
}; };
void setupParameters() { void setupParameters() {
storage.begin("flix", false); print("Setup parameters\n");
storage.begin("flix");
// Read parameters from storage // Read parameters from storage
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
if (!storage.isKey(parameter.name)) { if (!storage.isKey(parameter.name)) {
storage.putFloat(parameter.name, *parameter.variable); storage.putFloat(parameter.name, parameter.getValue()); // store default value
} }
*parameter.variable = storage.getFloat(parameter.name, *parameter.variable); parameter.setValue(storage.getFloat(parameter.name, 0));
parameter.value = *parameter.variable; parameter.cache = parameter.getValue();
} }
} }
@@ -102,13 +138,13 @@ const char *getParameterName(int index) {
float getParameter(int index) { float getParameter(int index) {
if (index < 0 || index >= parametersCount()) return NAN; if (index < 0 || index >= parametersCount()) return NAN;
return *parameters[index].variable; return parameters[index].getValue();
} }
float getParameter(const char *name) { float getParameter(const char *name) {
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
if (strcmp(parameter.name, name) == 0) { if (strcasecmp(parameter.name, name) == 0) {
return *parameter.variable; return parameter.getValue();
} }
} }
return NAN; return NAN;
@@ -116,8 +152,10 @@ float getParameter(const char *name) {
bool setParameter(const char *name, const float value) { bool setParameter(const char *name, const float value) {
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
if (strcmp(parameter.name, name) == 0) { if (strcasecmp(parameter.name, name) == 0) {
*parameter.variable = value; if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
parameter.setValue(value);
if (parameter.callback) parameter.callback();
return true; return true;
} }
} }
@@ -130,16 +168,17 @@ void syncParameters() {
if (motorsActive()) return; // don't use flash while flying, it may cause a delay if (motorsActive()) return; // don't use flash while flying, it may cause a delay
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
if (parameter.value == *parameter.variable) continue; if (parameter.getValue() == parameter.cache) continue; // no change
if (isnan(parameter.value) && isnan(*parameter.variable)) continue; // handle NAN != NAN if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NAN
storage.putFloat(parameter.name, *parameter.variable);
parameter.value = *parameter.variable; storage.putFloat(parameter.name, parameter.getValue());
parameter.cache = parameter.getValue(); // update cache
} }
} }
void printParameters() { void printParameters() {
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
print("%s = %g\n", parameter.name, *parameter.variable); print("%s = %g\n", parameter.name, parameter.getValue());
} }
} }

View File

@@ -7,24 +7,26 @@
#include "util.h" #include "util.h"
SBUS rc(Serial2); SBUS rc(Serial2);
int rcRxPin = -1; // -1 means disabled
uint16_t channels[16]; // raw rc channels uint16_t channels[16]; // raw rc channels
float channelZero[16]; // calibration zero values int channelZero[16]; // calibration zero values
float channelMax[16]; // calibration max values int channelMax[16]; // calibration max values
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1] float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN; // float controlMode = NAN;
float controlTime; // time of the last controls update (0 when no RC) float controlTime = NAN; // time of the last controls update
// Channels mapping (using float to store in parameters): int rollChannel = -1, pitchChannel = -1, throttleChannel = -1, yawChannel = -1, modeChannel = -1; // channel mapping
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
void setupRC() { void setupRC() {
if (rcRxPin < 0) return;
print("Setup RC\n"); print("Setup RC\n");
rc.begin(); rc.begin(rcRxPin);
} }
bool readRC() { bool readRC() {
if (rcRxPin < 0) return false;
if (rc.read()) { if (rc.read()) {
SBUSData data = rc.data(); SBUSData data = rc.data();
for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data
@@ -41,14 +43,18 @@ void normalizeRC() {
controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1); controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1);
} }
// Update control values // Update control values
controlRoll = rollChannel >= 0 ? controls[(int)rollChannel] : 0; controlRoll = rollChannel < 0 ? 0 : controls[rollChannel];
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : 0; controlPitch = pitchChannel < 0 ? 0 : controls[pitchChannel];
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : 0; controlYaw = yawChannel < 0 ? 0 : controls[yawChannel];
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : 0; controlThrottle = throttleChannel < 0 ? 0 : controls[throttleChannel];
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN; // mode switch should not have affect if not set controlMode = modeChannel < 0 ? NAN : controls[modeChannel]; // mode control is ineffective if not mapped
} }
void calibrateRC() { void calibrateRC() {
if (rcRxPin < 0) {
print("RC_RX_PIN = %d, set the RC pin!\n", rcRxPin);
return;
}
uint16_t zero[16]; uint16_t zero[16];
uint16_t center[16]; uint16_t center[16];
uint16_t max[16]; uint16_t max[16];
@@ -64,7 +70,7 @@ void calibrateRC() {
printRCCalibration(); printRCCalibration();
} }
void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const char *str) { void calibrateRCChannel(int *channel, uint16_t in[16], uint16_t out[16], const char *str) {
print("%s", str); print("%s", str);
pause(3); pause(3);
for (int i = 0; i < 30; i++) readRC(); // try update 30 times max for (int i = 0; i < 30; i++) readRC(); // try update 30 times max
@@ -85,15 +91,15 @@ void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const
channelZero[ch] = in[ch]; channelZero[ch] = in[ch];
channelMax[ch] = out[ch]; channelMax[ch] = out[ch];
} else { } else {
*channel = NAN; *channel = -1;
} }
} }
void printRCCalibration() { void printRCCalibration() {
print("Control Ch Zero Max\n"); print("Control Ch Zero Max\n");
print("Roll %-7g%-7g%-7g\n", rollChannel, rollChannel >= 0 ? channelZero[(int)rollChannel] : NAN, rollChannel >= 0 ? channelMax[(int)rollChannel] : NAN); print("Roll %-7d%-7d%-7d\n", rollChannel, rollChannel < 0 ? 0 : channelZero[rollChannel], rollChannel < 0 ? 0 : channelMax[rollChannel]);
print("Pitch %-7g%-7g%-7g\n", pitchChannel, pitchChannel >= 0 ? channelZero[(int)pitchChannel] : NAN, pitchChannel >= 0 ? channelMax[(int)pitchChannel] : NAN); print("Pitch %-7d%-7d%-7d\n", pitchChannel, pitchChannel < 0 ? 0 : channelZero[pitchChannel], pitchChannel < 0 ? 0 : channelMax[pitchChannel]);
print("Yaw %-7g%-7g%-7g\n", yawChannel, yawChannel >= 0 ? channelZero[(int)yawChannel] : NAN, yawChannel >= 0 ? channelMax[(int)yawChannel] : NAN); print("Yaw %-7d%-7d%-7d\n", yawChannel, yawChannel < 0 ? 0 : channelZero[yawChannel], yawChannel < 0 ? 0 : channelMax[yawChannel]);
print("Throttle %-7g%-7g%-7g\n", throttleChannel, throttleChannel >= 0 ? channelZero[(int)throttleChannel] : NAN, throttleChannel >= 0 ? channelMax[(int)throttleChannel] : NAN); print("Throttle %-7d%-7d%-7d\n", throttleChannel, throttleChannel < 0 ? 0 : channelZero[throttleChannel], throttleChannel < 0 ? 0 : channelMax[throttleChannel]);
print("Mode %-7g%-7g%-7g\n", modeChannel, modeChannel >= 0 ? channelZero[(int)modeChannel] : NAN, modeChannel >= 0 ? channelMax[(int)modeChannel] : NAN); print("Mode %-7d%-7d%-7d\n", modeChannel, modeChannel < 0 ? 0 : channelZero[modeChannel], modeChannel < 0 ? 0 : channelMax[modeChannel]);
} }

View File

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

View File

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

View File

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

View File

@@ -13,7 +13,7 @@ class SBUS {
public: public:
SBUS(HardwareSerial& bus, const bool inv = true) {}; SBUS(HardwareSerial& bus, const bool inv = true) {};
SBUS(HardwareSerial& bus, const int8_t rxpin, const int8_t txpin, const bool inv = true) {}; SBUS(HardwareSerial& bus, const int8_t rxpin, const int8_t txpin, const bool inv = true) {};
void begin() {}; void begin(int rxpin = -1, int txpin = -1, bool inv = true, bool fast = false) {};
bool read() { return joystickInit(); }; bool read() { return joystickInit(); };
SBUSData data() { SBUSData data() {
SBUSData data; SBUSData data;

View File

@@ -9,8 +9,7 @@
#include "quaternion.h" #include "quaternion.h"
#include "Arduino.h" #include "Arduino.h"
#include "wifi.h" #include "wifi.h"
#include "lpf.h"
#define WIFI_ENABLED 1
extern float t, dt; extern float t, dt;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode; extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
@@ -21,6 +20,7 @@ extern float motors[4];
Vector gyro, acc, imuRotation; Vector gyro, acc, imuRotation;
Vector accBias, gyroBias, accScale(1, 1, 1); Vector accBias, gyroBias, accScale(1, 1, 1);
LowPassFilter<Vector> gyroBiasFilter(0);
// declarations // declarations
void step(); void step();
@@ -34,6 +34,7 @@ void controlRates();
void controlTorque(); void controlTorque();
const char* getModeName(); const char* getModeName();
void sendMotors(); void sendMotors();
int getDutyCycle(float value);
bool motorsActive(); bool motorsActive();
void testMotor(int n); void testMotor(int n);
void print(const char* format, ...); void print(const char* format, ...);
@@ -42,7 +43,7 @@ void doCommand(String str, bool echo);
void handleInput(); void handleInput();
void normalizeRC(); void normalizeRC();
void calibrateRC(); void calibrateRC();
void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str); void calibrateRCChannel(int *channel, uint16_t zero[16], uint16_t max[16], const char *str);
void printRCCalibration(); void printRCCalibration();
void printLogHeader(); void printLogHeader();
void printLogData(); void printLogData();
@@ -73,3 +74,4 @@ void calibrateAccel() { print("Skip accel calibrating\n"); };
void printIMUCalibration() { print("cal: N/A\n"); }; void printIMUCalibration() { print("cal: N/A\n"); };
void printIMUInfo() {}; void printIMUInfo() {};
void printWiFiInfo() {}; void printWiFiInfo() {};
void configWiFi(bool, const char*, const char*) { print("Skip WiFi config\n"); };

View File

@@ -11,9 +11,10 @@
#include <sys/poll.h> #include <sys/poll.h>
#include <gazebo/gazebo.hh> #include <gazebo/gazebo.hh>
#define WIFI_UDP_PORT 14580 int wifiMode = 1; // mock
#define WIFI_UDP_REMOTE_PORT 14550 int udpLocalPort = 14580;
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255" int udpRemotePort = 14550;
const char *udpRemoteIP = "255.255.255.255";
int wifiSocket; int wifiSocket;
@@ -22,22 +23,22 @@ void setupWiFi() {
sockaddr_in addr; // local address sockaddr_in addr; // local address
addr.sin_family = AF_INET; addr.sin_family = AF_INET;
addr.sin_addr.s_addr = INADDR_ANY; addr.sin_addr.s_addr = INADDR_ANY;
addr.sin_port = htons(WIFI_UDP_PORT); addr.sin_port = htons(udpLocalPort);
if (bind(wifiSocket, (sockaddr *)&addr, sizeof(addr))) { if (bind(wifiSocket, (sockaddr *)&addr, sizeof(addr))) {
gzerr << "Failed to bind WiFi UDP socket on port " << WIFI_UDP_PORT << std::endl; gzerr << "Failed to bind WiFi UDP socket on port " << udpLocalPort << std::endl;
return; return;
} }
int broadcast = 1; int broadcast = 1;
setsockopt(wifiSocket, SOL_SOCKET, SO_BROADCAST, &broadcast, sizeof(broadcast)); // enable broadcast setsockopt(wifiSocket, SOL_SOCKET, SO_BROADCAST, &broadcast, sizeof(broadcast)); // enable broadcast
gzmsg << "WiFi UDP socket initialized on port " << WIFI_UDP_PORT << " (remote port " << WIFI_UDP_REMOTE_PORT << ")" << std::endl; gzmsg << "WiFi UDP socket initialized on port " << udpLocalPort << " (remote port " << udpRemotePort << ")" << std::endl;
} }
void sendWiFi(const uint8_t *buf, int len) { void sendWiFi(const uint8_t *buf, int len) {
if (wifiSocket == 0) setupWiFi(); if (wifiSocket == 0) setupWiFi();
sockaddr_in addr; // remote address sockaddr_in addr; // remote address
addr.sin_family = AF_INET; addr.sin_family = AF_INET;
addr.sin_addr.s_addr = inet_addr(WIFI_UDP_REMOTE_ADDR); addr.sin_addr.s_addr = inet_addr(udpRemoteIP);
addr.sin_port = htons(WIFI_UDP_REMOTE_PORT); addr.sin_port = htons(udpRemotePort);
sendto(wifiSocket, buf, len, 0, (sockaddr *)&addr, sizeof(addr)); sendto(wifiSocket, buf, len, 0, (sockaddr *)&addr, sizeof(addr));
} }

View File

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

View File

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

View File

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

View File

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