mirror of
https://github.com/okalachev/flix.git
synced 2026-03-30 03:54:20 +00:00
Compare commits
25 Commits
cpp
...
a8c25d8ac0
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
a8c25d8ac0 | ||
|
|
3e49d41986 | ||
|
|
67430c7aac | ||
|
|
3631743a29 | ||
|
|
3dde380bb7 | ||
|
|
377b21429b | ||
|
|
1ac443d6f8 | ||
|
|
964c0f7bc1 | ||
|
|
40bdaacedb | ||
|
|
7d74f3d5cd | ||
|
|
9fd35ba361 | ||
|
|
ca50f75576 | ||
|
|
e47a31f981 | ||
|
|
7ad3022798 | ||
|
|
5b654e4d8e | ||
|
|
cf10ec6161 | ||
|
|
6d01cd2e79 | ||
|
|
0abb18c616 | ||
|
|
30326a5662 | ||
|
|
dd3575174b | ||
|
|
c0f3301da4 | ||
|
|
a6bad3a69b | ||
|
|
9a9bd07251 | ||
|
|
28f5855a57 | ||
|
|
7e24ee30f7 |
2
.github/workflows/build.yml
vendored
2
.github/workflows/build.yml
vendored
@@ -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
|
||||||
|
|
||||||
|
|||||||
@@ -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,
|
||||||
|
|||||||
87
.vscode/c_cpp_properties.json
vendored
87
.vscode/c_cpp_properties.json
vendored
@@ -6,21 +6,34 @@
|
|||||||
"${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/control.ino",
|
||||||
|
"${workspaceFolder}/flix/estimate.ino",
|
||||||
|
"${workspaceFolder}/flix/flix.ino",
|
||||||
|
"${workspaceFolder}/flix/imu.ino",
|
||||||
|
"${workspaceFolder}/flix/led.ino",
|
||||||
|
"${workspaceFolder}/flix/log.ino",
|
||||||
|
"${workspaceFolder}/flix/mavlink.ino",
|
||||||
|
"${workspaceFolder}/flix/motors.ino",
|
||||||
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
|
"${workspaceFolder}/flix/time.ino",
|
||||||
|
"${workspaceFolder}/flix/wifi.ino",
|
||||||
|
"${workspaceFolder}/flix/parameters.ino",
|
||||||
|
"${workspaceFolder}/flix/safety.ino"
|
||||||
],
|
],
|
||||||
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/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": [
|
||||||
@@ -40,21 +53,34 @@
|
|||||||
"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/cli.ino",
|
||||||
|
"${workspaceFolder}/flix/control.ino",
|
||||||
|
"${workspaceFolder}/flix/estimate.ino",
|
||||||
|
"${workspaceFolder}/flix/imu.ino",
|
||||||
|
"${workspaceFolder}/flix/led.ino",
|
||||||
|
"${workspaceFolder}/flix/log.ino",
|
||||||
|
"${workspaceFolder}/flix/mavlink.ino",
|
||||||
|
"${workspaceFolder}/flix/motors.ino",
|
||||||
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
|
"${workspaceFolder}/flix/time.ino",
|
||||||
|
"${workspaceFolder}/flix/wifi.ino",
|
||||||
|
"${workspaceFolder}/flix/parameters.ino",
|
||||||
|
"${workspaceFolder}/flix/safety.ino"
|
||||||
],
|
],
|
||||||
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/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": [
|
||||||
@@ -77,19 +103,32 @@
|
|||||||
"${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/control.ino",
|
||||||
|
"${workspaceFolder}/flix/estimate.ino",
|
||||||
|
"${workspaceFolder}/flix/flix.ino",
|
||||||
|
"${workspaceFolder}/flix/imu.ino",
|
||||||
|
"${workspaceFolder}/flix/led.ino",
|
||||||
|
"${workspaceFolder}/flix/log.ino",
|
||||||
|
"${workspaceFolder}/flix/mavlink.ino",
|
||||||
|
"${workspaceFolder}/flix/motors.ino",
|
||||||
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
|
"${workspaceFolder}/flix/time.ino",
|
||||||
|
"${workspaceFolder}/flix/wifi.ino",
|
||||||
|
"${workspaceFolder}/flix/parameters.ino",
|
||||||
|
"${workspaceFolder}/flix/safety.ino"
|
||||||
],
|
],
|
||||||
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/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": [
|
||||||
|
|||||||
4
Makefile
4
Makefile
@@ -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
|
||||||
|
|||||||
16
README.md
16
README.md
@@ -21,15 +21,13 @@
|
|||||||
* Dedicated for education and research.
|
* Dedicated for education and research.
|
||||||
* Made from general-purpose components.
|
* Made from general-purpose components.
|
||||||
* Simple and clean source code in Arduino (<2k lines firmware).
|
* Simple and clean source code in Arduino (<2k lines firmware).
|
||||||
|
* Connectivity using Wi-Fi and MAVLink protocol.
|
||||||
* Control using USB gamepad, remote control or smartphone.
|
* Control using USB gamepad, remote control or smartphone.
|
||||||
* Wi-Fi and MAVLink support.
|
|
||||||
* Wireless command line interface and analyzing.
|
* Wireless command line interface and analyzing.
|
||||||
* Precise simulation with Gazebo.
|
* Precise simulation with Gazebo.
|
||||||
* Python library.
|
* Python library for scripting and automatic flights.
|
||||||
* Textbook on flight control theory and practice ([in development](https://quadcopter.dev)).
|
* Textbook on flight control theory and practice ([in development](https://quadcopter.dev)).
|
||||||
* *Position control (using external camera) and autonomous flights¹*.
|
* *Position control (planned)*.
|
||||||
|
|
||||||
*¹ — planned.*
|
|
||||||
|
|
||||||
## It actually flies
|
## It actually flies
|
||||||
|
|
||||||
@@ -140,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.
|
||||||
|
|||||||
@@ -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
|
||||||
|
|
||||||
|
|||||||
@@ -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) \\]
|
||||||
|
|
||||||
|
|||||||
@@ -87,13 +87,13 @@ Flix поддерживает следующие модели IMU:
|
|||||||
#include <FlixPeriph.h>
|
#include <FlixPeriph.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
|
||||||
MPU9250 IMU(SPI);
|
MPU9250 imu(SPI);
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
bool success = IMU.begin();
|
bool success = imu.begin();
|
||||||
if (!success) {
|
if (!success) {
|
||||||
Serial.println("Failed to initialize IMU");
|
Serial.println("Failed to initialize the IMU");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
```
|
```
|
||||||
@@ -108,21 +108,21 @@ void setup() {
|
|||||||
#include <FlixPeriph.h>
|
#include <FlixPeriph.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
|
||||||
MPU9250 IMU(SPI);
|
MPU9250 imu(SPI);
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
bool success = IMU.begin();
|
bool success = imu.begin();
|
||||||
if (!success) {
|
if (!success) {
|
||||||
Serial.println("Failed to initialize IMU");
|
Serial.println("Failed to initialize the IMU");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
IMU.waitForData();
|
imu.waitForData();
|
||||||
|
|
||||||
float gx, gy, gz;
|
float gx, gy, gz;
|
||||||
IMU.getGyro(gx, gy, gz);
|
imu.getGyro(gx, gy, gz);
|
||||||
|
|
||||||
Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
|
Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
|
||||||
delay(50); // замедление вывода
|
delay(50); // замедление вывода
|
||||||
@@ -135,36 +135,36 @@ void loop() {
|
|||||||
|
|
||||||
## Конфигурация гироскопа
|
## Конфигурация гироскопа
|
||||||
|
|
||||||
В коде Flix настройка IMU происходит в функции `configureIMU`. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплов и частота LPF-фильтра.
|
В коде Flix настройка IMU происходит в функции `configureIMU`. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплирования и частота LPF-фильтра.
|
||||||
|
|
||||||
### Частота сэмплов
|
### Частота сэмплирования
|
||||||
|
|
||||||
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер.
|
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота, тем выше точность управления полетом, но и тем больше нагрузка на микроконтроллер.
|
||||||
|
|
||||||
Частота сэмплов устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
|
Частота сэмплирования устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
|
||||||
|
|
||||||
```cpp
|
```cpp
|
||||||
IMU.setRate(IMU.RATE_1KHZ_APPROX);
|
IMU.setRate(IMU.RATE_1KHZ_APPROX);
|
||||||
```
|
```
|
||||||
|
|
||||||
Поскольку не все поддерживаемые IMU могут работать строго на частоте 1 кГц, в библиотеке FlixPeriph существует возможность приближенной настройки частоты сэмплов. Например, у IMU ICM-20948 при такой настройке реальная частота сэмплирования будет равна 1125 Гц.
|
Поскольку не все поддерживаемые IMU могут работать строго на частоте 1 кГц, в библиотеке FlixPeriph существует возможность приближенной настройки частоты сэмплирования. Например, у IMU ICM-20948 при такой настройке реальная частота сэмплирования будет равна 1125 Гц.
|
||||||
|
|
||||||
Другие доступные для установки в библиотеке FlixPeriph частоты сэмплирования:
|
Другие доступные для установки в библиотеке FlixPeriph частоты сэмплирования:
|
||||||
|
|
||||||
* `RATE_MIN` — минимальная частота сэмплов для конкретного IMU.
|
* `RATE_MIN` — минимальная частота для конкретного IMU.
|
||||||
* `RATE_50HZ_APPROX` — значение, близкое к 50 Гц.
|
* `RATE_50HZ_APPROX` — значение, близкое к 50 Гц.
|
||||||
* `RATE_1KHZ_APPROX` — значение, близкое к 1 кГц.
|
* `RATE_1KHZ_APPROX` — значение, близкое к 1 кГц.
|
||||||
* `RATE_8KHZ_APPROX` — значение, близкое к 8 кГц.
|
* `RATE_8KHZ_APPROX` — значение, близкое к 8 кГц.
|
||||||
* `RATE_MAX` — максимальная частота сэмплов для конкретного IMU.
|
* `RATE_MAX` — максимальная частота для конкретного IMU.
|
||||||
|
|
||||||
#### Диапазон измерений
|
#### Диапазон измерений
|
||||||
|
|
||||||
Большинство MEMS-гироскопов поддерживают несколько диапазонов измерений угловой скорости. Главное преимущество выбора меньшего диапазона — бо́льшая чувствительность. В полетных контроллерах обычно выбирается максимальный диапазон измерений от –2000 до 2000 градусов в секунду, чтобы обеспечить возможность динамичных маневров.
|
Большинство MEMS-гироскопов поддерживают несколько диапазонов измерений угловой скорости. Главное преимущество выбора меньшего диапазона — бо́льшая чувствительность. В полетных контроллерах обычно выбирается максимальный диапазон измерений от –2000 до 2000 градусов в секунду, чтобы обеспечить возможность быстрых маневров.
|
||||||
|
|
||||||
В библиотеке FlixPeriph диапазон измерений гироскопа устанавливается методом `setGyroRange()`:
|
В библиотеке FlixPeriph диапазон измерений гироскопа устанавливается методом `setGyroRange()`:
|
||||||
|
|
||||||
```cpp
|
```cpp
|
||||||
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
|
imu.setGyroRange(imu.GYRO_RANGE_2000DPS);
|
||||||
```
|
```
|
||||||
|
|
||||||
### LPF-фильтр
|
### LPF-фильтр
|
||||||
@@ -172,16 +172,16 @@ IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
|
|||||||
IMU InvenSense могут фильтровать измерения на аппаратном уровне при помощи фильтра нижних частот (LPF). Flix реализует собственный фильтр для гироскопа, чтобы иметь больше гибкости при поддержке разных IMU. Поэтому для встроенного LPF устанавливается максимальная частота среза:
|
IMU InvenSense могут фильтровать измерения на аппаратном уровне при помощи фильтра нижних частот (LPF). Flix реализует собственный фильтр для гироскопа, чтобы иметь больше гибкости при поддержке разных IMU. Поэтому для встроенного LPF устанавливается максимальная частота среза:
|
||||||
|
|
||||||
```cpp
|
```cpp
|
||||||
IMU.setDLPF(IMU.DLPF_MAX);
|
imu.setDLPF(imu.DLPF_MAX);
|
||||||
```
|
```
|
||||||
|
|
||||||
## Калибровка гироскопа
|
## Калибровка гироскопа
|
||||||
|
|
||||||
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения (*bias*) и случайный шум (*noise*):
|
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения *(bias)* и случайный шум *(noise)*:
|
||||||
|
|
||||||
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]
|
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]
|
||||||
|
|
||||||
Для качественной работы подсистемы оценки ориентации и управления дроном необходимо оценить *bias* гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции `calibrateGyro()`. Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются *bias* гироскопа и в дальнейшем вычитаются из измерений.
|
Для точной работы подсистемы оценки ориентации и управления дроном необходимо оценить *bias* гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции `calibrateGyro()`. Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются *bias* гироскопа и в дальнейшем вычитаются из измерений.
|
||||||
|
|
||||||
Программа для вывода данных с гироскопа с калибровкой:
|
Программа для вывода данных с гироскопа с калибровкой:
|
||||||
|
|
||||||
@@ -189,23 +189,23 @@ IMU.setDLPF(IMU.DLPF_MAX);
|
|||||||
#include <FlixPeriph.h>
|
#include <FlixPeriph.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
|
||||||
MPU9250 IMU(SPI);
|
MPU9250 imu(SPI);
|
||||||
|
|
||||||
float gyroBiasX, gyroBiasY, gyroBiasZ; // bias гироскопа
|
float gyroBiasX, gyroBiasY, gyroBiasZ; // bias гироскопа
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
bool success = IMU.begin();
|
bool success = imu.begin();
|
||||||
if (!success) {
|
if (!success) {
|
||||||
Serial.println("Failed to initialize IMU");
|
Serial.println("Failed to initialize the IMU");
|
||||||
}
|
}
|
||||||
calibrateGyro();
|
calibrateGyro();
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
float gx, gy, gz;
|
float gx, gy, gz;
|
||||||
IMU.waitForData();
|
imu.waitForData();
|
||||||
IMU.getGyro(gx, gy, gz);
|
imu.getGyro(gx, gy, gz);
|
||||||
|
|
||||||
// Устранение bias гироскопа
|
// Устранение bias гироскопа
|
||||||
gx -= gyroBiasX;
|
gx -= gyroBiasX;
|
||||||
@@ -226,9 +226,9 @@ void calibrateGyro() {
|
|||||||
|
|
||||||
// Получение 1000 измерений гироскопа
|
// Получение 1000 измерений гироскопа
|
||||||
for (int i = 0; i < samples; i++) {
|
for (int i = 0; i < samples; i++) {
|
||||||
IMU.waitForData();
|
imu.waitForData();
|
||||||
float gx, gy, gz;
|
float gx, gy, gz;
|
||||||
IMU.getGyro(gx, gy, gz);
|
imu.getGyro(gx, gy, gz);
|
||||||
gyroBiasX += gx;
|
gyroBiasX += gx;
|
||||||
gyroBiasY += gy;
|
gyroBiasY += gy;
|
||||||
gyroBiasZ += gz;
|
gyroBiasZ += gz;
|
||||||
|
|||||||
@@ -42,7 +42,7 @@ Pilot inputs are interpreted in `interpretControls()`, and then converted to the
|
|||||||
|
|
||||||
* `attitudeTarget` *(Quaternion)* — target attitude of the drone.
|
* `attitudeTarget` *(Quaternion)* — target attitude of the drone.
|
||||||
* `ratesTarget` *(Vector)* — target angular rates, *rad/s*.
|
* `ratesTarget` *(Vector)* — target angular rates, *rad/s*.
|
||||||
* `ratesExtra` *(Vector)* — additional (feed-forward) angular rates , used for yaw rate control in STAB mode, *rad/s*.
|
* `ratesExtra` *(Vector)* — additional (feed-forward) angular rates, used for yaw rate control in STAB mode, *rad/s*.
|
||||||
* `torqueTarget` *(Vector)* — target torque, range [-1, 1].
|
* `torqueTarget` *(Vector)* — target torque, range [-1, 1].
|
||||||
* `thrustTarget` *(float)* — collective motor thrust target, range [0, 1].
|
* `thrustTarget` *(float)* — collective motor thrust target, range [0, 1].
|
||||||
|
|
||||||
|
|||||||
BIN
docs/img/user/arkymatsekh/1.jpg
Normal file
BIN
docs/img/user/arkymatsekh/1.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 62 KiB |
BIN
docs/img/user/arkymatsekh/2.jpg
Normal file
BIN
docs/img/user/arkymatsekh/2.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 48 KiB |
BIN
docs/img/user/arkymatsekh/3.jpg
Normal file
BIN
docs/img/user/arkymatsekh/3.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 50 KiB |
BIN
docs/img/user/arkymatsekh/video.jpg
Normal file
BIN
docs/img/user/arkymatsekh/video.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 17 KiB |
@@ -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 to make sure you see the whole ESP32 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:
|
||||||
|
|||||||
@@ -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,43 @@ 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).
|
||||||
|
|
||||||
|
Reboot the drone to apply the changes.
|
||||||
|
|
||||||
|
> [!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. Attitude indicator in QGroundControl is shown below:
|
2. Check the attitude estimation: connect to the drone using QGroundControl, rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. Compare your attitude indicator (in the *large vertical* mode) to the video:
|
||||||
|
|
||||||
<img src="img/qgc-attitude.png" height="200">
|
<a href="https://youtu.be/yVRN23-GISU"><img width=300 src="https://i3.ytimg.com/vi/yVRN23-GISU/maxresdefault.jpg"></a>
|
||||||
|
|
||||||
3. Perform motor tests in the console. Use the following commands **— remove the propellers before running the tests!**
|
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>
|
||||||
|
|
||||||
@@ -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
|
||||||
|
|||||||
11
docs/user.md
11
docs/user.md
@@ -4,6 +4,17 @@ This page contains user-built drones based on the Flix project. Publish your pro
|
|||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
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>
|
||||||
|
|||||||
@@ -3,11 +3,10 @@
|
|||||||
|
|
||||||
// Implementation of command line interface
|
// Implementation of command line interface
|
||||||
|
|
||||||
#include <Arduino.h>
|
|
||||||
#include "flix.h"
|
|
||||||
#include "pid.h"
|
#include "pid.h"
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
#include "lpf.h"
|
||||||
|
|
||||||
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
||||||
extern const int RAW, ACRO, STAB, AUTO;
|
extern const int RAW, ACRO, STAB, AUTO;
|
||||||
@@ -16,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"
|
||||||
@@ -40,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"
|
||||||
@@ -56,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) {
|
||||||
@@ -66,14 +66,12 @@ void pause(float duration) {
|
|||||||
while (t - start < duration) {
|
while (t - start < duration) {
|
||||||
step();
|
step();
|
||||||
handleInput();
|
handleInput();
|
||||||
#if WIFI_ENABLED
|
|
||||||
processMavlink();
|
processMavlink();
|
||||||
#endif
|
|
||||||
delay(50);
|
delay(50);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void doCommand(String str, bool echo) {
|
void doCommand(String str, bool echo = false) {
|
||||||
// parse command
|
// parse command
|
||||||
String command, arg0, arg1;
|
String command, arg0, arg1;
|
||||||
splitString(str, command, arg0, arg1);
|
splitString(str, command, arg0, arg1);
|
||||||
@@ -96,7 +94,7 @@ void doCommand(String str, bool echo) {
|
|||||||
} 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());
|
||||||
}
|
}
|
||||||
@@ -138,9 +136,11 @@ void doCommand(String str, bool echo) {
|
|||||||
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]);
|
||||||
@@ -180,6 +180,7 @@ void doCommand(String str, bool echo) {
|
|||||||
#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 {
|
||||||
@@ -1,55 +0,0 @@
|
|||||||
// Wi-Fi
|
|
||||||
#define WIFI_ENABLED 1
|
|
||||||
#define WIFI_SSID "flix"
|
|
||||||
#define WIFI_PASSWORD "flixwifi"
|
|
||||||
#define WIFI_UDP_PORT 14550
|
|
||||||
#define WIFI_UDP_REMOTE_PORT 14550
|
|
||||||
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
|
|
||||||
|
|
||||||
// Motors
|
|
||||||
#define MOTOR_0_PIN 12 // rear left
|
|
||||||
#define MOTOR_1_PIN 13 // rear right
|
|
||||||
#define MOTOR_2_PIN 14 // front right
|
|
||||||
#define MOTOR_3_PIN 15 // front left
|
|
||||||
#define PWM_FREQUENCY 78000
|
|
||||||
#define PWM_RESOLUTION 10
|
|
||||||
#define PWM_STOP 0
|
|
||||||
#define PWM_MIN 0
|
|
||||||
#define PWM_MAX 1000000 / PWM_FREQUENCY
|
|
||||||
|
|
||||||
// Control
|
|
||||||
#define PITCHRATE_P 0.05
|
|
||||||
#define PITCHRATE_I 0.2
|
|
||||||
#define PITCHRATE_D 0.001
|
|
||||||
#define PITCHRATE_I_LIM 0.3
|
|
||||||
#define ROLLRATE_P PITCHRATE_P
|
|
||||||
#define ROLLRATE_I PITCHRATE_I
|
|
||||||
#define ROLLRATE_D PITCHRATE_D
|
|
||||||
#define ROLLRATE_I_LIM PITCHRATE_I_LIM
|
|
||||||
#define YAWRATE_P 0.3
|
|
||||||
#define YAWRATE_I 0.0
|
|
||||||
#define YAWRATE_D 0.0
|
|
||||||
#define YAWRATE_I_LIM 0.3
|
|
||||||
#define ROLL_P 6
|
|
||||||
#define ROLL_I 0
|
|
||||||
#define ROLL_D 0
|
|
||||||
#define PITCH_P ROLL_P
|
|
||||||
#define PITCH_I ROLL_I
|
|
||||||
#define PITCH_D ROLL_D
|
|
||||||
#define YAW_P 3
|
|
||||||
#define PITCHRATE_MAX radians(360)
|
|
||||||
#define ROLLRATE_MAX radians(360)
|
|
||||||
#define YAWRATE_MAX radians(300)
|
|
||||||
#define TILT_MAX radians(30)
|
|
||||||
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
|
||||||
|
|
||||||
// Estimation
|
|
||||||
#define WEIGHT_ACC 0.003
|
|
||||||
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
|
||||||
|
|
||||||
// MAVLink
|
|
||||||
#define SYSTEM_ID 1
|
|
||||||
|
|
||||||
// Safety
|
|
||||||
#define RC_LOSS_TIMEOUT 1
|
|
||||||
#define DESCEND_TIME 10
|
|
||||||
@@ -3,16 +3,38 @@
|
|||||||
|
|
||||||
// Flight control
|
// Flight control
|
||||||
|
|
||||||
#include "config.h"
|
|
||||||
#include "flix.h"
|
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
#include "quaternion.h"
|
#include "quaternion.h"
|
||||||
#include "pid.h"
|
#include "pid.h"
|
||||||
#include "lpf.h"
|
#include "lpf.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
extern const int RAW = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
|
#define PITCHRATE_P 0.05
|
||||||
|
#define PITCHRATE_I 0.2
|
||||||
|
#define PITCHRATE_D 0.001
|
||||||
|
#define PITCHRATE_I_LIM 0.3
|
||||||
|
#define ROLLRATE_P PITCHRATE_P
|
||||||
|
#define ROLLRATE_I PITCHRATE_I
|
||||||
|
#define ROLLRATE_D PITCHRATE_D
|
||||||
|
#define ROLLRATE_I_LIM PITCHRATE_I_LIM
|
||||||
|
#define YAWRATE_P 0.3
|
||||||
|
#define YAWRATE_I 0.0
|
||||||
|
#define YAWRATE_D 0.0
|
||||||
|
#define YAWRATE_I_LIM 0.3
|
||||||
|
#define ROLL_P 6
|
||||||
|
#define ROLL_I 0
|
||||||
|
#define ROLL_D 0
|
||||||
|
#define PITCH_P ROLL_P
|
||||||
|
#define PITCH_I ROLL_I
|
||||||
|
#define PITCH_D ROLL_D
|
||||||
|
#define YAW_P 3
|
||||||
|
#define PITCHRATE_MAX radians(360)
|
||||||
|
#define ROLLRATE_MAX radians(360)
|
||||||
|
#define YAWRATE_MAX radians(300)
|
||||||
|
#define TILT_MAX radians(30)
|
||||||
|
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||||
|
|
||||||
|
const int RAW = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
|
||||||
int mode = STAB;
|
int mode = STAB;
|
||||||
bool armed = false;
|
bool armed = false;
|
||||||
|
|
||||||
@@ -30,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;
|
||||||
@@ -43,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
|
||||||
|
|
||||||
@@ -1,10 +1,8 @@
|
|||||||
// 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 "config.h"
|
|
||||||
#include "flix.h"
|
|
||||||
#include "quaternion.h"
|
#include "quaternion.h"
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
#include "lpf.h"
|
#include "lpf.h"
|
||||||
90
flix/flix.h
90
flix/flix.h
@@ -1,90 +0,0 @@
|
|||||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
|
||||||
// Repository: https://github.com/okalachev/flix
|
|
||||||
|
|
||||||
// All-in-one header file
|
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include <Arduino.h>
|
|
||||||
#include "vector.h"
|
|
||||||
#include "quaternion.h"
|
|
||||||
|
|
||||||
extern float t, dt;
|
|
||||||
extern float loopRate;
|
|
||||||
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
|
||||||
extern Vector gyro, acc;
|
|
||||||
extern Vector rates;
|
|
||||||
extern Quaternion attitude;
|
|
||||||
extern bool landed;
|
|
||||||
extern int mode;
|
|
||||||
extern bool armed;
|
|
||||||
extern Quaternion attitudeTarget;
|
|
||||||
extern Vector ratesTarget, ratesExtra, torqueTarget;
|
|
||||||
extern float thrustTarget;
|
|
||||||
extern float motors[4];
|
|
||||||
|
|
||||||
void print(const char* format, ...);
|
|
||||||
void pause(float duration);
|
|
||||||
void doCommand(String str, bool echo = false);
|
|
||||||
void handleInput();
|
|
||||||
void control();
|
|
||||||
void interpretControls();
|
|
||||||
void controlAttitude();
|
|
||||||
void controlRates();
|
|
||||||
void controlTorque();
|
|
||||||
const char *getModeName();
|
|
||||||
void estimate();
|
|
||||||
void applyGyro();
|
|
||||||
void applyAcc();
|
|
||||||
void setupIMU();
|
|
||||||
void configureIMU();
|
|
||||||
void readIMU();
|
|
||||||
void rotateIMU(Vector& data);
|
|
||||||
void calibrateGyroOnce();
|
|
||||||
void calibrateAccel();
|
|
||||||
void calibrateAccelOnce();
|
|
||||||
void printIMUCalibration();
|
|
||||||
void printIMUInfo();
|
|
||||||
void setupLED();
|
|
||||||
void setLED(bool on);
|
|
||||||
void blinkLED();
|
|
||||||
void prepareLogData();
|
|
||||||
void logData();
|
|
||||||
void printLogHeader();
|
|
||||||
void printLogData();
|
|
||||||
void processMavlink();
|
|
||||||
void sendMavlink();
|
|
||||||
void sendMessage(const void *msg);
|
|
||||||
void receiveMavlink();
|
|
||||||
void handleMavlink(const void *_msg);
|
|
||||||
void mavlinkPrint(const char* str);
|
|
||||||
void sendMavlinkPrint();
|
|
||||||
void setupMotors();
|
|
||||||
int getDutyCycle(float value);
|
|
||||||
void sendMotors();
|
|
||||||
bool motorsActive();
|
|
||||||
void testMotor(int n);
|
|
||||||
void setupParameters();
|
|
||||||
int parametersCount();
|
|
||||||
const char *getParameterName(int index);
|
|
||||||
float getParameter(int index);
|
|
||||||
float getParameter(const char *name);
|
|
||||||
bool setParameter(const char *name, const float value);
|
|
||||||
void syncParameters();
|
|
||||||
void printParameters();
|
|
||||||
void resetParameters();
|
|
||||||
void setupRC();
|
|
||||||
bool readRC();
|
|
||||||
void normalizeRC();
|
|
||||||
void calibrateRC();
|
|
||||||
void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const char *str);
|
|
||||||
void printRCCalibration();
|
|
||||||
void failsafe();
|
|
||||||
void rcLossFailsafe();
|
|
||||||
void descend();
|
|
||||||
void autoFailsafe();
|
|
||||||
void step();
|
|
||||||
void computeLoopRate();
|
|
||||||
void setupWiFi();
|
|
||||||
void sendWiFi(const uint8_t *buf, int len);
|
|
||||||
int receiveWiFi(uint8_t *buf, int len);
|
|
||||||
@@ -3,11 +3,17 @@
|
|||||||
|
|
||||||
// Main firmware file
|
// Main firmware file
|
||||||
|
|
||||||
#include "config.h"
|
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
#include "quaternion.h"
|
#include "quaternion.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
#include "flix.h"
|
|
||||||
|
extern float t, dt;
|
||||||
|
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
||||||
|
extern Vector gyro, acc;
|
||||||
|
extern Vector rates;
|
||||||
|
extern Quaternion attitude;
|
||||||
|
extern bool landed;
|
||||||
|
extern float motors[4];
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
@@ -15,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);
|
||||||
@@ -34,9 +38,7 @@ void loop() {
|
|||||||
control();
|
control();
|
||||||
sendMotors();
|
sendMotors();
|
||||||
handleInput();
|
handleInput();
|
||||||
#if WIFI_ENABLED
|
|
||||||
processMavlink();
|
processMavlink();
|
||||||
#endif
|
|
||||||
logData();
|
logData();
|
||||||
syncParameters();
|
syncParameters();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -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);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -3,8 +3,6 @@
|
|||||||
|
|
||||||
// Board's LED control
|
// Board's LED control
|
||||||
|
|
||||||
#include <Arduino.h>
|
|
||||||
|
|
||||||
#define BLINK_PERIOD 500000
|
#define BLINK_PERIOD 500000
|
||||||
|
|
||||||
#ifndef LED_BUILTIN
|
#ifndef LED_BUILTIN
|
||||||
@@ -3,7 +3,6 @@
|
|||||||
|
|
||||||
// In-RAM logging
|
// In-RAM logging
|
||||||
|
|
||||||
#include "flix.h"
|
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
16
flix/lpf.h
16
flix/lpf.h
@@ -5,8 +5,6 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <Arduino.h>
|
|
||||||
|
|
||||||
template <typename T> // Using template to make the filter usable for scalar and vector values
|
template <typename T> // Using template to make the filter usable for scalar and vector values
|
||||||
class LowPassFilter {
|
class LowPassFilter {
|
||||||
public:
|
public:
|
||||||
@@ -16,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);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -33,9 +22,6 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
void reset() {
|
void reset() {
|
||||||
initialized = false;
|
output = T(); // set to zero
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
|
||||||
bool initialized = false;
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -3,23 +3,15 @@
|
|||||||
|
|
||||||
// MAVLink communication
|
// MAVLink communication
|
||||||
|
|
||||||
#include <Arduino.h>
|
|
||||||
#include "config.h"
|
|
||||||
#include "flix.h"
|
|
||||||
|
|
||||||
#if WIFI_ENABLED
|
|
||||||
|
|
||||||
#include <MAVLink.h>
|
#include <MAVLink.h>
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
#define SYSTEM_ID 1
|
|
||||||
#define MAVLINK_RATE_SLOW 1
|
|
||||||
#define MAVLINK_RATE_FAST 10
|
|
||||||
|
|
||||||
extern const int AUTO, STAB;
|
|
||||||
extern uint16_t channels[16];
|
|
||||||
extern float controlTime;
|
extern float controlTime;
|
||||||
|
|
||||||
|
int mavlinkSysId = 1;
|
||||||
|
Rate telemetryFast(10);
|
||||||
|
Rate telemetrySlow(2);
|
||||||
|
|
||||||
bool mavlinkConnected = false;
|
bool mavlinkConnected = false;
|
||||||
String mavlinkPrintBuffer;
|
String mavlinkPrintBuffer;
|
||||||
|
|
||||||
@@ -34,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),
|
||||||
@@ -46,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);
|
||||||
@@ -101,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;
|
||||||
@@ -114,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);
|
||||||
}
|
}
|
||||||
@@ -127,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
|
||||||
@@ -136,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);
|
||||||
}
|
}
|
||||||
@@ -144,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
|
||||||
@@ -181,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;
|
||||||
@@ -203,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();
|
||||||
@@ -212,33 +203,31 @@ void handleMavlink(const void *_msg) {
|
|||||||
armed = motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0;
|
armed = motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* TODO:
|
|
||||||
if (msg.msgid == MAVLINK_MSG_ID_LOG_REQUEST_DATA) {
|
if (msg.msgid == MAVLINK_MSG_ID_LOG_REQUEST_DATA) {
|
||||||
mavlink_log_request_data_t m;
|
mavlink_log_request_data_t m;
|
||||||
mavlink_msg_log_request_data_decode(&msg, &m);
|
mavlink_msg_log_request_data_decode(&msg, &m);
|
||||||
if (m.target_system && m.target_system != 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);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
*/
|
|
||||||
|
|
||||||
// Handle commands
|
// Handle commands
|
||||||
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
|
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
|
||||||
mavlink_command_long_t m;
|
mavlink_command_long_t m;
|
||||||
mavlink_msg_command_long_decode(&msg, &m);
|
mavlink_msg_command_long_decode(&msg, &m);
|
||||||
if (m.target_system && m.target_system != 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);
|
||||||
}
|
}
|
||||||
@@ -257,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);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -274,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);
|
||||||
@@ -282,5 +271,3 @@ void sendMavlinkPrint() {
|
|||||||
}
|
}
|
||||||
mavlinkPrintBuffer.clear();
|
mavlinkPrintBuffer.clear();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
@@ -1,60 +0,0 @@
|
|||||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
|
||||||
// Repository: https://github.com/okalachev/flix
|
|
||||||
|
|
||||||
// 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 <Arduino.h>
|
|
||||||
#include "config.h"
|
|
||||||
#include "flix.h"
|
|
||||||
#include "util.h"
|
|
||||||
|
|
||||||
float motors[4]; // normalized motor thrusts in range [0..1]
|
|
||||||
|
|
||||||
extern const int MOTOR_REAR_LEFT = 0;
|
|
||||||
extern const int MOTOR_REAR_RIGHT = 1;
|
|
||||||
extern const int MOTOR_FRONT_RIGHT = 2;
|
|
||||||
extern const int MOTOR_FRONT_LEFT = 3;
|
|
||||||
|
|
||||||
void setupMotors() {
|
|
||||||
print("Setup Motors\n");
|
|
||||||
|
|
||||||
// configure pins
|
|
||||||
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");
|
|
||||||
}
|
|
||||||
|
|
||||||
int getDutyCycle(float value) {
|
|
||||||
value = constrain(value, 0, 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() {
|
|
||||||
return motors[0] != 0 || motors[1] != 0 || motors[2] != 0 || motors[3] != 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
void testMotor(int n) {
|
|
||||||
print("Testing motor %d\n", n);
|
|
||||||
motors[n] = 1;
|
|
||||||
delay(50); // ESP32 may need to wait until the end of the current cycle to change duty https://github.com/espressif/arduino-esp32/issues/5306
|
|
||||||
sendMotors();
|
|
||||||
pause(3);
|
|
||||||
motors[n] = 0;
|
|
||||||
sendMotors();
|
|
||||||
print("Done\n");
|
|
||||||
}
|
|
||||||
63
flix/motors.ino
Normal file
63
flix/motors.ino
Normal file
@@ -0,0 +1,63 @@
|
|||||||
|
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||||
|
// Repository: https://github.com/okalachev/flix
|
||||||
|
|
||||||
|
// PWM control for motors
|
||||||
|
|
||||||
|
#include "util.h"
|
||||||
|
|
||||||
|
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_RIGHT = 1;
|
||||||
|
const int MOTOR_FRONT_RIGHT = 2;
|
||||||
|
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);
|
||||||
|
}
|
||||||
|
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));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool motorsActive() {
|
||||||
|
return motors[0] != 0 || motors[1] != 0 || motors[2] != 0 || motors[3] != 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void testMotor(int n) {
|
||||||
|
print("Testing motor %d\n", n);
|
||||||
|
motors[n] = 1;
|
||||||
|
delay(50); // ESP32 may need to wait until the end of the current cycle to change duty https://github.com/espressif/arduino-esp32/issues/5306
|
||||||
|
sendMotors();
|
||||||
|
pause(3);
|
||||||
|
motors[n] = 0;
|
||||||
|
sendMotors();
|
||||||
|
print("Done\n");
|
||||||
|
}
|
||||||
@@ -4,29 +4,25 @@
|
|||||||
// Parameters storage in flash memory
|
// Parameters storage in flash memory
|
||||||
|
|
||||||
#include <Preferences.h>
|
#include <Preferences.h>
|
||||||
#include "flix.h"
|
|
||||||
#include "pid.h"
|
|
||||||
#include "lpf.h"
|
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
extern float channelZero[16];
|
extern 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 float tiltMax;
|
extern int wifiMode, udpLocalPort, udpRemotePort;
|
||||||
extern PID rollPID, pitchPID, yawPID;
|
extern float rcLossTimeout, descendTime;
|
||||||
extern PID rollRatePID, pitchRatePID, yawRatePID;
|
|
||||||
extern Vector maxRate;
|
|
||||||
extern Vector imuRotation;
|
|
||||||
extern Vector accBias, accScale;
|
|
||||||
extern float accWeight;
|
|
||||||
extern LowPassFilter<Vector> ratesFilter;
|
|
||||||
|
|
||||||
Preferences storage;
|
Preferences storage;
|
||||||
|
|
||||||
struct Parameter {
|
struct Parameter {
|
||||||
const char *name; // max length is 15 (Preferences key limit)
|
const char *name; // max length is 15
|
||||||
float *variable;
|
bool integer;
|
||||||
float value; // cache
|
union { float *f; int *i; }; // pointer to the variable
|
||||||
|
float cache; // what's stored in flash
|
||||||
|
Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {};
|
||||||
|
Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {};
|
||||||
|
float getValue() const { return integer ? *i : *f; };
|
||||||
|
void setValue(const float value) { if (integer) *i = value; else *f = value; };
|
||||||
};
|
};
|
||||||
|
|
||||||
Parameter parameters[] = {
|
Parameter parameters[] = {
|
||||||
@@ -53,6 +49,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},
|
||||||
@@ -63,9 +62,20 @@ 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]},
|
||||||
|
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT]},
|
||||||
|
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT]},
|
||||||
|
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT]},
|
||||||
|
{"MOT_PWM_FREQ", &pwmFrequency},
|
||||||
|
{"MOT_PWM_RES", &pwmResolution},
|
||||||
|
{"MOT_PWM_STOP", &pwmStop},
|
||||||
|
{"MOT_PWM_MIN", &pwmMin},
|
||||||
|
{"MOT_PWM_MAX", &pwmMax},
|
||||||
// rc
|
// rc
|
||||||
{"RC_ZERO_0", &channelZero[0]},
|
{"RC_ZERO_0", &channelZero[0]},
|
||||||
{"RC_ZERO_1", &channelZero[1]},
|
{"RC_ZERO_1", &channelZero[1]},
|
||||||
@@ -88,17 +98,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() {
|
||||||
|
print("Setup parameters\n");
|
||||||
storage.begin("flix", false);
|
storage.begin("flix", false);
|
||||||
// Read parameters from storage
|
// Read parameters from storage
|
||||||
for (auto ¶meter : parameters) {
|
for (auto ¶meter : 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();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -113,13 +135,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 ¶meter : parameters) {
|
for (auto ¶meter : parameters) {
|
||||||
if (strcmp(parameter.name, name) == 0) {
|
if (strcasecmp(parameter.name, name) == 0) {
|
||||||
return *parameter.variable;
|
return parameter.getValue();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return NAN;
|
return NAN;
|
||||||
@@ -127,8 +149,9 @@ float getParameter(const char *name) {
|
|||||||
|
|
||||||
bool setParameter(const char *name, const float value) {
|
bool setParameter(const char *name, const float value) {
|
||||||
for (auto ¶meter : parameters) {
|
for (auto ¶meter : 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);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -141,16 +164,18 @@ 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 ¶meter : parameters) {
|
for (auto ¶meter : 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);
|
if (isinf(parameter.getValue()) && isinf(parameter.cache)) continue; // both are Inf
|
||||||
parameter.value = *parameter.variable;
|
|
||||||
|
storage.putFloat(parameter.name, parameter.getValue());
|
||||||
|
parameter.cache = parameter.getValue(); // update cache
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void printParameters() {
|
void printParameters() {
|
||||||
for (auto ¶meter : parameters) {
|
for (auto ¶meter : parameters) {
|
||||||
print("%s = %g\n", parameter.name, *parameter.variable);
|
print("%s = %g\n", parameter.name, parameter.getValue());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -5,8 +5,6 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "Arduino.h"
|
|
||||||
#include "flix.h"
|
|
||||||
#include "lpf.h"
|
#include "lpf.h"
|
||||||
|
|
||||||
class PID {
|
class PID {
|
||||||
|
|||||||
@@ -5,7 +5,6 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <Arduino.h>
|
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
|
|
||||||
class Quaternion : public Printable {
|
class Quaternion : public Printable {
|
||||||
|
|||||||
@@ -9,15 +9,14 @@
|
|||||||
SBUS rc(Serial2);
|
SBUS rc(Serial2);
|
||||||
|
|
||||||
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() {
|
||||||
print("Setup RC\n");
|
print("Setup RC\n");
|
||||||
@@ -41,11 +40,11 @@ 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() {
|
||||||
@@ -64,7 +63,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 +84,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]);
|
||||||
}
|
}
|
||||||
@@ -3,11 +3,11 @@
|
|||||||
|
|
||||||
// Fail-safe functions
|
// Fail-safe functions
|
||||||
|
|
||||||
#include "config.h"
|
|
||||||
#include "flix.h"
|
|
||||||
|
|
||||||
extern float controlTime;
|
extern float controlTime;
|
||||||
extern const int AUTO, STAB;
|
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
|
||||||
|
|
||||||
|
float rcLossTimeout = 1;
|
||||||
|
float descendTime = 10;
|
||||||
|
|
||||||
void failsafe() {
|
void failsafe() {
|
||||||
rcLossFailsafe();
|
rcLossFailsafe();
|
||||||
@@ -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;
|
||||||
@@ -3,9 +3,6 @@
|
|||||||
|
|
||||||
// Time related functions
|
// Time related functions
|
||||||
|
|
||||||
#include "Arduino.h"
|
|
||||||
#include "flix.h"
|
|
||||||
|
|
||||||
float t = NAN; // current time, s
|
float t = NAN; // current time, s
|
||||||
float dt; // time delta with the previous step, s
|
float dt; // time delta with the previous step, s
|
||||||
float loopRate; // Hz
|
float loopRate; // Hz
|
||||||
14
flix/util.h
14
flix/util.h
@@ -8,24 +8,24 @@
|
|||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <soc/soc.h>
|
#include <soc/soc.h>
|
||||||
#include <soc/rtc_cntl_reg.h>
|
#include <soc/rtc_cntl_reg.h>
|
||||||
#include "flix.h"
|
|
||||||
|
|
||||||
const float ONE_G = 9.80665;
|
const float ONE_G = 9.80665;
|
||||||
|
extern float t;
|
||||||
|
|
||||||
inline float mapf(float x, float in_min, float in_max, float out_min, float out_max) {
|
float mapf(float x, float in_min, float in_max, float out_min, float out_max) {
|
||||||
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline bool invalid(float x) {
|
bool invalid(float x) {
|
||||||
return !isfinite(x);
|
return !isfinite(x);
|
||||||
}
|
}
|
||||||
|
|
||||||
inline bool valid(float x) {
|
bool valid(float x) {
|
||||||
return isfinite(x);
|
return isfinite(x);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Wrap angle to [-PI, PI)
|
// Wrap angle to [-PI, PI)
|
||||||
inline float wrapAngle(float angle) {
|
float wrapAngle(float angle) {
|
||||||
angle = fmodf(angle, 2 * PI);
|
angle = fmodf(angle, 2 * PI);
|
||||||
if (angle > PI) {
|
if (angle > PI) {
|
||||||
angle -= 2 * PI;
|
angle -= 2 * PI;
|
||||||
@@ -36,12 +36,12 @@ inline float wrapAngle(float angle) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Disable reset on low voltage
|
// Disable reset on low voltage
|
||||||
inline void disableBrownOut() {
|
void disableBrownOut() {
|
||||||
REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA);
|
REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Trim and split string by spaces
|
// Trim and split string by spaces
|
||||||
inline void splitString(String& str, String& token0, String& token1, String& token2) {
|
void splitString(String& str, String& token0, String& token1, String& token2) {
|
||||||
str.trim();
|
str.trim();
|
||||||
char chars[str.length() + 1];
|
char chars[str.length() + 1];
|
||||||
str.toCharArray(chars, str.length() + 1);
|
str.toCharArray(chars, str.length() + 1);
|
||||||
|
|||||||
@@ -5,8 +5,6 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <Arduino.h>
|
|
||||||
|
|
||||||
class Vector : public Printable {
|
class Vector : public Printable {
|
||||||
public:
|
public:
|
||||||
float x, y, z;
|
float x, y, z;
|
||||||
@@ -125,5 +123,5 @@ public:
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
inline Vector operator * (const float a, const Vector& b) { return b * a; }
|
Vector operator * (const float a, const Vector& b) { return b * a; }
|
||||||
inline Vector operator + (const float a, const Vector& b) { return b + a; }
|
Vector operator + (const float a, const Vector& b) { return b + a; }
|
||||||
|
|||||||
@@ -1,48 +0,0 @@
|
|||||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
|
||||||
// Repository: https://github.com/okalachev/flix
|
|
||||||
|
|
||||||
// Wi-Fi support
|
|
||||||
|
|
||||||
#include "config.h"
|
|
||||||
#include "flix.h"
|
|
||||||
|
|
||||||
#if WIFI_ENABLED
|
|
||||||
|
|
||||||
#include <WiFi.h>
|
|
||||||
#include <WiFiAP.h>
|
|
||||||
#include <WiFiUdp.h>
|
|
||||||
|
|
||||||
WiFiUDP udp;
|
|
||||||
|
|
||||||
extern bool mavlinkConnected;
|
|
||||||
|
|
||||||
void setupWiFi() {
|
|
||||||
print("Setup Wi-Fi\n");
|
|
||||||
WiFi.softAP(WIFI_SSID, WIFI_PASSWORD);
|
|
||||||
udp.begin(WIFI_UDP_PORT);
|
|
||||||
}
|
|
||||||
|
|
||||||
void sendWiFi(const uint8_t *buf, int len) {
|
|
||||||
if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return;
|
|
||||||
udp.beginPacket(udp.remoteIP() ? udp.remoteIP() : WIFI_UDP_REMOTE_ADDR, WIFI_UDP_REMOTE_PORT);
|
|
||||||
udp.write(buf, len);
|
|
||||||
udp.endPacket();
|
|
||||||
}
|
|
||||||
|
|
||||||
int receiveWiFi(uint8_t *buf, int len) {
|
|
||||||
udp.parsePacket();
|
|
||||||
return udp.read(buf, len);
|
|
||||||
}
|
|
||||||
|
|
||||||
void printWiFiInfo() {
|
|
||||||
print("MAC: %s\n", WiFi.softAPmacAddress().c_str());
|
|
||||||
print("SSID: %s\n", WiFi.softAPSSID().c_str());
|
|
||||||
print("Password: %s\n", WIFI_PASSWORD);
|
|
||||||
print("Clients: %d\n", WiFi.softAPgetStationNum());
|
|
||||||
print("Status: %d\n", WiFi.status());
|
|
||||||
print("IP: %s\n", WiFi.softAPIP().toString().c_str());
|
|
||||||
print("Remote IP: %s\n", udp.remoteIP().toString().c_str());
|
|
||||||
print("MAVLink connected: %d\n", mavlinkConnected);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
76
flix/wifi.ino
Normal file
76
flix/wifi.ino
Normal file
@@ -0,0 +1,76 @@
|
|||||||
|
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||||
|
// Repository: https://github.com/okalachev/flix
|
||||||
|
|
||||||
|
// Wi-Fi communication
|
||||||
|
|
||||||
|
#include <WiFi.h>
|
||||||
|
#include <WiFiAP.h>
|
||||||
|
#include <WiFiUdp.h>
|
||||||
|
#include "Preferences.h"
|
||||||
|
|
||||||
|
extern Preferences storage; // use the main preferences storage
|
||||||
|
|
||||||
|
const int W_DISABLED = 0, W_AP = 1, W_STA = 2;
|
||||||
|
int wifiMode = W_AP;
|
||||||
|
int udpLocalPort = 14550;
|
||||||
|
int udpRemotePort = 14550;
|
||||||
|
IPAddress udpRemoteIP = "255.255.255.255";
|
||||||
|
|
||||||
|
WiFiUDP udp;
|
||||||
|
|
||||||
|
void setupWiFi() {
|
||||||
|
print("Setup Wi-Fi\n");
|
||||||
|
if (wifiMode == W_AP) {
|
||||||
|
WiFi.softAP(storage.getString("WIFI_AP_SSID", "flix").c_str(), storage.getString("WIFI_AP_PASS", "flixwifi").c_str());
|
||||||
|
} else if (wifiMode == W_STA) {
|
||||||
|
WiFi.begin(storage.getString("WIFI_STA_SSID", "").c_str(), storage.getString("WIFI_STA_PASS", "").c_str());
|
||||||
|
}
|
||||||
|
udp.begin(udpLocalPort);
|
||||||
|
}
|
||||||
|
|
||||||
|
void sendWiFi(const uint8_t *buf, int len) {
|
||||||
|
if (WiFi.softAPgetStationNum() == 0 && !WiFi.isConnected()) return;
|
||||||
|
udp.beginPacket(udpRemoteIP, udpRemotePort);
|
||||||
|
udp.write(buf, len);
|
||||||
|
udp.endPacket();
|
||||||
|
}
|
||||||
|
|
||||||
|
int receiveWiFi(uint8_t *buf, int len) {
|
||||||
|
udp.parsePacket();
|
||||||
|
if (udp.remoteIP()) udpRemoteIP = udp.remoteIP();
|
||||||
|
return udp.read(buf, len);
|
||||||
|
}
|
||||||
|
|
||||||
|
void printWiFiInfo() {
|
||||||
|
if (WiFi.getMode() == WIFI_MODE_AP) {
|
||||||
|
print("Mode: Access Point (AP)\n");
|
||||||
|
print("MAC: %s\n", WiFi.softAPmacAddress().c_str());
|
||||||
|
print("SSID: %s\n", WiFi.softAPSSID().c_str());
|
||||||
|
print("Password: ***\n");
|
||||||
|
print("Clients: %d\n", WiFi.softAPgetStationNum());
|
||||||
|
print("IP: %s\n", WiFi.softAPIP().toString().c_str());
|
||||||
|
} else if (WiFi.getMode() == WIFI_MODE_STA) {
|
||||||
|
print("Mode: Client (STA)\n");
|
||||||
|
print("Connected: %d\n", WiFi.isConnected());
|
||||||
|
print("MAC: %s\n", WiFi.macAddress().c_str());
|
||||||
|
print("SSID: %s\n", WiFi.SSID().c_str());
|
||||||
|
print("Password: ***\n");
|
||||||
|
print("IP: %s\n", WiFi.localIP().toString().c_str());
|
||||||
|
} else {
|
||||||
|
print("Mode: Disabled\n");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
print("Remote IP: %s\n", udpRemoteIP.toString().c_str());
|
||||||
|
print("MAVLink connected: %d\n", mavlinkConnected);
|
||||||
|
}
|
||||||
|
|
||||||
|
void configWiFi(bool ap, const char *ssid, const char *password) {
|
||||||
|
if (ap) {
|
||||||
|
storage.putString("WIFI_AP_SSID", ssid);
|
||||||
|
storage.putString("WIFI_AP_PASS", password);
|
||||||
|
} else {
|
||||||
|
storage.putString("WIFI_STA_SSID", ssid);
|
||||||
|
storage.putString("WIFI_STA_PASS", password);
|
||||||
|
}
|
||||||
|
print("✓ Reboot to apply new settings\n");
|
||||||
|
}
|
||||||
@@ -10,23 +10,9 @@ list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}")
|
|||||||
|
|
||||||
set(FLIX_SOURCE_DIR ../flix)
|
set(FLIX_SOURCE_DIR ../flix)
|
||||||
include_directories(${FLIX_SOURCE_DIR})
|
include_directories(${FLIX_SOURCE_DIR})
|
||||||
set(FLIX_SOURCE_DIR ../flix)
|
|
||||||
include_directories(${FLIX_SOURCE_DIR})
|
|
||||||
set(FLIX_SOURCES
|
|
||||||
${FLIX_SOURCE_DIR}/cli.cpp
|
|
||||||
${FLIX_SOURCE_DIR}/control.cpp
|
|
||||||
${FLIX_SOURCE_DIR}/estimate.cpp
|
|
||||||
${FLIX_SOURCE_DIR}/safety.cpp
|
|
||||||
${FLIX_SOURCE_DIR}/log.cpp
|
|
||||||
${FLIX_SOURCE_DIR}/mavlink.cpp
|
|
||||||
${FLIX_SOURCE_DIR}/motors.cpp
|
|
||||||
${FLIX_SOURCE_DIR}/parameters.cpp
|
|
||||||
${FLIX_SOURCE_DIR}/rc.cpp
|
|
||||||
${FLIX_SOURCE_DIR}/time.cpp
|
|
||||||
)
|
|
||||||
|
|
||||||
set(CMAKE_BUILD_TYPE RelWithDebInfo)
|
set(CMAKE_BUILD_TYPE RelWithDebInfo)
|
||||||
add_library(flix SHARED simulator.cpp ${FLIX_SOURCES})
|
add_library(flix SHARED simulator.cpp)
|
||||||
target_link_libraries(flix ${GAZEBO_LIBRARIES} ${SDL2_LIBRARIES})
|
target_link_libraries(flix ${GAZEBO_LIBRARIES} ${SDL2_LIBRARIES})
|
||||||
target_include_directories(flix PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
|
target_include_directories(flix PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
target_compile_options(flix PRIVATE -Wno-address-of-packed-member) # disable unneeded mavlink warnings
|
target_compile_options(flix PRIVATE -Wno-address-of-packed-member) # disable unneeded mavlink warnings
|
||||||
|
|||||||
@@ -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"); };
|
||||||
|
|||||||
@@ -18,6 +18,18 @@
|
|||||||
#include "Arduino.h"
|
#include "Arduino.h"
|
||||||
#include "flix.h"
|
#include "flix.h"
|
||||||
|
|
||||||
|
#include "cli.ino"
|
||||||
|
#include "control.ino"
|
||||||
|
#include "estimate.ino"
|
||||||
|
#include "safety.ino"
|
||||||
|
#include "log.ino"
|
||||||
|
#include "lpf.h"
|
||||||
|
#include "mavlink.ino"
|
||||||
|
#include "motors.ino"
|
||||||
|
#include "parameters.ino"
|
||||||
|
#include "rc.ino"
|
||||||
|
#include "time.ino"
|
||||||
|
|
||||||
using ignition::math::Vector3d;
|
using ignition::math::Vector3d;
|
||||||
using namespace gazebo;
|
using namespace gazebo;
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|||||||
@@ -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));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -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:
|
||||||
|
|||||||
@@ -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:
|
||||||
|
|||||||
@@ -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.
|
|
||||||
|
|||||||
@@ -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()
|
||||||
|
|||||||
Reference in New Issue
Block a user