Compare commits
52 Commits
remove-esp
...
0730ceeffa
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
0730ceeffa | ||
|
|
a687303062 | ||
|
|
b2daf2587f | ||
|
|
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 | ||
|
|
2a8faf5759 | ||
|
|
f4e58a652a | ||
|
|
6c46328da1 | ||
|
|
c8e5e08b03 | ||
|
|
a5e3dfcf69 | ||
|
|
d6e8be0c05 | ||
|
|
68d16855df | ||
|
|
0547ea548b | ||
|
|
c02dba6812 | ||
|
|
f1dc4a0400 | ||
|
|
158827ac55 | ||
|
|
36ca30c3e4 | ||
|
|
48711b55e1 | ||
|
|
4d583185a9 | ||
|
|
d757ffa853 | ||
|
|
5352386486 | ||
|
|
9b5872740f | ||
|
|
31dbdaf241 | ||
|
|
f4b56262b1 | ||
|
|
49039f752d | ||
|
|
348721acc9 | ||
|
|
774144c430 | ||
|
|
0e6651ab82 | ||
|
|
1a017ccb97 |
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,8 @@
|
|||||||
"MD024": false,
|
"MD024": false,
|
||||||
"MD033": false,
|
"MD033": false,
|
||||||
"MD034": false,
|
"MD034": false,
|
||||||
|
"MD040": false,
|
||||||
|
"MD059": false,
|
||||||
"MD044": {
|
"MD044": {
|
||||||
"html_elements": false,
|
"html_elements": false,
|
||||||
"code_blocks": false,
|
"code_blocks": false,
|
||||||
@@ -64,5 +66,6 @@
|
|||||||
"PX4"
|
"PX4"
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
"MD045": false
|
"MD045": false,
|
||||||
|
"MD060": false
|
||||||
}
|
}
|
||||||
|
|||||||
54
.vscode/c_cpp_properties.json
vendored
@@ -6,19 +6,18 @@
|
|||||||
"${workspaceFolder}/flix",
|
"${workspaceFolder}/flix",
|
||||||
"${workspaceFolder}/gazebo",
|
"${workspaceFolder}/gazebo",
|
||||||
"${workspaceFolder}/tools/**",
|
"${workspaceFolder}/tools/**",
|
||||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
|
||||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
|
||||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32",
|
||||||
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**",
|
"~/.arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**",
|
||||||
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
|
||||||
"~/Arduino/libraries/**",
|
"~/Arduino/libraries/**",
|
||||||
"/usr/include/gazebo-11/",
|
"/usr/include/gazebo-11/",
|
||||||
"/usr/include/ignition/math6/"
|
"/usr/include/ignition/math6/"
|
||||||
],
|
],
|
||||||
"forcedInclude": [
|
"forcedInclude": [
|
||||||
"${workspaceFolder}/.vscode/intellisense.h",
|
"${workspaceFolder}/.vscode/intellisense.h",
|
||||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
|
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32/Arduino.h",
|
||||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h",
|
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32/pins_arduino.h",
|
||||||
"${workspaceFolder}/flix/cli.ino",
|
"${workspaceFolder}/flix/cli.ino",
|
||||||
"${workspaceFolder}/flix/control.ino",
|
"${workspaceFolder}/flix/control.ino",
|
||||||
"${workspaceFolder}/flix/estimate.ino",
|
"${workspaceFolder}/flix/estimate.ino",
|
||||||
@@ -31,9 +30,10 @@
|
|||||||
"${workspaceFolder}/flix/rc.ino",
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
"${workspaceFolder}/flix/time.ino",
|
"${workspaceFolder}/flix/time.ino",
|
||||||
"${workspaceFolder}/flix/wifi.ino",
|
"${workspaceFolder}/flix/wifi.ino",
|
||||||
"${workspaceFolder}/flix/parameters.ino"
|
"${workspaceFolder}/flix/parameters.ino",
|
||||||
|
"${workspaceFolder}/flix/safety.ino"
|
||||||
],
|
],
|
||||||
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
|
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2511/bin/xtensa-esp32-elf-g++",
|
||||||
"cStandard": "c11",
|
"cStandard": "c11",
|
||||||
"cppStandard": "c++17",
|
"cppStandard": "c++17",
|
||||||
"defines": [
|
"defines": [
|
||||||
@@ -53,19 +53,18 @@
|
|||||||
"name": "Mac",
|
"name": "Mac",
|
||||||
"includePath": [
|
"includePath": [
|
||||||
"${workspaceFolder}/flix",
|
"${workspaceFolder}/flix",
|
||||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
|
||||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
|
||||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32",
|
||||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/include/**",
|
"~/Library/Arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**",
|
||||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
|
||||||
"~/Documents/Arduino/libraries/**",
|
"~/Documents/Arduino/libraries/**",
|
||||||
"/opt/homebrew/include/gazebo-11/",
|
"/opt/homebrew/include/gazebo-11/",
|
||||||
"/opt/homebrew/include/ignition/math6/"
|
"/opt/homebrew/include/ignition/math6/"
|
||||||
],
|
],
|
||||||
"forcedInclude": [
|
"forcedInclude": [
|
||||||
"${workspaceFolder}/.vscode/intellisense.h",
|
"${workspaceFolder}/.vscode/intellisense.h",
|
||||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32/Arduino.h",
|
||||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h",
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32/pins_arduino.h",
|
||||||
"${workspaceFolder}/flix/flix.ino",
|
"${workspaceFolder}/flix/flix.ino",
|
||||||
"${workspaceFolder}/flix/cli.ino",
|
"${workspaceFolder}/flix/cli.ino",
|
||||||
"${workspaceFolder}/flix/control.ino",
|
"${workspaceFolder}/flix/control.ino",
|
||||||
@@ -78,9 +77,10 @@
|
|||||||
"${workspaceFolder}/flix/rc.ino",
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
"${workspaceFolder}/flix/time.ino",
|
"${workspaceFolder}/flix/time.ino",
|
||||||
"${workspaceFolder}/flix/wifi.ino",
|
"${workspaceFolder}/flix/wifi.ino",
|
||||||
"${workspaceFolder}/flix/parameters.ino"
|
"${workspaceFolder}/flix/parameters.ino",
|
||||||
|
"${workspaceFolder}/flix/safety.ino"
|
||||||
],
|
],
|
||||||
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
|
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2511/bin/xtensa-esp32-elf-g++",
|
||||||
"cStandard": "c11",
|
"cStandard": "c11",
|
||||||
"cppStandard": "c++17",
|
"cppStandard": "c++17",
|
||||||
"defines": [
|
"defines": [
|
||||||
@@ -103,17 +103,16 @@
|
|||||||
"${workspaceFolder}/flix",
|
"${workspaceFolder}/flix",
|
||||||
"${workspaceFolder}/gazebo",
|
"${workspaceFolder}/gazebo",
|
||||||
"${workspaceFolder}/tools/**",
|
"${workspaceFolder}/tools/**",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**",
|
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
|
||||||
"~/Documents/Arduino/libraries/**"
|
"~/Documents/Arduino/libraries/**"
|
||||||
],
|
],
|
||||||
"forcedInclude": [
|
"forcedInclude": [
|
||||||
"${workspaceFolder}/.vscode/intellisense.h",
|
"${workspaceFolder}/.vscode/intellisense.h",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32/Arduino.h",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h",
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32/pins_arduino.h",
|
||||||
"${workspaceFolder}/flix/cli.ino",
|
"${workspaceFolder}/flix/cli.ino",
|
||||||
"${workspaceFolder}/flix/control.ino",
|
"${workspaceFolder}/flix/control.ino",
|
||||||
"${workspaceFolder}/flix/estimate.ino",
|
"${workspaceFolder}/flix/estimate.ino",
|
||||||
@@ -126,9 +125,10 @@
|
|||||||
"${workspaceFolder}/flix/rc.ino",
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
"${workspaceFolder}/flix/time.ino",
|
"${workspaceFolder}/flix/time.ino",
|
||||||
"${workspaceFolder}/flix/wifi.ino",
|
"${workspaceFolder}/flix/wifi.ino",
|
||||||
"${workspaceFolder}/flix/parameters.ino"
|
"${workspaceFolder}/flix/parameters.ino",
|
||||||
|
"${workspaceFolder}/flix/safety.ino"
|
||||||
],
|
],
|
||||||
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++.exe",
|
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2511/bin/xtensa-esp32-elf-g++.exe",
|
||||||
"cStandard": "c11",
|
"cStandard": "c11",
|
||||||
"cppStandard": "c++17",
|
"cppStandard": "c++17",
|
||||||
"defines": [
|
"defines": [
|
||||||
|
|||||||
6
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
|
||||||
@@ -32,7 +32,7 @@ simulator: build_simulator
|
|||||||
gazebo --verbose ${CURDIR}/gazebo/flix.world
|
gazebo --verbose ${CURDIR}/gazebo/flix.world
|
||||||
|
|
||||||
log:
|
log:
|
||||||
PORT=$(PORT) tools/grab_log.py
|
tools/log.py
|
||||||
|
|
||||||
plot:
|
plot:
|
||||||
plotjuggler -d $(shell ls -t tools/log/*.csv | head -n1)
|
plotjuggler -d $(shell ls -t tools/log/*.csv | head -n1)
|
||||||
|
|||||||
106
README.md
@@ -1,6 +1,9 @@
|
|||||||
# Flix
|
<!-- markdownlint-disable MD041 -->
|
||||||
|
|
||||||
**Flix** (*flight + X*) — making an open source ESP32-based quadcopter from scratch.
|
<p align="center">
|
||||||
|
<img src="docs/img/flix.svg" width=180 alt="Flix logo"><br>
|
||||||
|
<b>Flix</b> (<i>flight + X</i>) — open source ESP32-based quadcopter made from scratch.
|
||||||
|
</p>
|
||||||
|
|
||||||
<table>
|
<table>
|
||||||
<tr>
|
<tr>
|
||||||
@@ -18,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
|
||||||
|
|
||||||
@@ -52,25 +53,29 @@ The simulator is implemented using Gazebo and runs the original Arduino code:
|
|||||||
|
|
||||||
<img src="docs/img/simulator1.png" width=500 alt="Flix simulator">
|
<img src="docs/img/simulator1.png" width=500 alt="Flix simulator">
|
||||||
|
|
||||||
## Articles
|
## Documentation
|
||||||
|
|
||||||
|
1. [Assembly instructions](docs/assembly.md).
|
||||||
|
2. [Usage: build, setup and flight](docs/usage.md).
|
||||||
|
3. [Simulation](gazebo/README.md).
|
||||||
|
4. [Python library](tools/pyflix/README.md).
|
||||||
|
|
||||||
|
Additional articles:
|
||||||
|
|
||||||
* [Assembly instructions](docs/assembly.md).
|
|
||||||
* [Usage: build, setup and flight](docs/usage.md).
|
|
||||||
* [Troubleshooting](docs/troubleshooting.md).
|
|
||||||
* [Firmware architecture overview](docs/firmware.md).
|
|
||||||
* [Python library tutorial](tools/pyflix/README.md).
|
|
||||||
* [Log analysis](docs/log.md).
|
|
||||||
* [User builds gallery](docs/user.md).
|
* [User builds gallery](docs/user.md).
|
||||||
|
* [Firmware architectural overview](docs/firmware.md).
|
||||||
|
* [Troubleshooting](docs/troubleshooting.md).
|
||||||
|
* [Log analysis](docs/log.md).
|
||||||
|
|
||||||
## Components
|
## Components
|
||||||
|
|
||||||
|Type|Part|Image|Quantity|
|
|Type|Part|Image|Quantity|
|
||||||
|-|-|:-:|:-:|
|
|-|-|:-:|:-:|
|
||||||
|Microcontroller board|ESP32 Mini|<img src="docs/img/esp32.jpg" width=100>|1|
|
|Microcontroller board|ESP32 Mini|<img src="docs/img/esp32.jpg" width=100>|1|
|
||||||
|IMU (and barometer²) board|GY‑91, MPU-9265 (or other MPU‑9250/MPU‑6500 board)<br>ICM20948V2 (ICM‑20948)³<br>GY-521 (MPU-6050)³⁻¹|<img src="docs/img/gy-91.jpg" width=90 align=center><br><img src="docs/img/icm-20948.jpg" width=100><br><img src="docs/img/gy-521.jpg" width=100>|1|
|
|IMU (and barometer¹) board|GY‑91, MPU-9265 (or other MPU‑9250/MPU‑6500 board)<br>ICM20948V2 (ICM‑20948)³<br>GY-521 (MPU-6050)³⁻¹|<img src="docs/img/gy-91.jpg" width=90 align=center><br><img src="docs/img/icm-20948.jpg" width=100><br><img src="docs/img/gy-521.jpg" width=100>|1|
|
||||||
|<span style="background:yellow">Buck-boost converter</span> (recommended)|To be determined, output 5V or 3.3V, see [user-contributed schematics](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612179508274&cot=14)|<img src="docs/img/buck-boost.jpg" width=100>|1|
|
|Boost converter (optional, for more stable power supply)|5V output|<img src="docs/img/buck-boost.jpg" width=100>|1|
|
||||||
|Motor|8520 3.7V brushed motor (shaft 0.8mm).<br>Motor with exact 3.7V voltage is needed, not ranged working voltage (3.7V — 6V).|<img src="docs/img/motor.jpeg" width=100>|4|
|
|Motor|8520 3.7V brushed motor.<br>Motor with exact 3.7V voltage is needed, not ranged working voltage (3.7V — 6V).<br>Make sure the motor shaft diameter and propeller hole diameter match!|<img src="docs/img/motor.jpeg" width=100>|4|
|
||||||
|Propeller|Hubsan 55 mm|<img src="docs/img/prop.jpg" width=100>|4|
|
|Propeller|55 mm (alternatively 65 mm)|<img src="docs/img/prop.jpg" width=100>|4|
|
||||||
|MOSFET (transistor)|100N03A or [analog](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4|
|
|MOSFET (transistor)|100N03A or [analog](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4|
|
||||||
|Pull-down resistor|10 kΩ|<img src="docs/img/resistor10k.jpg" width=100>|4|
|
|Pull-down resistor|10 kΩ|<img src="docs/img/resistor10k.jpg" width=100>|4|
|
||||||
|3.7V Li-Po battery|LW 952540 (or any compatible by the size)|<img src="docs/img/battery.jpg" width=100>|1|
|
|3.7V Li-Po battery|LW 952540 (or any compatible by the size)|<img src="docs/img/battery.jpg" width=100>|1|
|
||||||
@@ -78,19 +83,17 @@ The simulator is implemented using Gazebo and runs the original Arduino code:
|
|||||||
|Li-Po Battery charger|Any|<img src="docs/img/charger.jpg" width=100>|1|
|
|Li-Po Battery charger|Any|<img src="docs/img/charger.jpg" width=100>|1|
|
||||||
|Screws for IMU board mounting|M3x5|<img src="docs/img/screw-m3.jpg" width=100>|2|
|
|Screws for IMU board mounting|M3x5|<img src="docs/img/screw-m3.jpg" width=100>|2|
|
||||||
|Screws for frame assembly|M1.4x5|<img src="docs/img/screw-m1.4.jpg" height=30 align=center>|4|
|
|Screws for frame assembly|M1.4x5|<img src="docs/img/screw-m1.4.jpg" height=30 align=center>|4|
|
||||||
|Frame main part|3D printed⁴:<br>[`flix-frame-1.1.stl`](docs/assets/flix-frame-1.1.stl) [`flix-frame-1.1.step`](docs/assets/flix-frame-1.1.step)<br>Recommended settings: layer 0.2 mm, line 0.4 mm, infill 100%.|<img src="docs/img/frame1.jpg" width=100>|1|
|
|Frame main part|3D printed²: [`stl`](docs/assets/flix-frame-1.1.stl) [`step`](docs/assets/flix-frame-1.1.step)<br>Recommended settings: layer 0.2 mm, line 0.4 mm, infill 100%.|<img src="docs/img/frame1.jpg" width=100>|1|
|
||||||
|Frame top part|3D printed:<br>[`esp32-holder.stl`](docs/assets/esp32-holder.stl) [`esp32-holder.step`](docs/assets/esp32-holder.step)|<img src="docs/img/esp32-holder.jpg" width=100>|1|
|
|Frame top part|3D printed: [`stl`](docs/assets/esp32-holder.stl) [`step`](docs/assets/esp32-holder.step)|<img src="docs/img/esp32-holder.jpg" width=100>|1|
|
||||||
|Washer for IMU board mounting|3D printed:<br>[`washer-m3.stl`](docs/assets/washer-m3.stl) [`washer-m3.step`](docs/assets/washer-m3.step)|<img src="docs/img/washer-m3.jpg" width=100>|2|
|
|Washer for IMU board mounting|3D printed: [`stl`](docs/assets/washer-m3.stl) [`step`](docs/assets/washer-m3.step)|<img src="docs/img/washer-m3.jpg" width=100>|2|
|
||||||
|Controller (recommended)|CC2500 transmitter, like BetaFPV LiteRadio CC2500 (RC receiver/Wi-Fi).<br>Two-sticks gamepad (Wi-Fi only) — see [recommended gamepads](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/joystick.html#supported-joysticks).<br>Other⁵|<img src="docs/img/betafpv.jpg" width=100><img src="docs/img/logitech.jpg" width=80>|1|
|
|Controller (recommended)|CC2500 transmitter, like BetaFPV LiteRadio CC2500 (RC receiver/Wi-Fi).<br>Two-sticks gamepad (Wi-Fi only) — see [recommended gamepads](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/joystick.html#supported-joysticks).<br>Other⁵|<img src="docs/img/betafpv.jpg" width=100><img src="docs/img/logitech.jpg" width=80>|1|
|
||||||
|*RC receiver (optional)*|*DF500 or other⁵*|<img src="docs/img/rx.jpg" width=100>|1|
|
|*RC receiver (optional)*|*DF500 or other³*|<img src="docs/img/rx.jpg" width=100>|1|
|
||||||
|Wires|28 AWG recommended|<img src="docs/img/wire-28awg.jpg" width=100>||
|
|Wires|28 AWG recommended|<img src="docs/img/wire-28awg.jpg" width=100>||
|
||||||
|Tape, double-sided tape||||
|
|Tape, double-sided tape||||
|
||||||
|
|
||||||
*² — barometer is not used for now.*<br>
|
*¹ — barometer is not used for now.*<br>
|
||||||
*³ — change `MPU9250` to `ICM20948` or `MPU6050` in `imu.ino` file for using the appropriate boards.*<br>
|
*² — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*<br>
|
||||||
*³⁻¹ — MPU-6050 supports I²C interface only (not recommended). To use it change IMU declaration to `MPU6050 IMU(Wire)`.*<br>
|
*³ — you also may use any transmitter-receiver pair with SBUS interface.*
|
||||||
*⁴ — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*<br>
|
|
||||||
*⁵ — you also may use any transmitter-receiver pair with SBUS interface.*
|
|
||||||
|
|
||||||
Tools required for assembly:
|
Tools required for assembly:
|
||||||
|
|
||||||
@@ -100,7 +103,7 @@ Tools required for assembly:
|
|||||||
* Screwdrivers.
|
* Screwdrivers.
|
||||||
* Multimeter.
|
* Multimeter.
|
||||||
|
|
||||||
Feel free to modify the design and or code, and create your own improved versions of Flix! Send your results to the [official Telegram chat](https://t.me/opensourcequadcopterchat), or directly to the author ([E-mail](mailto:okalachev@gmail.com), [Telegram](https://t.me/okalachev)).
|
Feel free to modify the design and or code, and create your own improved versions. Send your results to the [official Telegram chat](https://t.me/opensourcequadcopterchat), or directly to the author ([E-mail](mailto:okalachev@gmail.com), [Telegram](https://t.me/okalachev)).
|
||||||
|
|
||||||
## Schematics
|
## Schematics
|
||||||
|
|
||||||
@@ -108,7 +111,7 @@ Feel free to modify the design and or code, and create your own improved version
|
|||||||
|
|
||||||
<img src="docs/img/schematics1.svg" width=700 alt="Flix version 1 schematics">
|
<img src="docs/img/schematics1.svg" width=700 alt="Flix version 1 schematics">
|
||||||
|
|
||||||
*(Dashed is optional).*
|
*(Dashed elements are optional).*
|
||||||
|
|
||||||
Motor connection scheme:
|
Motor connection scheme:
|
||||||
|
|
||||||
@@ -116,8 +119,6 @@ Motor connection scheme:
|
|||||||
|
|
||||||
You can see a user-contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612338222067&cot=14) of the drone.
|
You can see a user-contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612338222067&cot=14) of the drone.
|
||||||
|
|
||||||
See [assembly guide](docs/assembly.md) for instructions on assembling the drone.
|
|
||||||
|
|
||||||
### Notes
|
### Notes
|
||||||
|
|
||||||
* Power ESP32 Mini with Li-Po battery using VCC (+) and GND (-) pins.
|
* Power ESP32 Mini with Li-Po battery using VCC (+) and GND (-) pins.
|
||||||
@@ -135,14 +136,15 @@ See [assembly guide](docs/assembly.md) for instructions on assembling the drone.
|
|||||||
* Solder pull-down resistors to the MOSFETs.
|
* Solder pull-down resistors to the MOSFETs.
|
||||||
* Connect the motors to the ESP32 Mini using MOSFETs, by following scheme:
|
* Connect the motors to the ESP32 Mini using MOSFETs, by following scheme:
|
||||||
|
|
||||||
|Motor|Position|Direction|Wires|GPIO|
|
|Motor|Position|Direction|Prop type|Motor wires|GPIO|
|
||||||
|-|-|-|-|-|
|
|-|-|-|-|-|-|
|
||||||
|Motor 0|Rear left|Counter-clockwise|Black & White|GPIO12 (*TDI*)|
|
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 *(TDI)*|
|
||||||
|Motor 1|Rear right|Clockwise|Blue & Red|GPIO13 (*TCK*)|
|
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 *(TCK)*|
|
||||||
|Motor 2|Front right|Counter-clockwise|Black & White|GPIO14 (*TMS*)|
|
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 *(TMS)*|
|
||||||
|Motor 3|Front left|Clockwise|Blue & Red|GPIO15 (*TD0*)|
|
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 *(TD0)*|
|
||||||
|
|
||||||
Counter-clockwise motors have black and white wires and clockwise motors have blue and red wires.
|
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.
|
||||||
|
|
||||||
* Optionally connect the RC receiver to the ESP32's UART2:
|
* Optionally connect the RC receiver to the ESP32's UART2:
|
||||||
|
|
||||||
@@ -150,32 +152,18 @@ See [assembly guide](docs/assembly.md) for instructions on assembling the drone.
|
|||||||
|-|-|
|
|-|-|
|
||||||
|GND|GND|
|
|GND|GND|
|
||||||
|VIN|VCC (or 3.3V depending on the receiver)|
|
|VIN|VCC (or 3.3V depending on the receiver)|
|
||||||
|Signal (TX)|GPIO4⁶|
|
|Signal (TX)|GPIO4¹|
|
||||||
|
|
||||||
*⁶ — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.*
|
*¹ — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.*
|
||||||
|
|
||||||
### IMU placement
|
## Resources
|
||||||
|
|
||||||
Default IMU orientation in the code is **LFD** (Left-Forward-Down):
|
* Telegram channel on developing the drone and the flight controller (in Russian): https://t.me/opensourcequadcopter.
|
||||||
|
* Official Telegram chat: https://t.me/opensourcequadcopterchat.
|
||||||
<img src="docs/img/gy91-lfd.svg" width=400 alt="GY-91 axes">
|
* Detailed article on Habr.com about the development of the drone (in Russian): https://habr.com/ru/articles/814127/.
|
||||||
|
|
||||||
In case of using other IMU orientation, modify the `rotateIMU` function in the `imu.ino` file.
|
|
||||||
|
|
||||||
See [FlixPeriph documentation](https://github.com/okalachev/flixperiph?tab=readme-ov-file#imu-axes-orientation) to learn axis orientation of other IMU boards.
|
|
||||||
|
|
||||||
## Materials
|
|
||||||
|
|
||||||
Subscribe to the Telegram channel on developing the drone and the flight controller (in Russian): https://t.me/opensourcequadcopter.
|
|
||||||
|
|
||||||
Join the official Telegram chat: https://t.me/opensourcequadcopterchat.
|
|
||||||
|
|
||||||
Detailed article on Habr.com about the development of the drone (in Russian): https://habr.com/ru/articles/814127/.
|
|
||||||
|
|
||||||
See the information on the obsolete version 0 in the [corresponding article](docs/version0.md).
|
|
||||||
|
|
||||||
## Disclaimer
|
## Disclaimer
|
||||||
|
|
||||||
This is a fun DIY project, and I hope you find it interesting and useful. However, it's not easy to assemble and set up, and it's provided "as is" without any warranties. There’s no guarantee that it will work perfectly — or even work at all.
|
This is a DIY project, and I hope you find it interesting and useful. However, it's not easy to assemble and set up, and it's provided "as is" without any warranties. There's no guarantee that it will work perfectly, or even work at all.
|
||||||
|
|
||||||
⚠️ The author is not responsible for any damage, injury, or loss resulting from the use of this project. Use at your own risk!
|
⚠️ The author is not responsible for any damage, injury, or loss resulting from the use of this project. Use at your own risk!
|
||||||
|
|||||||
@@ -1,2 +1,5 @@
|
|||||||
|
board_manager:
|
||||||
|
additional_urls:
|
||||||
|
- https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json
|
||||||
network:
|
network:
|
||||||
connection_timeout: 1h
|
connection_timeout: 1h
|
||||||
|
|||||||
@@ -27,3 +27,27 @@ Soldered components ([schematics variant](https://miro.com/app/board/uXjVN-dTjoo
|
|||||||
<br>Assembled drone:
|
<br>Assembled drone:
|
||||||
|
|
||||||
<img src="img/assembly/7.jpg" width=600>
|
<img src="img/assembly/7.jpg" width=600>
|
||||||
|
|
||||||
|
## Motor directions
|
||||||
|
|
||||||
|
> [!WARNING]
|
||||||
|
> The drone above is an early build, and it has **inversed** motor directions scheme. The photos only illustrate the assembly process in general.
|
||||||
|
|
||||||
|
Use standard motor directions scheme:
|
||||||
|
|
||||||
|
<img src="img/motors.svg" width=200>
|
||||||
|
|
||||||
|
Motors connection table:
|
||||||
|
|
||||||
|
|Motor|Position|Direction|Prop type|Motor wires|GPIO|
|
||||||
|
|-|-|-|-|-|-|
|
||||||
|
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 *(TDI)*|
|
||||||
|
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 *(TCK)*|
|
||||||
|
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 *(TMS)*|
|
||||||
|
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 *(TD0)*|
|
||||||
|
|
||||||
|
## Motors tightening
|
||||||
|
|
||||||
|
Motors should be installed very tightly — any vibration may lead to bad attitude estimation and unstable flight. If motors are loose, use tiny tape pieces to fix them tightly as shown below:
|
||||||
|
|
||||||
|
<img src="img/motor-tape.jpg" width=600>
|
||||||
|
|||||||
@@ -12,8 +12,8 @@
|
|||||||
* `acc` *(Vector)* — данные с акселерометра, *м/с<sup>2</sup>*.
|
* `acc` *(Vector)* — данные с акселерометра, *м/с<sup>2</sup>*.
|
||||||
* `rates` *(Vector)* — отфильтрованные угловые скорости, *рад/с*.
|
* `rates` *(Vector)* — отфильтрованные угловые скорости, *рад/с*.
|
||||||
* `attitude` *(Quaternion)* — оценка ориентации (положения) дрона.
|
* `attitude` *(Quaternion)* — оценка ориентации (положения) дрона.
|
||||||
* `controlRoll`, `controlPitch`, ... *(float[])* — команды управления от пилота, в диапазоне [-1, 1].
|
* `controlRoll`, `controlPitch`, `controlYaw`, `controlThrottle`, `controlMode` *(float)* — команды управления от пилота, в диапазоне [-1, 1].
|
||||||
* `motors` *(float[])* — выходные сигналы на моторы, в диапазоне [0, 1].
|
* `motors` *(float[4])* — выходные сигналы на моторы, в диапазоне [0, 1].
|
||||||
|
|
||||||
## Исходные файлы
|
## Исходные файлы
|
||||||
|
|
||||||
@@ -35,7 +35,7 @@
|
|||||||
|
|
||||||
### Подсистема управления
|
### Подсистема управления
|
||||||
|
|
||||||
Состояние органов управления обрабатывается в функции `interpretControls()` и преобразуется в *команду управления*, которая включает следующее:
|
Состояние органов управления обрабатывается в функции `interpretControls()` и преобразуется в **команду управления**, которая включает следующее:
|
||||||
|
|
||||||
* `attitudeTarget` *(Quaternion)* — целевая ориентация дрона.
|
* `attitudeTarget` *(Quaternion)* — целевая ориентация дрона.
|
||||||
* `ratesTarget` *(Vector)* — целевые угловые скорости, *рад/с*.
|
* `ratesTarget` *(Vector)* — целевые угловые скорости, *рад/с*.
|
||||||
|
|||||||
@@ -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;
|
||||||
|
|||||||
@@ -1 +0,0 @@
|
|||||||
usage.md
|
|
||||||
2
docs/build.md
Normal file
@@ -0,0 +1,2 @@
|
|||||||
|
<!-- markdownlint-disable MD041 -->
|
||||||
|
Build instructions are moved to [usage article](usage.md).
|
||||||
@@ -6,7 +6,7 @@ The firmware is a regular Arduino sketch, and it follows the classic Arduino one
|
|||||||
|
|
||||||
<img src="img/dataflow.svg" width=600 alt="Firmware dataflow diagram">
|
<img src="img/dataflow.svg" width=600 alt="Firmware dataflow diagram">
|
||||||
|
|
||||||
The main loop is running at 1000 Hz. All the dataflow goes through global variables (for simplicity):
|
The main loop is running at 1000 Hz. The dataflow goes through global variables, including:
|
||||||
|
|
||||||
* `t` *(float)* — current step time, *s*.
|
* `t` *(float)* — current step time, *s*.
|
||||||
* `dt` *(float)* — time delta between the current and previous steps, *s*.
|
* `dt` *(float)* — time delta between the current and previous steps, *s*.
|
||||||
@@ -14,12 +14,12 @@ The main loop is running at 1000 Hz. All the dataflow goes through global variab
|
|||||||
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*.
|
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*.
|
||||||
* `rates` *(Vector)* — filtered angular rates, *rad/s*.
|
* `rates` *(Vector)* — filtered angular rates, *rad/s*.
|
||||||
* `attitude` *(Quaternion)* — estimated attitude (orientation) of drone.
|
* `attitude` *(Quaternion)* — estimated attitude (orientation) of drone.
|
||||||
* `controlRoll`, `controlPitch`, ... *(float[])* — pilot control inputs, range [-1, 1].
|
* `controlRoll`, `controlPitch`, `controlYaw`, `controlThrottle`, `controlMode` *(float)* — pilot control inputs, range [-1, 1].
|
||||||
* `motors` *(float[])* — motor outputs, range [0, 1].
|
* `motors` *(float[4])* — motor outputs, range [0, 1].
|
||||||
|
|
||||||
## Source files
|
## Source files
|
||||||
|
|
||||||
Firmware source files are located in `flix` directory. The core files are:
|
Firmware source files are located in `flix` directory.
|
||||||
|
|
||||||
* [`flix.ino`](../flix/flix.ino) — Arduino sketch main file, entry point.Includes some global variable definitions and the main loop.
|
* [`flix.ino`](../flix/flix.ino) — Arduino sketch main file, entry point.Includes some global variable definitions and the main loop.
|
||||||
* [`imu.ino`](../flix/imu.ino) — reading data from the IMU sensor (gyroscope and accelerometer), IMU calibration.
|
* [`imu.ino`](../flix/imu.ino) — reading data from the IMU sensor (gyroscope and accelerometer), IMU calibration.
|
||||||
@@ -28,6 +28,7 @@ Firmware source files are located in `flix` directory. The core files are:
|
|||||||
* [`control.ino`](../flix/control.ino) — control subsystem, three-dimensional two-level cascade PID controller.
|
* [`control.ino`](../flix/control.ino) — control subsystem, three-dimensional two-level cascade PID controller.
|
||||||
* [`motors.ino`](../flix/motors.ino) — PWM motor output control.
|
* [`motors.ino`](../flix/motors.ino) — PWM motor output control.
|
||||||
* [`mavlink.ino`](../flix/mavlink.ino) — interaction with QGroundControl or [pyflix](../tools/pyflix) via MAVLink protocol.
|
* [`mavlink.ino`](../flix/mavlink.ino) — interaction with QGroundControl or [pyflix](../tools/pyflix) via MAVLink protocol.
|
||||||
|
* [`cli.ino`](../flix/cli.ino) — serial and MAVLink console.
|
||||||
|
|
||||||
Utility files:
|
Utility files:
|
||||||
|
|
||||||
@@ -37,20 +38,35 @@ Utility files:
|
|||||||
|
|
||||||
### Control subsystem
|
### Control subsystem
|
||||||
|
|
||||||
Pilot inputs are interpreted in `interpretControls()`, and then converted to the *control command*, which consists of the following:
|
Pilot inputs are interpreted in `interpretControls()`, and then converted to the **control command**, which consists of the following:
|
||||||
|
|
||||||
* `attitudeTarget` *(Quaternion)* — target attitude of the drone.
|
* `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 thrust target, range [0, 1].
|
* `thrustTarget` *(float)* — collective motor thrust target, range [0, 1].
|
||||||
|
|
||||||
Control command is processed in `controlAttitude()`, `controlRates()`, `controlTorque()` functions. Each function may be skipped if the corresponding target is set to `NAN`.
|
Control command is handled in `controlAttitude()`, `controlRates()`, `controlTorque()` functions. Each function may be skipped if the corresponding control target is set to `NAN`.
|
||||||
|
|
||||||
<img src="img/control.svg" width=300 alt="Control subsystem diagram">
|
<img src="img/control.svg" width=300 alt="Control subsystem diagram">
|
||||||
|
|
||||||
Armed state is stored in `armed` variable, and current mode is stored in `mode` variable.
|
Armed state is stored in `armed` variable, and current mode is stored in `mode` variable.
|
||||||
|
|
||||||
## Building
|
### Console
|
||||||
|
|
||||||
|
To write into the console, `print()` function is used. This function sends data both to the Serial console and to the MAVLink console (which can be accessed wirelessly in QGroundControl). The function supports formatting:
|
||||||
|
|
||||||
|
```cpp
|
||||||
|
print("Test value: %.2f\n", testValue);
|
||||||
|
```
|
||||||
|
|
||||||
|
In order to add a console command, modify the `doCommand()` function in `cli.ino` file.
|
||||||
|
|
||||||
|
> [!IMPORTANT]
|
||||||
|
> Avoid using delays in in-flight commands, it will **crash** the drone! (The design is one-threaded.)
|
||||||
|
>
|
||||||
|
> For on-the-ground commands, use `pause()` function, instead of `delay()`. This function allows to pause in a way that MAVLink connection will continue working.
|
||||||
|
|
||||||
|
## Building the firmware
|
||||||
|
|
||||||
See build instructions in [usage.md](usage.md).
|
See build instructions in [usage.md](usage.md).
|
||||||
|
|||||||
BIN
docs/img/arduino-ide.png
Normal file
|
After Width: | Height: | Size: 70 KiB |
|
Before Width: | Height: | Size: 140 KiB After Width: | Height: | Size: 15 KiB |
|
Before Width: | Height: | Size: 101 KiB After Width: | Height: | Size: 13 KiB |
136
docs/img/drone-axes-rotate.svg
Normal file
@@ -0,0 +1,136 @@
|
|||||||
|
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 813.79 508.65">
|
||||||
|
<defs>
|
||||||
|
<style>
|
||||||
|
.a, .d, .f, .j, .p {
|
||||||
|
fill: none;
|
||||||
|
}
|
||||||
|
|
||||||
|
.a {
|
||||||
|
stroke: #d5d5d5;
|
||||||
|
stroke-width: 31px;
|
||||||
|
}
|
||||||
|
|
||||||
|
.a, .p {
|
||||||
|
stroke-miterlimit: 10;
|
||||||
|
}
|
||||||
|
|
||||||
|
.b {
|
||||||
|
fill: #ff9400;
|
||||||
|
}
|
||||||
|
|
||||||
|
.c {
|
||||||
|
opacity: 0.8;
|
||||||
|
}
|
||||||
|
|
||||||
|
.d {
|
||||||
|
stroke: #d80100;
|
||||||
|
}
|
||||||
|
|
||||||
|
.d, .f, .j {
|
||||||
|
stroke-linejoin: bevel;
|
||||||
|
stroke-width: 13px;
|
||||||
|
}
|
||||||
|
|
||||||
|
.e {
|
||||||
|
fill: #d80100;
|
||||||
|
}
|
||||||
|
|
||||||
|
.f {
|
||||||
|
stroke: #57ed00;
|
||||||
|
}
|
||||||
|
|
||||||
|
.g {
|
||||||
|
fill: #57ed00;
|
||||||
|
}
|
||||||
|
|
||||||
|
.h {
|
||||||
|
fill: #c1c1c1;
|
||||||
|
}
|
||||||
|
|
||||||
|
.i {
|
||||||
|
opacity: 0.12;
|
||||||
|
}
|
||||||
|
|
||||||
|
.j {
|
||||||
|
stroke: #0076ba;
|
||||||
|
}
|
||||||
|
|
||||||
|
.k {
|
||||||
|
fill: #0076ba;
|
||||||
|
}
|
||||||
|
|
||||||
|
.l {
|
||||||
|
font-size: 50px;
|
||||||
|
font-family: Tahoma;
|
||||||
|
}
|
||||||
|
|
||||||
|
.m {
|
||||||
|
letter-spacing: -0.01em;
|
||||||
|
}
|
||||||
|
|
||||||
|
.n {
|
||||||
|
letter-spacing: -0.01em;
|
||||||
|
}
|
||||||
|
|
||||||
|
.o {
|
||||||
|
letter-spacing: 0em;
|
||||||
|
}
|
||||||
|
|
||||||
|
.p {
|
||||||
|
stroke: #000;
|
||||||
|
stroke-width: 10px;
|
||||||
|
}
|
||||||
|
</style>
|
||||||
|
</defs>
|
||||||
|
<g>
|
||||||
|
<g>
|
||||||
|
<line class="a" x1="259.14" y1="432.84" x2="532.46" y2="340.23"/>
|
||||||
|
<line class="a" x1="311.69" y1="313.16" x2="481.62" y2="461.39"/>
|
||||||
|
<ellipse class="b" cx="311.35" cy="312.8" rx="88.68" ry="47.94"/>
|
||||||
|
<ellipse class="b" cx="532.53" cy="340.42" rx="88.68" ry="47.94"/>
|
||||||
|
<ellipse class="b" cx="479.72" cy="460.7" rx="88.68" ry="47.94"/>
|
||||||
|
<ellipse class="b" cx="259.21" cy="433.03" rx="88.68" ry="47.94"/>
|
||||||
|
</g>
|
||||||
|
<g class="c">
|
||||||
|
<g>
|
||||||
|
<line class="d" x1="396.65" y1="386.83" x2="564.66" y2="35.72"/>
|
||||||
|
<polygon class="e" points="582.76 51.95 579.15 5.42 540.66 31.8 582.76 51.95"/>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<g class="c">
|
||||||
|
<g>
|
||||||
|
<line class="f" x1="396.77" y1="387.06" x2="69.41" y2="341.09"/>
|
||||||
|
<polygon class="g" points="79.42 318.93 36.15 336.42 72.93 365.15 79.42 318.93"/>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<ellipse class="h" cx="396.36" cy="386.61" rx="47.21" ry="25.52"/>
|
||||||
|
<path class="i" d="M398,375.67l-14.42,12.95a4.32,4.32,0,0,0,2.35,7.5l16.81,2.11a4.33,4.33,0,0,0,4.8-5l-2.39-15.06A4.32,4.32,0,0,0,398,375.67Z"/>
|
||||||
|
<g class="c">
|
||||||
|
<g>
|
||||||
|
<line class="j" x1="396.77" y1="385.56" x2="396.77" y2="92.64"/>
|
||||||
|
<polygon class="k" points="420.1 99.47 396.77 59.06 373.43 99.47 420.1 99.47"/>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<text class="l" transform="translate(0 292.27)">y/left</text>
|
||||||
|
<text class="l" transform="translate(268.4 81.58)">z/up</text>
|
||||||
|
<text class="l" transform="translate(600.99 43.18)">x/<tspan class="m" x="43.87" y="0">f</tspan><tspan x="59.3" y="0">or</tspan><tspan class="n" x="104.47" y="0">w</tspan><tspan x="141.14" y="0">a</tspan><tspan class="o" x="167.38" y="0">r</tspan><tspan x="185.16" y="0">d</tspan></text>
|
||||||
|
<g class="c">
|
||||||
|
<g>
|
||||||
|
<path class="p" d="M470.35,114a52.71,52.71,0,0,1,103.57-2.31,51.67,51.67,0,0,1-1.33,25.92"/>
|
||||||
|
<polygon points="562.15 128.29 563.93 154.16 585.44 139.69 562.15 128.29"/>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<g class="c">
|
||||||
|
<g>
|
||||||
|
<path class="p" d="M344.16,164.77a52.66,52.66,0,1,0,103.78,16.31"/>
|
||||||
|
<polygon points="460.61 184.04 446.18 162.5 434.74 185.76 460.61 184.04"/>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<g class="c">
|
||||||
|
<g>
|
||||||
|
<path class="p" d="M138.4,411.11a52.71,52.71,0,0,1,18.43-101.94A51.68,51.68,0,0,1,182,315.65"/>
|
||||||
|
<polygon points="170.73 324.01 196.43 327.44 186.55 303.47 170.73 324.01"/>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
||||||
|
After Width: | Height: | Size: 3.5 KiB |
110
docs/img/drone-axes.svg
Normal file
@@ -0,0 +1,110 @@
|
|||||||
|
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 664.49 478.47">
|
||||||
|
<defs>
|
||||||
|
<style>
|
||||||
|
.a, .d, .f, .j {
|
||||||
|
fill: none;
|
||||||
|
}
|
||||||
|
|
||||||
|
.a {
|
||||||
|
stroke: #d5d5d5;
|
||||||
|
stroke-miterlimit: 10;
|
||||||
|
stroke-width: 31px;
|
||||||
|
}
|
||||||
|
|
||||||
|
.b {
|
||||||
|
fill: #ff9400;
|
||||||
|
}
|
||||||
|
|
||||||
|
.c {
|
||||||
|
opacity: 0.8;
|
||||||
|
}
|
||||||
|
|
||||||
|
.d {
|
||||||
|
stroke: #d80100;
|
||||||
|
}
|
||||||
|
|
||||||
|
.d, .f, .j {
|
||||||
|
stroke-linejoin: bevel;
|
||||||
|
stroke-width: 13px;
|
||||||
|
}
|
||||||
|
|
||||||
|
.e {
|
||||||
|
fill: #d80100;
|
||||||
|
}
|
||||||
|
|
||||||
|
.f {
|
||||||
|
stroke: #57ed00;
|
||||||
|
}
|
||||||
|
|
||||||
|
.g {
|
||||||
|
fill: #57ed00;
|
||||||
|
}
|
||||||
|
|
||||||
|
.h {
|
||||||
|
fill: #c1c1c1;
|
||||||
|
}
|
||||||
|
|
||||||
|
.i {
|
||||||
|
opacity: 0.12;
|
||||||
|
}
|
||||||
|
|
||||||
|
.j {
|
||||||
|
stroke: #0076ba;
|
||||||
|
}
|
||||||
|
|
||||||
|
.k {
|
||||||
|
fill: #0076ba;
|
||||||
|
}
|
||||||
|
|
||||||
|
.l {
|
||||||
|
font-size: 50px;
|
||||||
|
font-family: Tahoma;
|
||||||
|
}
|
||||||
|
|
||||||
|
.m {
|
||||||
|
letter-spacing: -0.01em;
|
||||||
|
}
|
||||||
|
|
||||||
|
.n {
|
||||||
|
letter-spacing: -0.01em;
|
||||||
|
}
|
||||||
|
|
||||||
|
.o {
|
||||||
|
letter-spacing: 0em;
|
||||||
|
}
|
||||||
|
</style>
|
||||||
|
</defs>
|
||||||
|
<g>
|
||||||
|
<g>
|
||||||
|
<line class="a" x1="207.39" y1="402.28" x2="480.71" y2="309.67"/>
|
||||||
|
<line class="a" x1="259.93" y1="282.6" x2="429.86" y2="430.83"/>
|
||||||
|
<ellipse class="b" cx="259.59" cy="282.24" rx="88.68" ry="47.94"/>
|
||||||
|
<ellipse class="b" cx="480.77" cy="309.86" rx="88.68" ry="47.94"/>
|
||||||
|
<ellipse class="b" cx="427.96" cy="430.14" rx="88.68" ry="47.94"/>
|
||||||
|
<ellipse class="b" cx="207.45" cy="402.47" rx="88.68" ry="47.94"/>
|
||||||
|
</g>
|
||||||
|
<g class="c">
|
||||||
|
<g>
|
||||||
|
<line class="d" x1="344.89" y1="356.27" x2="422.02" y2="172.47"/>
|
||||||
|
<polygon class="e" points="440.89 187.79 435.01 141.5 397.86 169.74 440.89 187.79"/>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<g class="c">
|
||||||
|
<g>
|
||||||
|
<line class="f" x1="345.01" y1="356.5" x2="79.27" y2="319.17"/>
|
||||||
|
<polygon class="g" points="89.28 297.01 46.01 314.5 82.78 343.23 89.28 297.01"/>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<ellipse class="h" cx="344.6" cy="356.05" rx="47.21" ry="25.52"/>
|
||||||
|
<path class="i" d="M346.25,345.11l-14.41,12.95a4.32,4.32,0,0,0,2.34,7.5L351,367.67a4.33,4.33,0,0,0,4.8-5l-2.39-15.06A4.31,4.31,0,0,0,346.25,345.11Z"/>
|
||||||
|
<g class="c">
|
||||||
|
<g>
|
||||||
|
<line class="j" x1="345.01" y1="355" x2="345.01" y2="62.08"/>
|
||||||
|
<polygon class="k" points="368.35 68.91 345.01 28.5 321.67 68.91 368.35 68.91"/>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<text class="l" transform="translate(-0.76 281.71)">y/left</text>
|
||||||
|
<text class="l" transform="translate(371.65 38.02)">z/up</text>
|
||||||
|
<text class="l" transform="translate(455.23 152.62)">x/<tspan class="m" x="43.87" y="0">f</tspan><tspan x="59.3" y="0">or</tspan><tspan class="n" x="104.47" y="0">w</tspan><tspan x="141.14" y="0">a</tspan><tspan class="o" x="167.38" y="0">r</tspan><tspan x="185.16" y="0">d</tspan></text>
|
||||||
|
</g>
|
||||||
|
</svg>
|
||||||
|
After Width: | Height: | Size: 2.7 KiB |
38
docs/img/flix.svg
Normal file
@@ -0,0 +1,38 @@
|
|||||||
|
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 734.86 378.46">
|
||||||
|
<defs>
|
||||||
|
<style>
|
||||||
|
.a {
|
||||||
|
fill: none;
|
||||||
|
stroke: #d5d5d5;
|
||||||
|
stroke-miterlimit: 10;
|
||||||
|
stroke-width: 31px;
|
||||||
|
}
|
||||||
|
|
||||||
|
.b {
|
||||||
|
fill: #c1c1c1;
|
||||||
|
}
|
||||||
|
|
||||||
|
.c {
|
||||||
|
fill: #ff9400;
|
||||||
|
}
|
||||||
|
|
||||||
|
.d {
|
||||||
|
fill: #d5d5d5;
|
||||||
|
}
|
||||||
|
</style>
|
||||||
|
</defs>
|
||||||
|
<g>
|
||||||
|
<g>
|
||||||
|
<line class="a" x1="448.78" y1="294.23" x2="648.77" y2="93.24"/>
|
||||||
|
<line class="a" x1="449.78" y1="94.24" x2="649.77" y2="295.23"/>
|
||||||
|
<circle class="b" cx="549.27" cy="193.73" r="41.5"/>
|
||||||
|
<circle class="c" cx="449.35" cy="93.74" r="77.95"/>
|
||||||
|
<circle class="c" cx="648.89" cy="93.53" r="77.95"/>
|
||||||
|
<circle class="c" cx="647.89" cy="294.51" r="77.95"/>
|
||||||
|
<circle class="c" cx="448.9" cy="294.51" r="77.95"/>
|
||||||
|
</g>
|
||||||
|
<path class="d" d="M8,161.93q0-17.85,22.36-17.85h4.81V100.57Q35.17,8.49,131.23,8h1q36.87,0,47.31,7.48L181,17.41l1,2.41V50q0,12.32-5.82,12.31-2.43,0-7.4-4.64t-14.19-9a48.63,48.63,0,0,0-21.22-4.41q-12,0-19.17,3.5a18.85,18.85,0,0,0-9.82,10.62,67.35,67.35,0,0,0-3.52,12.06,82.52,82.52,0,0,0-.85,13.39v60.32h27.28q10.86,0,16.05,5.43a17.52,17.52,0,0,1,5.19,12.42,22.5,22.5,0,0,1-1.21,7.36q-1.22,3.51-6.64,7.24t-14.36,3.74H101.64V344.82a56,56,0,0,1-.61,9.65,37.8,37.8,0,0,1-2.56,7.6,11.83,11.83,0,0,1-6.94,6.4q-5,1.93-13.51,1.93H57.08q-10.47,0-15.7-4.71t-5.73-8.44a77.31,77.31,0,0,1-.48-9.53V180.27H29.4Q8,180.27,8,161.93Z"/>
|
||||||
|
<path class="d" d="M201.21,348.2V37q0-23.16,20.86-23.4h22.81q22.8,0,22.8,22.44V346.27a68.92,68.92,0,0,1-.49,9.41,22.59,22.59,0,0,1-2.42,7.12,11.48,11.48,0,0,1-6.67,5.43,47.78,47.78,0,0,1-12.74,2.17H225q-11.4,0-17.58-4.47T201.21,348.2Z"/>
|
||||||
|
<path class="d" d="M284.9,61.08V36.47a40.39,40.39,0,0,1,1.7-12.91,11.36,11.36,0,0,1,6.18-7,25.27,25.27,0,0,1,6.68-2.3c1.45-.15,4-.4,7.76-.72h25.23q10.43,0,16.73,4.7t6.31,18.22V62.05a27.94,27.94,0,0,1-.85,7.11,23,23,0,0,1-2.06,5.43,20,20,0,0,1-2.91,4,10,10,0,0,1-3.52,2.54c-1.21.48-2.54,1-4,1.44a11.53,11.53,0,0,1-3.4.73,13.71,13.71,0,0,0-3.15.48H307.7q-10.43,0-16.61-4.7T284.9,61.08Zm1.94,284.71V166.28q0-22.2,21.83-22.2h20.38q10.92,0,16.62,4t6.67,8.45a60.47,60.47,0,0,1,1,12.18V348.2q0,22.2-21.83,22.2H308.67q-10.43,0-15.64-4.95t-5.7-8.81A90.93,90.93,0,0,1,286.84,345.79Z"/>
|
||||||
|
</g>
|
||||||
|
</svg>
|
||||||
|
After Width: | Height: | Size: 2.2 KiB |
BIN
docs/img/imu-axes.png
Normal file
|
After Width: | Height: | Size: 23 KiB |
BIN
docs/img/imu-rot-1.png
Normal file
|
After Width: | Height: | Size: 18 KiB |
BIN
docs/img/imu-rot-2.png
Normal file
|
After Width: | Height: | Size: 18 KiB |
BIN
docs/img/imu-rot-3.png
Normal file
|
After Width: | Height: | Size: 17 KiB |
BIN
docs/img/imu-rot-4.png
Normal file
|
After Width: | Height: | Size: 17 KiB |
BIN
docs/img/imu-rot-5.png
Normal file
|
After Width: | Height: | Size: 10 KiB |
BIN
docs/img/imu-rot-6.png
Normal file
|
After Width: | Height: | Size: 9.6 KiB |
BIN
docs/img/imu-rot-7.png
Normal file
|
After Width: | Height: | Size: 10 KiB |
BIN
docs/img/imu-rot-8.png
Normal file
|
After Width: | Height: | Size: 10 KiB |
|
Before Width: | Height: | Size: 38 KiB After Width: | Height: | Size: 46 KiB |
BIN
docs/img/motor-tape.jpg
Normal file
|
After Width: | Height: | Size: 61 KiB |
89
docs/img/motors.svg
Normal file
@@ -0,0 +1,89 @@
|
|||||||
|
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 356.79 357.11">
|
||||||
|
<defs>
|
||||||
|
<style>
|
||||||
|
.a, .e {
|
||||||
|
fill: none;
|
||||||
|
stroke-miterlimit: 10;
|
||||||
|
}
|
||||||
|
|
||||||
|
.a {
|
||||||
|
stroke: #d5d5d5;
|
||||||
|
stroke-width: 31px;
|
||||||
|
}
|
||||||
|
|
||||||
|
.b {
|
||||||
|
fill: #c1c1c1;
|
||||||
|
}
|
||||||
|
|
||||||
|
.c {
|
||||||
|
fill: #ff9400;
|
||||||
|
}
|
||||||
|
|
||||||
|
.d {
|
||||||
|
opacity: 0.12;
|
||||||
|
}
|
||||||
|
|
||||||
|
.e {
|
||||||
|
stroke: #cc5200;
|
||||||
|
stroke-width: 8px;
|
||||||
|
}
|
||||||
|
|
||||||
|
.f {
|
||||||
|
fill: #cc5200;
|
||||||
|
}
|
||||||
|
|
||||||
|
.g {
|
||||||
|
font-size: 50px;
|
||||||
|
fill: #fff;
|
||||||
|
}
|
||||||
|
|
||||||
|
.g, .h {
|
||||||
|
font-family: Tahoma;
|
||||||
|
}
|
||||||
|
|
||||||
|
.h {
|
||||||
|
font-size: 20px;
|
||||||
|
}
|
||||||
|
|
||||||
|
.i {
|
||||||
|
letter-spacing: 0em;
|
||||||
|
}
|
||||||
|
</style>
|
||||||
|
</defs>
|
||||||
|
<g>
|
||||||
|
<g>
|
||||||
|
<line class="a" x1="77.4" y1="278.67" x2="277.4" y2="77.67"/>
|
||||||
|
<line class="a" x1="78.4" y1="78.67" x2="278.4" y2="279.67"/>
|
||||||
|
<circle class="b" cx="177.9" cy="178.17" r="41.5"/>
|
||||||
|
<circle class="c" cx="77.97" cy="78.17" r="77.95"/>
|
||||||
|
<circle class="c" cx="277.52" cy="77.95" r="77.95"/>
|
||||||
|
</g>
|
||||||
|
<path class="d" d="M174.29,163.6l-8.45,26.05A4.32,4.32,0,0,0,170,195.3h16.9a4.32,4.32,0,0,0,4.11-5.65l-8.45-26.05A4.32,4.32,0,0,0,174.29,163.6Z"/>
|
||||||
|
<g>
|
||||||
|
<path class="e" d="M307.47,122.53a52.66,52.66,0,1,0-72.08-76"/>
|
||||||
|
<polygon class="f" points="228.68 38.51 227.44 59.21 245.99 49.94 228.68 38.51"/>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<path class="e" d="M48.11,122.22a52.66,52.66,0,1,1,72.08-75.95"/>
|
||||||
|
<polygon class="f" points="109.59 49.63 128.14 58.91 126.9 38.2 109.59 49.63"/>
|
||||||
|
</g>
|
||||||
|
<text class="g" transform="translate(64.89 98.77)">3</text>
|
||||||
|
<text class="g" transform="translate(260.92 98.8)">2</text>
|
||||||
|
<text class="h" transform="translate(66.06 129.25)">p<tspan class="i" x="11.05" y="0">r</tspan><tspan x="18.16" y="0">op A</tspan></text>
|
||||||
|
<text class="h" transform="translate(232.55 128.95)">p<tspan class="i" x="11.05" y="0">r</tspan><tspan x="18.16" y="0">op B</tspan></text>
|
||||||
|
<circle class="c" cx="278.83" cy="277.92" r="77.95"/>
|
||||||
|
<g>
|
||||||
|
<path class="e" d="M249,322a52.66,52.66,0,1,1,72.09-76"/>
|
||||||
|
<polygon class="f" points="310.45 249.38 329 258.66 327.76 237.95 310.45 249.38"/>
|
||||||
|
</g>
|
||||||
|
<text class="g" transform="translate(265.76 298.52)">1</text>
|
||||||
|
<text class="h" transform="translate(266.92 329.01)">p<tspan class="i" x="11.05" y="0">r</tspan><tspan x="18.16" y="0">op A</tspan></text>
|
||||||
|
<circle class="c" cx="77.95" cy="277.92" r="77.95"/>
|
||||||
|
<g>
|
||||||
|
<path class="e" d="M107.9,322.49a52.66,52.66,0,1,0-72.08-76"/>
|
||||||
|
<polygon class="f" points="29.11 238.47 27.87 259.18 46.42 249.91 29.11 238.47"/>
|
||||||
|
</g>
|
||||||
|
<text class="g" transform="translate(61.35 298.76)">0</text>
|
||||||
|
<text class="h" transform="translate(32.98 328.92)">p<tspan class="i" x="11.05" y="0">r</tspan><tspan x="18.16" y="0">op B</tspan></text>
|
||||||
|
</g>
|
||||||
|
</svg>
|
||||||
|
After Width: | Height: | Size: 2.8 KiB |
BIN
docs/img/qgc-attitude.png
Normal file
|
After Width: | Height: | Size: 16 KiB |
|
Before Width: | Height: | Size: 18 KiB After Width: | Height: | Size: 18 KiB |
BIN
docs/img/user/arkymatsekh/1.jpg
Normal file
|
After Width: | Height: | Size: 62 KiB |
BIN
docs/img/user/arkymatsekh/2.jpg
Normal file
|
After Width: | Height: | Size: 48 KiB |
BIN
docs/img/user/arkymatsekh/3.jpg
Normal file
|
After Width: | Height: | Size: 50 KiB |
BIN
docs/img/user/arkymatsekh/video.jpg
Normal file
|
After Width: | Height: | Size: 17 KiB |
BIN
docs/img/user/fanby0ru/1.jpg
Normal file
|
After Width: | Height: | Size: 44 KiB |
BIN
docs/img/user/fanby0ru/2.jpg
Normal file
|
After Width: | Height: | Size: 55 KiB |
BIN
docs/img/user/goldarte/1.jpg
Normal file
|
After Width: | Height: | Size: 68 KiB |
BIN
docs/img/user/goldarte/2.jpg
Normal file
|
After Width: | Height: | Size: 35 KiB |
BIN
docs/img/user/goldarte/video.jpg
Normal file
|
After Width: | Height: | Size: 32 KiB |
BIN
docs/img/user/phalko/1.jpg
Normal file
|
After Width: | Height: | Size: 105 KiB |
BIN
docs/img/user/phalko/2.jpg
Normal file
|
After Width: | Height: | Size: 34 KiB |
BIN
docs/img/user/phalko/3.jpg
Normal file
|
After Width: | Height: | Size: 36 KiB |
BIN
docs/img/user/school548/1.jpg
Normal file
|
After Width: | Height: | Size: 108 KiB |
BIN
docs/img/user/school548/2.jpg
Normal file
|
After Width: | Height: | Size: 93 KiB |
BIN
docs/img/user/school548/3.jpg
Normal file
|
After Width: | Height: | Size: 65 KiB |
BIN
docs/img/user/school548/kiraflux-video.jpg
Normal file
|
After Width: | Height: | Size: 28 KiB |
BIN
docs/img/user/school548/kiraflux1.jpg
Normal file
|
After Width: | Height: | Size: 31 KiB |
BIN
docs/img/user/school548/kiraflux2.jpg
Normal file
|
After Width: | Height: | Size: 42 KiB |
BIN
docs/img/user/school548/tolyan4krut-video.jpg
Normal file
|
After Width: | Height: | Size: 43 KiB |
BIN
docs/img/user/school548/tolyan4krut.jpg
Normal file
|
After Width: | Height: | Size: 76 KiB |
BIN
docs/img/user/school548/vlad_tolshinov-video.jpg
Normal file
|
After Width: | Height: | Size: 28 KiB |
BIN
docs/img/user/school548/vlad_tolshinov1.jpg
Normal file
|
After Width: | Height: | Size: 44 KiB |
BIN
docs/img/user/school548/vlad_tolshinov2.jpg
Normal file
|
After Width: | Height: | Size: 32 KiB |
@@ -2,11 +2,7 @@
|
|||||||
|
|
||||||
Flix quadcopter uses RAM to store flight log data. The default log capacity is 10 seconds at 100 Hz. This configuration can be adjusted in the `log.ino` file.
|
Flix quadcopter uses RAM to store flight log data. The default log capacity is 10 seconds at 100 Hz. This configuration can be adjusted in the `log.ino` file.
|
||||||
|
|
||||||
To perform log analysis, you need to download the log right after the flight without powering off the drone. Then you can use several tools to analyze the log data.
|
To perform log analysis, you need to download the flight log. To to that, ensure you're connected to the drone using Wi-Fi and run the following command:
|
||||||
|
|
||||||
## Log download
|
|
||||||
|
|
||||||
To download the log, connect the ESP32 using USB right after the flight and run the following command:
|
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
make log
|
make log
|
||||||
|
|||||||
@@ -4,7 +4,7 @@
|
|||||||
|
|
||||||
Do the following:
|
Do the following:
|
||||||
|
|
||||||
* **Check ESP32 core is installed**. Check if the version matches the one used in the [tutorial](usage.md#firmware).
|
* **Check ESP32 core is installed**. Check if the version matches the one used in the [tutorial](usage.md#building-the-firmware).
|
||||||
* **Check libraries**. Install all the required libraries from the tutorial. Make sure there are no MPU9250 or other peripherals libraries that may conflict with the ones used in the tutorial.
|
* **Check libraries**. Install all the required libraries from the tutorial. Make sure there are no MPU9250 or other peripherals libraries that may conflict with the ones used in the tutorial.
|
||||||
* **Check the chosen board**. The correct board to choose in Arduino IDE for ESP32 Mini is *WEMOS D1 MINI ESP32*.
|
* **Check the chosen board**. The correct board to choose in Arduino IDE for ESP32 Mini is *WEMOS D1 MINI ESP32*.
|
||||||
|
|
||||||
@@ -13,10 +13,10 @@ Do the following:
|
|||||||
Do the following:
|
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:
|
||||||
@@ -25,13 +25,15 @@ Do the following:
|
|||||||
* The `accel` and `gyro` fields should change as you move the drone.
|
* The `accel` and `gyro` fields should change as you move the drone.
|
||||||
* **Calibrate the accelerometer.** if is wasn't done before. Type `ca` command in Serial Monitor and follow the instructions.
|
* **Calibrate the accelerometer.** if is wasn't done before. Type `ca` command in Serial Monitor and follow the instructions.
|
||||||
* **Check the attitude estimation**. Connect to the drone using QGroundControl. Rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct.
|
* **Check the attitude estimation**. Connect to the drone using QGroundControl. Rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct.
|
||||||
* **Check the IMU orientation is set correctly**. If the attitude estimation is rotated, make sure `rotateIMU` function is defined correctly in `imu.ino` file.
|
* **Check the IMU orientation is set correctly**. If the attitude estimation is rotated, set the correct IMU orientation as described in the [tutorial](usage.md#define-imu-orientation).
|
||||||
* **Check the motors type**. Motors with exact 3.7V voltage are needed, not ranged working voltage (3.7V — 6V).
|
* **Check the motors type**. Motors with exact 3.7V voltage are needed, not ranged working voltage (3.7V — 6V).
|
||||||
* **Check the motors**. Perform the following commands using Serial Monitor:
|
* **Check the motors**. Perform the following commands using Serial Monitor:
|
||||||
* `mfr` — should rotate front right motor (counter-clockwise).
|
* `mfr` — should rotate front right motor (counter-clockwise).
|
||||||
* `mfl` — should rotate front left motor (clockwise).
|
* `mfl` — should rotate front left motor (clockwise).
|
||||||
* `mrl` — should rotate rear left motor (counter-clockwise).
|
* `mrl` — should rotate rear left motor (counter-clockwise).
|
||||||
* `mrr` — should rotate rear right motor (clockwise).
|
* `mrr` — should rotate rear right motor (clockwise).
|
||||||
|
* **Check the propeller directions are correct**. Make sure your propeller types (A or B) are installed as on the picture:
|
||||||
|
<img src="img/user/peter_ukhov-2/1.jpg" width="200">
|
||||||
* **Check the remote control**. Using `rc` command, check the control values reflect your sticks movement. All the controls should change between -1 and 1, and throttle between 0 and 1.
|
* **Check the remote control**. Using `rc` command, check the control values reflect your sticks movement. All the controls should change between -1 and 1, and throttle between 0 and 1.
|
||||||
* If using SBUS receiver, **calibrate the RC**. Type `cr` command in Serial Monitor and follow the instructions.
|
* If using SBUS receiver, **calibrate the RC**. Type `cr` command in Serial Monitor and follow the instructions.
|
||||||
* **Check the IMU output using QGroundControl**. Connect to the drone using QGroundControl on your computer. Go to the *Analyze* tab, *MAVLINK Inspector*. Plot the data from the `SCALED_IMU` message. The gyroscope and accelerometer data should change according to the drone movement.
|
* **Check the IMU output using QGroundControl**. Connect to the drone using QGroundControl on your computer. Go to the *Analyze* tab, *MAVLINK Inspector*. Plot the data from the `SCALED_IMU` message. The gyroscope and accelerometer data should change according to the drone movement.
|
||||||
|
|||||||
316
docs/usage.md
@@ -1,130 +1,38 @@
|
|||||||
# Usage: build, setup and flight
|
# Usage: build, setup and flight
|
||||||
|
|
||||||
To use Flix, you need to build the firmware and upload it to the ESP32 board. For simulation, you need to build and run the simulator.
|
To fly Flix quadcopter, you need to build the firmware, upload it to the ESP32 board, and set up the drone for flight.
|
||||||
|
|
||||||
For the start, clone the repository using git:
|
To get the firmware sources, clone the repository using git:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
git clone https://github.com/okalachev/flix.git
|
git clone https://github.com/okalachev/flix.git && cd flix
|
||||||
cd flix
|
|
||||||
```
|
```
|
||||||
|
|
||||||
## Simulation
|
Beginners can [download the source code as a ZIP archive](https://github.com/okalachev/flix/archive/refs/heads/master.zip).
|
||||||
|
|
||||||
### Ubuntu
|
## Building the firmware
|
||||||
|
|
||||||
The latest version of Ubuntu supported by Gazebo 11 simulator is 20.04. If you have a newer version, consider using a virtual machine.
|
You can build and upload the firmware using either **Arduino IDE** (easier for beginners) or **command line**.
|
||||||
|
|
||||||
1. Install Arduino CLI:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
|
|
||||||
```
|
|
||||||
|
|
||||||
2. Install Gazebo 11:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
|
|
||||||
wget https://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
|
|
||||||
sudo apt-get update
|
|
||||||
sudo apt-get install -y gazebo11 libgazebo11-dev
|
|
||||||
```
|
|
||||||
|
|
||||||
Set up your Gazebo environment variables:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
echo "source /usr/share/gazebo/setup.sh" >> ~/.bashrc
|
|
||||||
source ~/.bashrc
|
|
||||||
```
|
|
||||||
|
|
||||||
3. Install SDL2 and other dependencies:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
sudo apt-get update && sudo apt-get install build-essential libsdl2-dev
|
|
||||||
```
|
|
||||||
|
|
||||||
4. Add your user to the `input` group to enable joystick support (you need to re-login after this command):
|
|
||||||
|
|
||||||
```bash
|
|
||||||
sudo usermod -a -G input $USER
|
|
||||||
```
|
|
||||||
|
|
||||||
5. Run the simulation:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
make simulator
|
|
||||||
```
|
|
||||||
|
|
||||||
### macOS
|
|
||||||
|
|
||||||
1. Install Homebrew package manager, if you don't have it installed:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
/bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/HEAD/install.sh)"
|
|
||||||
```
|
|
||||||
|
|
||||||
2. Install Arduino CLI, Gazebo 11 and SDL2:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
brew tap osrf/simulation
|
|
||||||
brew install arduino-cli
|
|
||||||
brew install gazebo11
|
|
||||||
brew install sdl2
|
|
||||||
```
|
|
||||||
|
|
||||||
Set up your Gazebo environment variables:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
echo "source /opt/homebrew/share/gazebo/setup.sh" >> ~/.zshrc
|
|
||||||
source ~/.zshrc
|
|
||||||
```
|
|
||||||
|
|
||||||
3. Run the simulation:
|
|
||||||
|
|
||||||
```bash
|
|
||||||
make simulator
|
|
||||||
```
|
|
||||||
|
|
||||||
### Setup
|
|
||||||
|
|
||||||
#### Control with smartphone
|
|
||||||
|
|
||||||
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone. For **iOS**, use [QGroundControl build from TAJISOFT](https://apps.apple.com/ru/app/qgc-from-tajisoft/id1618653051).
|
|
||||||
2. Connect your smartphone to the same Wi-Fi network as the machine running the simulator.
|
|
||||||
3. If you're using a virtual machine, make sure that its network is set to the **bridged** mode with Wi-Fi adapter selected.
|
|
||||||
4. Run the simulation.
|
|
||||||
5. Open QGroundControl app. It should connect and begin showing the virtual drone's telemetry automatically.
|
|
||||||
6. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
|
|
||||||
7. Use the virtual joystick to fly the drone!
|
|
||||||
|
|
||||||
#### Control with USB remote control
|
|
||||||
|
|
||||||
1. Connect your USB remote control to the machine running the simulator.
|
|
||||||
2. Run the simulation.
|
|
||||||
3. Calibrate the RC using `cr` command in the command line interface.
|
|
||||||
4. Run the simulation again.
|
|
||||||
5. Use the USB remote control to fly the drone!
|
|
||||||
|
|
||||||
## Firmware
|
|
||||||
|
|
||||||
### Arduino IDE (Windows, Linux, macOS)
|
### Arduino IDE (Windows, Linux, macOS)
|
||||||
|
|
||||||
|
<img src="img/arduino-ide.png" width="400" alt="Flix firmware open in Arduino IDE">
|
||||||
|
|
||||||
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. Clone the project using git or [download the source code as a ZIP archive](https://codeload.github.com/okalachev/flix/zip/refs/heads/master).
|
5. Open the `flix/flix.ino` sketch from downloaded firmware sources in Arduino IDE.
|
||||||
6. Open the downloaded Arduino sketch `flix/flix.ino` in Arduino IDE.
|
6. Connect your ESP32 board to the computer and choose correct board type in Arduino IDE (*WEMOS D1 MINI ESP32* for ESP32 Mini) and the port.
|
||||||
7. 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.
|
||||||
8. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
|
|
||||||
|
|
||||||
### Command line (Windows, Linux, macOS)
|
### Command line (Windows, Linux, macOS)
|
||||||
|
|
||||||
1. [Install Arduino CLI](https://arduino.github.io/arduino-cli/installation/).
|
1. [Install Arduino CLI](https://arduino.github.io/arduino-cli/installation/).
|
||||||
|
|
||||||
On Linux, use:
|
On Linux, install it like this:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
|
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
|
||||||
@@ -149,19 +57,131 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 20.04. If you h
|
|||||||
make upload monitor
|
make upload monitor
|
||||||
```
|
```
|
||||||
|
|
||||||
See other available Make commands in the [Makefile](../Makefile).
|
See other available Make commands in [Makefile](../Makefile).
|
||||||
|
|
||||||
> [!TIP]
|
> [!TIP]
|
||||||
> You can test the firmware on a bare ESP32 board without connecting IMU and other peripherals. The Wi-Fi network `flix` should appear and all the basic functionality including CLI and QGroundControl connection should work.
|
> You can test the firmware on a bare ESP32 board without connecting IMU and other peripherals. The Wi-Fi network `flix` should appear and all the basic functionality including console and QGroundControl connection should work.
|
||||||
|
|
||||||
### Setup
|
## Before first flight
|
||||||
|
|
||||||
|
### Choose the IMU model
|
||||||
|
|
||||||
|
In case if using different IMU model than MPU9250, change `imu` variable declaration in the `imu.ino`:
|
||||||
|
|
||||||
|
```cpp
|
||||||
|
ICM20948 imu(SPI); // For ICM-20948
|
||||||
|
MPU6050 imu(Wire); // For MPU-6050
|
||||||
|
```
|
||||||
|
|
||||||
|
### Connect using QGroundControl
|
||||||
|
|
||||||
|
QGroundControl is a ground control station software that can be used to monitor and control the drone.
|
||||||
|
|
||||||
|
1. Install mobile or desktop version of [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html).
|
||||||
|
2. Power up the drone.
|
||||||
|
3. Connect your computer or smartphone to the appeared `flix` Wi-Fi network (password: `flixwifi`).
|
||||||
|
4. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
|
||||||
|
|
||||||
|
### Access console
|
||||||
|
|
||||||
|
The console is a command line interface (CLI) that allows to interact with the drone, change parameters, and perform various actions. There are two ways of accessing the console: using **serial port** or using **QGroundControl (wirelessly)**.
|
||||||
|
|
||||||
|
To access the console using serial port:
|
||||||
|
|
||||||
|
1. Connect the ESP32 board to the computer using USB cable.
|
||||||
|
2. Open Serial Monitor in Arduino IDE (or use `make monitor` in the command line).
|
||||||
|
3. In Arduino IDE, make sure the baudrate is set to 115200.
|
||||||
|
|
||||||
|
To access the console using QGroundControl:
|
||||||
|
|
||||||
|
1. Connect to the drone using QGroundControl app.
|
||||||
|
2. Go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*.
|
||||||
|
|
||||||
|
<img src="img/cli.png" width="400">
|
||||||
|
|
||||||
|
> [!TIP]
|
||||||
|
> Use `help` command to see the list of available commands.
|
||||||
|
|
||||||
|
### Access parameters
|
||||||
|
|
||||||
|
The drone is configured using parameters. To access and modify them, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*:
|
||||||
|
|
||||||
|
<img src="img/parameters.png" width="400">
|
||||||
|
|
||||||
|
You can also work with parameters using `p` command in the console. Parameter names are case-insensitive.
|
||||||
|
|
||||||
|
### Define IMU orientation
|
||||||
|
|
||||||
|
Use parameters, to define the IMU board axes orientation relative to the drone's axes: `IMU_ROT_ROLL`, `IMU_ROT_PITCH`, and `IMU_ROT_YAW`.
|
||||||
|
|
||||||
|
The drone has *X* axis pointing forward, *Y* axis pointing left, and *Z* axis pointing up, and the supported IMU boards have *X* axis pointing to the pins side and *Z* axis pointing up from the component side:
|
||||||
|
|
||||||
|
<img src="img/imu-axes.png" width="200">
|
||||||
|
|
||||||
|
Use the following table to set the parameters for common IMU orientations:
|
||||||
|
|
||||||
|
|Orientation|Parameters|Orientation|Parameters|
|
||||||
|
|:-:|-|-|-|
|
||||||
|
|<img src="img/imu-rot-1.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0 |<img src="img/imu-rot-5.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0|
|
||||||
|
|<img src="img/imu-rot-2.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|<img src="img/imu-rot-6.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|
|
||||||
|
|<img src="img/imu-rot-3.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|<img src="img/imu-rot-7.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|
|
||||||
|
|<img src="img/imu-rot-4.png" width="180"><br>☑️ **Default**|<br>`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|<img src="img/imu-rot-8.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|
|
||||||
|
|
||||||
|
### Calibrate accelerometer
|
||||||
|
|
||||||
Before flight you need to calibrate the accelerometer:
|
Before flight you need to calibrate the accelerometer:
|
||||||
|
|
||||||
1. Open Serial Monitor in Arduino IDE (or use `make monitor` command in the command line).
|
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.
|
||||||
|
|
||||||
#### Control with smartphone
|
### Setup motors
|
||||||
|
|
||||||
|
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 `rate` field should be about 1000 (Hz).
|
||||||
|
* The `accel` and `gyro` fields should change as you move the drone.
|
||||||
|
* The `accel bias` and `accel scale` fields should contain calibration parameters (not zeros and ones).
|
||||||
|
* The `gyro bias` field should contain estimated gyro bias (not zeros).
|
||||||
|
* The `landed` field should be `1` when the drone is still on the ground and `0` when you lift it up.
|
||||||
|
|
||||||
|
2. Check the attitude estimation: connect to the drone using QGroundControl, rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. Compare your attitude indicator (in the *large vertical* mode) to the video:
|
||||||
|
|
||||||
|
<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. Use the following commands **— remove the propellers before running the tests!**
|
||||||
|
|
||||||
|
* `mfr` — rotate front right motor (counter-clockwise).
|
||||||
|
* `mfl` — rotate front left motor (clockwise).
|
||||||
|
* `mrl` — rotate rear left motor (counter-clockwise).
|
||||||
|
* `mrr` — rotate rear right motor (clockwise).
|
||||||
|
|
||||||
|
Make sure rotation directions and propeller types match the following diagram:
|
||||||
|
|
||||||
|
<img src="img/motors.svg" width=200>
|
||||||
|
|
||||||
|
> [!WARNING]
|
||||||
|
> Never run the motors when powering the drone from USB, always use the battery for that.
|
||||||
|
|
||||||
|
## Setup remote control
|
||||||
|
|
||||||
|
There are several ways to control the drone's flight: using **smartphone** (Wi-Fi), using **SBUS remote control**, or using **USB remote control** (Wi-Fi).
|
||||||
|
|
||||||
|
### Control with a smartphone
|
||||||
|
|
||||||
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone.
|
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone.
|
||||||
2. Power the drone using the battery.
|
2. Power the drone using the battery.
|
||||||
@@ -171,17 +191,17 @@ Before flight you need to calibrate the accelerometer:
|
|||||||
6. Use the virtual joystick to fly the drone!
|
6. Use the virtual joystick to fly the drone!
|
||||||
|
|
||||||
> [!TIP]
|
> [!TIP]
|
||||||
> Decrease `TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
|
> Decrease `CTL_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
|
||||||
|
|
||||||
#### Control with remote control
|
### Control with a remote control
|
||||||
|
|
||||||
Before flight using remote control, you need to calibrate it:
|
Before using remote SBUS-connected remote control, you need to calibrate it:
|
||||||
|
|
||||||
1. Open Serial Monitor in Arduino IDE (or use `make monitor` command in the command line).
|
1. Access the console using QGroundControl (recommended) or Serial Monitor.
|
||||||
2. Type `cr` command there and follow the instructions.
|
2. Type `cr` command and follow the instructions.
|
||||||
3. Use the remote control to fly the drone!
|
3. Use the remote control to fly the drone!
|
||||||
|
|
||||||
#### Control with USB remote control (Wi-Fi)
|
### Control with a USB remote control
|
||||||
|
|
||||||
If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it.
|
If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it.
|
||||||
|
|
||||||
@@ -193,9 +213,6 @@ If your drone doesn't have RC receiver installed, you can use USB remote control
|
|||||||
6. Go the the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Joystick*. Calibrate you USB remote control there.
|
6. Go the the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Joystick*. Calibrate you USB remote control there.
|
||||||
7. Use the USB remote control to fly the drone!
|
7. Use the USB remote control to fly the drone!
|
||||||
|
|
||||||
> [!NOTE]
|
|
||||||
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.
|
|
||||||
|
|
||||||
## Flight
|
## Flight
|
||||||
|
|
||||||
For both virtual sticks and a physical joystick, the default control scheme is left stick for throttle and yaw and right stick for pitch and roll:
|
For both virtual sticks and a physical joystick, the default control scheme is left stick for throttle and yaw and right stick for pitch and roll:
|
||||||
@@ -214,13 +231,16 @@ When finished flying, **disarm** the drone, moving the left stick to the bottom
|
|||||||
|
|
||||||
<img src="img/disarming.svg" width="150">
|
<img src="img/disarming.svg" width="150">
|
||||||
|
|
||||||
|
> [!NOTE]
|
||||||
|
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.
|
||||||
|
|
||||||
### 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.
|
||||||
@@ -229,24 +249,56 @@ The default mode is *STAB*. In this mode, the drone stabilizes its attitude (ori
|
|||||||
|
|
||||||
In this mode, the pilot controls the angular rates. This control method is difficult to fly and mostly used in FPV racing.
|
In this mode, the pilot controls the angular rates. This control method is difficult to fly and mostly used in FPV racing.
|
||||||
|
|
||||||
#### MANUAL
|
#### RAW
|
||||||
|
|
||||||
Manual mode disables all the stabilization, and the pilot inputs are passed directly to the motors. This mode is intended for testing and demonstration purposes only, and basically the drone **cannot fly in this mode**.
|
*RAW* mode disables all the stabilization, and the pilot inputs are mixed directly to the motors. The IMU sensor is not involved. This mode is intended for testing and demonstration purposes only, and basically the drone **cannot fly in this mode**.
|
||||||
|
|
||||||
#### 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.
|
||||||
|
|
||||||
## Adjusting parameters
|
## Wi-Fi configuration
|
||||||
|
|
||||||
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl app. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*.
|
You can configure the Wi-Fi using parameters and console commands.
|
||||||
|
|
||||||
<img src="img/parameters.png" width="400">
|
The Wi-Fi mode is chosen using `WIFI_MODE` parameter in QGroundControl or in the console:
|
||||||
|
|
||||||
## CLI access
|
* `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)*.
|
||||||
|
|
||||||
In addition to accessing the drone's command line interface (CLI) using the serial port, you can also access it with QGroundControl using Wi-Fi connection. To do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*.
|
> [!WARNING]
|
||||||
|
> Tests showed that Client mode may cause **additional delays** in remote control (due to retranslations), so it's generally not recommended.
|
||||||
|
|
||||||
<img src="img/cli.png" width="400">
|
The SSID and password are configured using the `ap` and `sta` console commands:
|
||||||
|
|
||||||
|
```
|
||||||
|
ap <ssid> <password>
|
||||||
|
sta <ssid> <password>
|
||||||
|
```
|
||||||
|
|
||||||
|
Example of configuring the Access Point mode:
|
||||||
|
|
||||||
|
```
|
||||||
|
ap my-flix-ssid mypassword123
|
||||||
|
p WIFI_MODE 1
|
||||||
|
```
|
||||||
|
|
||||||
|
Disabling Wi-Fi:
|
||||||
|
|
||||||
|
```
|
||||||
|
p WIFI_MODE 0
|
||||||
|
```
|
||||||
|
|
||||||
|
## Flight log
|
||||||
|
|
||||||
|
After the flight, you can download the flight log for analysis wirelessly. Use the following command on your computer for that:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
make log
|
||||||
|
```
|
||||||
|
|
||||||
|
See more details about log analysis in the [log analysis](log.md) article.
|
||||||
|
|||||||
84
docs/user.md
@@ -4,12 +4,94 @@ This page contains user-built drones based on the Flix project. Publish your pro
|
|||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
Author: [FanBy0ru](https://https://github.com/FanBy0ru).<br>
|
||||||
|
Description: custom 3D-printed frame.<br>
|
||||||
|
Frame STLs and flight validation: https://cults3d.com/en/3d-model/gadget/armature-pour-flix-drone.
|
||||||
|
|
||||||
|
<img src="img/user/fanby0ru/1.jpg" height=200> <img src="img/user/fanby0ru/2.jpg" height=200>
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
Author: Ivan44 Phalko.<br>
|
||||||
|
Description: custom PCB, cusom test bench.<br>
|
||||||
|
[Flight validation](https://drive.google.com/file/d/17DNDJ1gPmCmDRAwjedCbJ9RXAyqMqqcX/view?usp=sharing).
|
||||||
|
|
||||||
|
<img src="img/user/phalko/1.jpg" height=200> <img src="img/user/phalko/2.jpg" height=200> <img src="img/user/phalko/3.jpg" height=200>
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
Author: **Arkadiy "Arky" Matsekh**, Foucault Dynamics, Gold Coast, Australia.<br>
|
||||||
|
The drone was built for the University of Queensland industry-led Master's capstone project.
|
||||||
|
|
||||||
|
**Flight video:**
|
||||||
|
|
||||||
|
<a href="https://drive.google.com/file/d/1NNYSVXBY-w0JjCo07D8-PgnVq3ca9plj/view?usp=sharing"><img height=300 src="img/user/arkymatsekh/video.jpg"></a>
|
||||||
|
|
||||||
|
<img src="img/user/arkymatsekh/1.jpg" height=150> <img src="img/user/arkymatsekh/2.jpg" height=150> <img src="img/user/arkymatsekh/3.jpg" height=150>
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
Author: [goldarte](https://t.me/goldarte).<br>
|
||||||
|
|
||||||
|
<img src="img/user/goldarte/1.jpg" height=150> <img src="img/user/goldarte/2.jpg" height=150>
|
||||||
|
|
||||||
|
**Flight video:**
|
||||||
|
|
||||||
|
<a href="https://drive.google.com/file/d/1nQtFjEcGGLx-l4xkL5ko9ZpOTVU-WDjL/view?usp=sharing"><img height=200 src="img/user/goldarte/video.jpg"></a>
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
## School 548 course
|
||||||
|
|
||||||
|
Special course on quadcopter design and engineering took place in october-november 2025 in School 548, Moscow. The course included UAV control theory, electronics, drone assembly and setup practice, using the Flix project.
|
||||||
|
|
||||||
|
<img height=200 src="img/user/school548/1.jpg"> <img height=200 src="img/user/school548/2.jpg"> <img height=200 src="img/user/school548/3.jpg">
|
||||||
|
|
||||||
|
STL files and other materials: see [here](https://drive.google.com/drive/folders/1wTUzj087LjKQQl3Lz5CjHCuobxoykhyp?usp=share_link).
|
||||||
|
|
||||||
|
### Selected works
|
||||||
|
|
||||||
|
Author: [KiraFlux](https://t.me/@kiraflux_0XC0000005).<br>
|
||||||
|
Description: **custom ESPNOW remote control** was implemented, modified firmware to support ESPNOW protocol.<br>
|
||||||
|
Telegram posts: [1](https://t.me/opensourcequadcopter/106), [2](https://t.me/opensourcequadcopter/114).<br>
|
||||||
|
Modified Flix firmware: https://github.com/KiraFlux/flix/tree/klyax.<br>
|
||||||
|
Remote control project: https://github.com/KiraFlux/ESP32-DJC.<br>
|
||||||
|
Drone design: https://github.com/KiraFlux/Klyax.<br>
|
||||||
|
|
||||||
|
<img src="img/user/school548/kiraflux1.jpg" height=150> <img src="img/user/school548/kiraflux2.jpg" height=150>
|
||||||
|
|
||||||
|
**ESPNOW remote control demonstration**:
|
||||||
|
|
||||||
|
<img height=200 src="img/user/school548/kiraflux-video.jpg"><a href="https://drive.google.com/file/d/1soHDAeHQWnm97Y4dg4nWevJuMiTdJJXW/view?usp=sharing"></a>
|
||||||
|
|
||||||
|
Author: [tolyan4krut](https://t.me/tolyan4krut).<br>
|
||||||
|
Description: the first drone based on ESP32-S3-CAM board **with a camera**, implementing Wi-Fi video streaming. Runs HTTP server and HTTP video stream.<br>
|
||||||
|
Modified Flix firmware: https://github.com/CatRey/Flix-Camera-Streaming.<br>
|
||||||
|
[Telegram post](https://t.me/opensourcequadcopter/117).
|
||||||
|
|
||||||
|
<img src="img/user/school548/tolyan4krut.jpg" height=150>
|
||||||
|
|
||||||
|
**Video streaming and flight demonstration**:
|
||||||
|
|
||||||
|
<a href="https://drive.google.com/file/d/1KuOBsujLsk7q8FoqKD8u7uoq4ptS5onp/view?usp=sharing"><img height=200 src="img/user/school548/tolyan4krut-video.jpg"></a>
|
||||||
|
|
||||||
|
Author: [Vlad Tolshinov](https://t.me/Vlad_Tolshinov).<br>
|
||||||
|
Description: custom frame with enlarged arm length, which provides very high flight stability, 65 mm props.
|
||||||
|
|
||||||
|
<img src="img/user/school548/vlad_tolshinov1.jpg" height=150> <img src="img/user/school548/vlad_tolshinov2.jpg" height=150>
|
||||||
|
|
||||||
|
**Flight video**:
|
||||||
|
|
||||||
|
<a href="https://drive.google.com/file/d/1zu00DZxhC7DJ9Z2mYjtxdNQqOOLAyYbp/view?usp=sharing"><img height=200 src="img/user/school548/vlad_tolshinov-video.jpg"></a>
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
## RoboCamp
|
## RoboCamp
|
||||||
|
|
||||||
Author: RoboCamp participants.<br>
|
Author: RoboCamp participants.<br>
|
||||||
Description: 3D-printed and wooden frames, ESP32 Mini, DC-DC buck-boost converters. BetaFPV LiteRadio 3 to control the drones via Wi-Fi connection.<br>
|
Description: 3D-printed and wooden frames, ESP32 Mini, DC-DC buck-boost converters. BetaFPV LiteRadio 3 to control the drones via Wi-Fi connection.<br>
|
||||||
Features: altitude hold, obstacle avoidance, autonomous flight elements.<br>
|
Features: altitude hold, obstacle avoidance, autonomous flight elements.<br>
|
||||||
Some of the designed model files: https://drive.google.com/drive/folders/18YHWGquKeIevzrMH4-OUT-zKXMETTEUu?usp=share_link.
|
Some of the designed model files: see [here](https://drive.google.com/drive/folders/18YHWGquKeIevzrMH4-OUT-zKXMETTEUu?usp=share_link).
|
||||||
|
|
||||||
RoboCamp took place in July 2025, Saint Petersburg, where 9 participants designed and built their own drones using the Flix project, and then modified the firmware to complete specific flight tasks.
|
RoboCamp took place in July 2025, Saint Petersburg, where 9 participants designed and built their own drones using the Flix project, and then modified the firmware to complete specific flight tasks.
|
||||||
|
|
||||||
|
|||||||
@@ -14,7 +14,7 @@ Flix version 0 (obsolete):
|
|||||||
|Motor|8520 3.7V brushed motor (**shaft 0.8mm!**)|<img src="img/motor.jpeg" width=100>|4|
|
|Motor|8520 3.7V brushed motor (**shaft 0.8mm!**)|<img src="img/motor.jpeg" width=100>|4|
|
||||||
|Propeller|Hubsan 55 mm|<img src="img/prop.jpg" width=100>|4|
|
|Propeller|Hubsan 55 mm|<img src="img/prop.jpg" width=100>|4|
|
||||||
|Motor ESC|2.7A 1S Dual Way Micro Brush ESC|<img src="img/esc.jpg" width=100>|4|
|
|Motor ESC|2.7A 1S Dual Way Micro Brush ESC|<img src="img/esc.jpg" width=100>|4|
|
||||||
|RC transmitter|KINGKONG TINY X8|<img src="img/tx.jpg" width=100>|1|
|
|RC transmitter|KINGKONG TINY X8|<img src="img/kingkong.jpg" width=100>|1|
|
||||||
|RC receiver|DF500 (SBUS)|<img src="img/rx.jpg" width=100>|1|
|
|RC receiver|DF500 (SBUS)|<img src="img/rx.jpg" width=100>|1|
|
||||||
|~~SBUS inverter~~*||<img src="img/inv.jpg" width=100>|~~1~~|
|
|~~SBUS inverter~~*||<img src="img/inv.jpg" width=100>|~~1~~|
|
||||||
|Battery|3.7 Li-Po 850 MaH 60C|||
|
|Battery|3.7 Li-Po 850 MaH 60C|||
|
||||||
|
|||||||
32
flix/cli.ino
@@ -6,14 +6,16 @@
|
|||||||
#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 ACRO, STAB, AUTO;
|
extern const int RAW, ACRO, STAB, AUTO;
|
||||||
extern float t, dt, loopRate;
|
extern float t, dt, loopRate;
|
||||||
extern uint16_t channels[16];
|
extern uint16_t channels[16];
|
||||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
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"
|
||||||
@@ -35,10 +37,13 @@ const char* motd =
|
|||||||
"imu - show IMU data\n"
|
"imu - show IMU data\n"
|
||||||
"arm - arm the drone\n"
|
"arm - arm the drone\n"
|
||||||
"disarm - disarm the drone\n"
|
"disarm - disarm the drone\n"
|
||||||
"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"
|
||||||
|
"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 in-RAM log\n"
|
"log [dump] - print log header [and data]\n"
|
||||||
"cr - calibrate RC\n"
|
"cr - calibrate RC\n"
|
||||||
"ca - calibrate accel\n"
|
"ca - calibrate accel\n"
|
||||||
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
|
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
|
||||||
@@ -53,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) {
|
||||||
@@ -63,9 +66,7 @@ void pause(float duration) {
|
|||||||
while (t - start < duration) {
|
while (t - start < duration) {
|
||||||
step();
|
step();
|
||||||
handleInput();
|
handleInput();
|
||||||
#if WIFI_ENABLED
|
|
||||||
processMavlink();
|
processMavlink();
|
||||||
#endif
|
|
||||||
delay(50);
|
delay(50);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -93,7 +94,7 @@ void doCommand(String str, bool echo = false) {
|
|||||||
} else if (command == "p") {
|
} else if (command == "p") {
|
||||||
bool success = setParameter(arg0.c_str(), arg1.toFloat());
|
bool success = setParameter(arg0.c_str(), arg1.toFloat());
|
||||||
if (success) {
|
if (success) {
|
||||||
print("%s = %g\n", arg0.c_str(), arg1.toFloat());
|
print("%s = %g\n", arg0.c_str(), getParameter(arg0.c_str()));
|
||||||
} else {
|
} else {
|
||||||
print("Parameter not found: %s\n", arg0.c_str());
|
print("Parameter not found: %s\n", arg0.c_str());
|
||||||
}
|
}
|
||||||
@@ -116,6 +117,8 @@ void doCommand(String str, bool echo = false) {
|
|||||||
armed = true;
|
armed = true;
|
||||||
} else if (command == "disarm") {
|
} else if (command == "disarm") {
|
||||||
armed = false;
|
armed = false;
|
||||||
|
} else if (command == "raw") {
|
||||||
|
mode = RAW;
|
||||||
} else if (command == "stab") {
|
} else if (command == "stab") {
|
||||||
mode = STAB;
|
mode = STAB;
|
||||||
} else if (command == "acro") {
|
} else if (command == "acro") {
|
||||||
@@ -129,13 +132,21 @@ void doCommand(String str, bool echo = false) {
|
|||||||
}
|
}
|
||||||
print("\nroll: %g pitch: %g yaw: %g throttle: %g mode: %g\n",
|
print("\nroll: %g pitch: %g yaw: %g throttle: %g mode: %g\n",
|
||||||
controlRoll, controlPitch, controlYaw, controlThrottle, controlMode);
|
controlRoll, controlPitch, controlYaw, controlThrottle, controlMode);
|
||||||
|
print("time: %.1f\n", controlTime);
|
||||||
print("mode: %s\n", getModeName());
|
print("mode: %s\n", getModeName());
|
||||||
print("armed: %d\n", armed);
|
print("armed: %d\n", armed);
|
||||||
|
} else if (command == "wifi") {
|
||||||
|
printWiFiInfo();
|
||||||
|
} else if (command == "ap") {
|
||||||
|
configWiFi(true, arg0.c_str(), arg1.c_str());
|
||||||
|
} else if (command == "sta") {
|
||||||
|
configWiFi(false, arg0.c_str(), arg1.c_str());
|
||||||
} else if (command == "mot") {
|
} 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]);
|
||||||
} else if (command == "log") {
|
} else if (command == "log") {
|
||||||
dumpLog();
|
printLogHeader();
|
||||||
|
if (arg0 == "dump") printLogData();
|
||||||
} else if (command == "cr") {
|
} else if (command == "cr") {
|
||||||
calibrateRC();
|
calibrateRC();
|
||||||
} else if (command == "ca") {
|
} else if (command == "ca") {
|
||||||
@@ -169,6 +180,7 @@ void doCommand(String str, bool echo = false) {
|
|||||||
#endif
|
#endif
|
||||||
} else if (command == "reset") {
|
} else if (command == "reset") {
|
||||||
attitude = Quaternion();
|
attitude = Quaternion();
|
||||||
|
gyroBiasFilter.reset();
|
||||||
} else if (command == "reboot") {
|
} else if (command == "reboot") {
|
||||||
ESP.restart();
|
ESP.restart();
|
||||||
} else {
|
} else {
|
||||||
|
|||||||
@@ -34,10 +34,16 @@
|
|||||||
#define TILT_MAX radians(30)
|
#define TILT_MAX radians(30)
|
||||||
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||||
|
|
||||||
const int MANUAL = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
|
const int RAW = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
|
||||||
int mode = STAB;
|
int mode = STAB;
|
||||||
bool armed = false;
|
bool armed = false;
|
||||||
|
|
||||||
|
Quaternion attitudeTarget;
|
||||||
|
Vector ratesTarget;
|
||||||
|
Vector ratesExtra; // feedforward rates
|
||||||
|
Vector torqueTarget;
|
||||||
|
float thrustTarget;
|
||||||
|
|
||||||
PID rollRatePID(ROLLRATE_P, ROLLRATE_I, ROLLRATE_D, ROLLRATE_I_LIM, RATES_D_LPF_ALPHA);
|
PID rollRatePID(ROLLRATE_P, ROLLRATE_I, ROLLRATE_D, ROLLRATE_I_LIM, RATES_D_LPF_ALPHA);
|
||||||
PID pitchRatePID(PITCHRATE_P, PITCHRATE_I, PITCHRATE_D, PITCHRATE_I_LIM, RATES_D_LPF_ALPHA);
|
PID pitchRatePID(PITCHRATE_P, PITCHRATE_I, PITCHRATE_D, PITCHRATE_I_LIM, RATES_D_LPF_ALPHA);
|
||||||
PID yawRatePID(YAWRATE_P, YAWRATE_I, YAWRATE_D);
|
PID yawRatePID(YAWRATE_P, YAWRATE_I, YAWRATE_D);
|
||||||
@@ -46,12 +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
|
||||||
Quaternion attitudeTarget;
|
|
||||||
Vector ratesTarget;
|
|
||||||
Vector ratesExtra; // feedforward rates
|
|
||||||
Vector torqueTarget;
|
|
||||||
float thrustTarget;
|
|
||||||
|
|
||||||
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
||||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
||||||
@@ -65,16 +66,17 @@ void control() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void interpretControls() {
|
void interpretControls() {
|
||||||
// NOTE: put ACRO or MANUAL modes there if you want to use them
|
if (controlMode < 0.25) mode = flightModes[0];
|
||||||
if (controlMode < 0.25) 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 (controlMode > 0.75) mode = STAB;
|
|
||||||
|
|
||||||
if (mode == AUTO) return; // pilot is not effective in AUTO mode
|
if (mode == AUTO) return; // pilot is not effective in AUTO mode
|
||||||
|
|
||||||
if (controlThrottle < 0.05 && controlYaw > 0.95) armed = true; // arm gesture
|
if (controlThrottle < 0.05 && controlYaw > 0.95) armed = true; // arm gesture
|
||||||
if (controlThrottle < 0.05 && controlYaw < -0.95) armed = false; // disarm gesture
|
if (controlThrottle < 0.05 && controlYaw < -0.95) armed = false; // disarm gesture
|
||||||
|
|
||||||
|
if (abs(controlYaw) < 0.1) controlYaw = 0; // yaw dead zone
|
||||||
|
|
||||||
thrustTarget = controlThrottle;
|
thrustTarget = controlThrottle;
|
||||||
|
|
||||||
if (mode == STAB) {
|
if (mode == STAB) {
|
||||||
@@ -91,10 +93,10 @@ void interpretControls() {
|
|||||||
ratesTarget.z = -controlYaw * maxRate.z; // positive yaw stick means clockwise rotation in FLU
|
ratesTarget.z = -controlYaw * maxRate.z; // positive yaw stick means clockwise rotation in FLU
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode == MANUAL) { // passthrough mode
|
if (mode == RAW) { // direct torque control
|
||||||
attitudeTarget.invalidate(); // skip attitude control
|
attitudeTarget.invalidate(); // skip attitude control
|
||||||
ratesTarget.invalidate(); // skip rate control
|
ratesTarget.invalidate(); // skip rate control
|
||||||
torqueTarget = Vector(controlRoll, controlPitch, -controlYaw) * 0.01;
|
torqueTarget = Vector(controlRoll, controlPitch, -controlYaw) * 0.1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -155,7 +157,7 @@ void controlTorque() {
|
|||||||
|
|
||||||
const char* getModeName() {
|
const char* getModeName() {
|
||||||
switch (mode) {
|
switch (mode) {
|
||||||
case MANUAL: return "MANUAL";
|
case RAW: return "RAW";
|
||||||
case ACRO: return "ACRO";
|
case ACRO: return "ACRO";
|
||||||
case STAB: return "STAB";
|
case STAB: return "STAB";
|
||||||
case AUTO: return "AUTO";
|
case AUTO: return "AUTO";
|
||||||
|
|||||||
@@ -1,15 +1,19 @@
|
|||||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||||
// Repository: https://github.com/okalachev/flix
|
// Repository: https://github.com/okalachev/flix
|
||||||
|
|
||||||
// Attitude estimation from gyro and accelerometer
|
// Attitude estimation using gyro and accelerometer
|
||||||
|
|
||||||
#include "quaternion.h"
|
#include "quaternion.h"
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
#include "lpf.h"
|
#include "lpf.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
#define WEIGHT_ACC 0.003
|
Vector rates; // estimated angular rates, rad/s
|
||||||
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
Quaternion attitude; // estimated attitude
|
||||||
|
bool landed;
|
||||||
|
|
||||||
|
float accWeight = 0.003;
|
||||||
|
LowPassFilter<Vector> ratesFilter(0.2); // cutoff frequency ~ 40 Hz
|
||||||
|
|
||||||
void estimate() {
|
void estimate() {
|
||||||
applyGyro();
|
applyGyro();
|
||||||
@@ -18,7 +22,6 @@ void estimate() {
|
|||||||
|
|
||||||
void applyGyro() {
|
void applyGyro() {
|
||||||
// filter gyro to get angular rates
|
// filter gyro to get angular rates
|
||||||
static LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
|
|
||||||
rates = ratesFilter.update(gyro);
|
rates = ratesFilter.update(gyro);
|
||||||
|
|
||||||
// apply rates to attitude
|
// apply rates to attitude
|
||||||
@@ -34,7 +37,7 @@ void applyAcc() {
|
|||||||
|
|
||||||
// calculate accelerometer correction
|
// calculate accelerometer correction
|
||||||
Vector up = Quaternion::rotateVector(Vector(0, 0, 1), attitude);
|
Vector up = Quaternion::rotateVector(Vector(0, 0, 1), attitude);
|
||||||
Vector correction = Vector::rotationVectorBetween(acc, up) * WEIGHT_ACC;
|
Vector correction = Vector::rotationVectorBetween(acc, up) * accWeight;
|
||||||
|
|
||||||
// apply correction
|
// apply correction
|
||||||
attitude = Quaternion::rotate(attitude, Quaternion::fromRotationVector(correction));
|
attitude = Quaternion::rotate(attitude, Quaternion::fromRotationVector(correction));
|
||||||
|
|||||||
@@ -7,31 +7,23 @@
|
|||||||
#include "quaternion.h"
|
#include "quaternion.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
#define SERIAL_BAUDRATE 115200
|
extern float t, dt;
|
||||||
#define WIFI_ENABLED 1
|
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
||||||
|
extern Vector gyro, acc;
|
||||||
float t = NAN; // current step time, s
|
extern Vector rates;
|
||||||
float dt; // time delta from previous step, s
|
extern Quaternion attitude;
|
||||||
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
|
extern bool landed;
|
||||||
float controlMode = NAN;
|
extern float motors[4];
|
||||||
Vector gyro; // gyroscope data
|
|
||||||
Vector acc; // accelerometer data, m/s/s
|
|
||||||
Vector rates; // filtered angular rates, rad/s
|
|
||||||
Quaternion attitude; // estimated attitude
|
|
||||||
bool landed; // are we landed and stationary
|
|
||||||
float motors[4]; // normalized motors thrust in range [0..1]
|
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
Serial.begin(SERIAL_BAUDRATE);
|
Serial.begin(115200);
|
||||||
print("Initializing flix\n");
|
print("Initializing flix\n");
|
||||||
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);
|
||||||
@@ -46,9 +38,7 @@ void loop() {
|
|||||||
control();
|
control();
|
||||||
sendMotors();
|
sendMotors();
|
||||||
handleInput();
|
handleInput();
|
||||||
#if WIFI_ENABLED
|
|
||||||
processMavlink();
|
processMavlink();
|
||||||
#endif
|
|
||||||
logData();
|
logData();
|
||||||
syncParameters();
|
syncParameters();
|
||||||
}
|
}
|
||||||
|
|||||||
26
flix/imu.ino
@@ -10,10 +10,16 @@
|
|||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
MPU9250 imu(SPI);
|
MPU9250 imu(SPI);
|
||||||
|
Vector imuRotation(0, 0, -PI / 2); // imu orientation as Euler angles
|
||||||
|
|
||||||
|
Vector gyro; // gyroscope output, rad/s
|
||||||
|
Vector gyroBias;
|
||||||
|
|
||||||
|
Vector acc; // accelerometer output, m/s/s
|
||||||
Vector accBias;
|
Vector accBias;
|
||||||
Vector accScale(1, 1, 1);
|
Vector accScale(1, 1, 1);
|
||||||
Vector gyroBias;
|
|
||||||
|
LowPassFilter<Vector> gyroBiasFilter(0.001);
|
||||||
|
|
||||||
void setupIMU() {
|
void setupIMU() {
|
||||||
print("Setup IMU\n");
|
print("Setup IMU\n");
|
||||||
@@ -37,24 +43,16 @@ void readIMU() {
|
|||||||
// apply scale and bias
|
// apply scale and bias
|
||||||
acc = (acc - accBias) / accScale;
|
acc = (acc - accBias) / accScale;
|
||||||
gyro = gyro - gyroBias;
|
gyro = gyro - gyroBias;
|
||||||
// rotate
|
// rotate to body frame
|
||||||
rotateIMU(acc);
|
Quaternion rotation = Quaternion::fromEuler(imuRotation);
|
||||||
rotateIMU(gyro);
|
acc = Quaternion::rotateVector(acc, rotation.inversed());
|
||||||
}
|
gyro = Quaternion::rotateVector(gyro, rotation.inversed());
|
||||||
|
|
||||||
void rotateIMU(Vector& data) {
|
|
||||||
// Rotate from LFD to FLU
|
|
||||||
// NOTE: In case of using other IMU orientation, change this line:
|
|
||||||
data = Vector(data.y, data.x, -data.z);
|
|
||||||
// Axes orientation for various boards: https://github.com/okalachev/flixperiph#imu-axes-orientation
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void calibrateGyroOnce() {
|
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
|
||||||
|
gyroBias = gyroBiasFilter.update(gyro);
|
||||||
static LowPassFilter<Vector> gyroCalibrationFilter(0.001);
|
|
||||||
gyroBias = gyroCalibrationFilter.update(gyro);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void calibrateAccel() {
|
void calibrateAccel() {
|
||||||
|
|||||||
14
flix/log.ino
@@ -4,10 +4,10 @@
|
|||||||
// In-RAM logging
|
// In-RAM logging
|
||||||
|
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
|
#include "util.h"
|
||||||
|
|
||||||
#define LOG_RATE 100
|
#define LOG_RATE 100
|
||||||
#define LOG_DURATION 10
|
#define LOG_DURATION 10
|
||||||
#define LOG_PERIOD 1.0 / LOG_RATE
|
|
||||||
#define LOG_SIZE LOG_DURATION * LOG_RATE
|
#define LOG_SIZE LOG_DURATION * LOG_RATE
|
||||||
|
|
||||||
Vector attitudeEuler;
|
Vector attitudeEuler;
|
||||||
@@ -46,9 +46,8 @@ void prepareLogData() {
|
|||||||
void logData() {
|
void logData() {
|
||||||
if (!armed) return;
|
if (!armed) return;
|
||||||
static int logPointer = 0;
|
static int logPointer = 0;
|
||||||
static float logTime = 0;
|
static Rate period(LOG_RATE);
|
||||||
if (t - logTime < LOG_PERIOD) return;
|
if (!period) return;
|
||||||
logTime = t;
|
|
||||||
|
|
||||||
prepareLogData();
|
prepareLogData();
|
||||||
|
|
||||||
@@ -62,12 +61,13 @@ void logData() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void dumpLog() {
|
void printLogHeader() {
|
||||||
// Print header
|
|
||||||
for (int i = 0; i < logColumns; i++) {
|
for (int i = 0; i < logColumns; i++) {
|
||||||
print("%s%s", logEntries[i].name, i < logColumns - 1 ? "," : "\n");
|
print("%s%s", logEntries[i].name, i < logColumns - 1 ? "," : "\n");
|
||||||
}
|
}
|
||||||
// Print data
|
}
|
||||||
|
|
||||||
|
void printLogData() {
|
||||||
for (int i = 0; i < LOG_SIZE; i++) {
|
for (int i = 0; i < LOG_SIZE; i++) {
|
||||||
if (logBuffer[i][0] == 0) continue; // skip empty records
|
if (logBuffer[i][0] == 0) continue; // skip empty records
|
||||||
for (int j = 0; j < logColumns; j++) {
|
for (int j = 0; j < logColumns; j++) {
|
||||||
|
|||||||
14
flix/lpf.h
@@ -14,15 +14,6 @@ public:
|
|||||||
LowPassFilter(float alpha): alpha(alpha) {};
|
LowPassFilter(float alpha): alpha(alpha) {};
|
||||||
|
|
||||||
T update(const T input) {
|
T update(const T input) {
|
||||||
if (alpha == 1) { // filter disabled
|
|
||||||
return input;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!initialized) {
|
|
||||||
output = input;
|
|
||||||
initialized = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
return output += alpha * (input - output);
|
return output += alpha * (input - output);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -31,9 +22,6 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
void reset() {
|
void reset() {
|
||||||
initialized = false;
|
output = T(); // set to zero
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
|
||||||
bool initialized = false;
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -3,21 +3,18 @@
|
|||||||
|
|
||||||
// MAVLink communication
|
// MAVLink communication
|
||||||
|
|
||||||
#if WIFI_ENABLED
|
|
||||||
|
|
||||||
#include <MAVLink.h>
|
#include <MAVLink.h>
|
||||||
|
#include "util.h"
|
||||||
|
|
||||||
#define SYSTEM_ID 1
|
extern float controlTime;
|
||||||
#define PERIOD_SLOW 1.0
|
|
||||||
#define PERIOD_FAST 0.1
|
int mavlinkSysId = 1;
|
||||||
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
Rate telemetryFast(10);
|
||||||
|
Rate telemetrySlow(2);
|
||||||
|
|
||||||
bool mavlinkConnected = false;
|
bool mavlinkConnected = false;
|
||||||
String mavlinkPrintBuffer;
|
String mavlinkPrintBuffer;
|
||||||
|
|
||||||
extern float controlTime;
|
|
||||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
|
||||||
|
|
||||||
void processMavlink() {
|
void processMavlink() {
|
||||||
sendMavlink();
|
sendMavlink();
|
||||||
receiveMavlink();
|
receiveMavlink();
|
||||||
@@ -26,16 +23,11 @@ void processMavlink() {
|
|||||||
void sendMavlink() {
|
void sendMavlink() {
|
||||||
sendMavlinkPrint();
|
sendMavlinkPrint();
|
||||||
|
|
||||||
static float lastSlow = 0;
|
|
||||||
static float lastFast = 0;
|
|
||||||
|
|
||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
uint32_t time = t * 1000;
|
uint32_t time = t * 1000;
|
||||||
|
|
||||||
if (t - lastSlow >= PERIOD_SLOW) {
|
if (telemetrySlow) {
|
||||||
lastSlow = t;
|
mavlink_msg_heartbeat_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
|
||||||
|
|
||||||
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),
|
||||||
@@ -44,29 +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 (t - lastFast >= PERIOD_FAST && mavlinkConnected) {
|
if (telemetryFast && mavlinkConnected) {
|
||||||
lastFast = t;
|
const float offset[] = {0, 0, 0, 0};
|
||||||
|
mavlink_msg_attitude_quaternion_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||||
const float zeroQuat[] = {0, 0, 0, 0};
|
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, offset); // convert to frd
|
||||||
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
|
||||||
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd
|
|
||||||
sendMessage(&msg);
|
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;
|
||||||
@@ -109,18 +99,16 @@ void handleMavlink(const void *_msg) {
|
|||||||
controlYaw = m.r / 1000.0f;
|
controlYaw = m.r / 1000.0f;
|
||||||
controlMode = NAN;
|
controlMode = NAN;
|
||||||
controlTime = t;
|
controlTime = t;
|
||||||
|
|
||||||
if (abs(controlYaw) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controlYaw = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
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);
|
||||||
}
|
}
|
||||||
@@ -129,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
|
||||||
@@ -138,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);
|
||||||
}
|
}
|
||||||
@@ -146,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
|
||||||
@@ -183,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;
|
||||||
@@ -205,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();
|
||||||
@@ -214,17 +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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (msg.msgid == MAVLINK_MSG_ID_LOG_REQUEST_DATA) {
|
||||||
|
mavlink_log_request_data_t m;
|
||||||
|
mavlink_msg_log_request_data_decode(&msg, &m);
|
||||||
|
if (m.target_system && m.target_system != mavlinkSysId) return;
|
||||||
|
|
||||||
|
// Send all log records
|
||||||
|
for (int i = 0; i < sizeof(logBuffer) / sizeof(logBuffer[0]); i++) {
|
||||||
|
mavlink_message_t msg;
|
||||||
|
mavlink_msg_log_data_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, 0, i,
|
||||||
|
sizeof(logBuffer[0]), (uint8_t *)logBuffer[i]);
|
||||||
|
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);
|
||||||
}
|
}
|
||||||
@@ -243,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);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -260,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);
|
||||||
@@ -268,5 +271,3 @@ void sendMavlinkPrint() {
|
|||||||
}
|
}
|
||||||
mavlinkPrintBuffer.clear();
|
mavlinkPrintBuffer.clear();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|||||||
@@ -1,23 +1,19 @@
|
|||||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||||
// Repository: https://github.com/okalachev/flix
|
// Repository: https://github.com/okalachev/flix
|
||||||
|
|
||||||
// Motors output control using MOSFETs
|
// PWM control for motors
|
||||||
// In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400)
|
|
||||||
|
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
#define MOTOR_0_PIN 12 // rear left
|
float motors[4]; // normalized motor thrusts in range [0..1]
|
||||||
#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
|
int motorPins[4] = {12, 13, 14, 15}; // default pin numbers
|
||||||
#define PWM_RESOLUTION 10
|
int pwmFrequency = 78000;
|
||||||
#define PWM_STOP 0
|
int pwmResolution = 10;
|
||||||
#define PWM_MIN 0
|
int pwmStop = 0;
|
||||||
#define PWM_MAX 1000000 / PWM_FREQUENCY
|
int pwmMin = 0;
|
||||||
|
int pwmMax = -1; // -1 means duty cycle mode
|
||||||
|
|
||||||
// Motors array indexes:
|
|
||||||
const int MOTOR_REAR_LEFT = 0;
|
const int MOTOR_REAR_LEFT = 0;
|
||||||
const int MOTOR_REAR_RIGHT = 1;
|
const int MOTOR_REAR_RIGHT = 1;
|
||||||
const int MOTOR_FRONT_RIGHT = 2;
|
const int MOTOR_FRONT_RIGHT = 2;
|
||||||
@@ -25,30 +21,31 @@ const int MOTOR_FRONT_LEFT = 3;
|
|||||||
|
|
||||||
void setupMotors() {
|
void setupMotors() {
|
||||||
print("Setup Motors\n");
|
print("Setup Motors\n");
|
||||||
|
|
||||||
// configure pins
|
// configure pins
|
||||||
ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
for (int i = 0; i < 4; i++) {
|
||||||
ledcAttach(MOTOR_1_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
ledcAttach(motorPins[i], pwmFrequency, pwmResolution);
|
||||||
ledcAttach(MOTOR_2_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
pwmFrequency = ledcChangeFrequency(motorPins[i], pwmFrequency, pwmResolution); // when reconfiguring
|
||||||
ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
}
|
||||||
|
|
||||||
sendMotors();
|
sendMotors();
|
||||||
print("Motors initialized\n");
|
print("Motors initialized\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
int getDutyCycle(float value) {
|
void sendMotors() {
|
||||||
value = constrain(value, 0, 1);
|
for (int i = 0; i < 4; i++) {
|
||||||
float pwm = mapff(value, 0, 1, PWM_MIN, PWM_MAX);
|
ledcWrite(motorPins[i], getDutyCycle(motors[i]));
|
||||||
if (value == 0) pwm = PWM_STOP;
|
}
|
||||||
float duty = mapff(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
|
|
||||||
return round(duty);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void sendMotors() {
|
int getDutyCycle(float value) {
|
||||||
ledcWrite(MOTOR_0_PIN, getDutyCycle(motors[0]));
|
value = constrain(value, 0, 1);
|
||||||
ledcWrite(MOTOR_1_PIN, getDutyCycle(motors[1]));
|
if (pwmMax >= 0) { // pwm mode
|
||||||
ledcWrite(MOTOR_2_PIN, getDutyCycle(motors[2]));
|
float pwm = mapf(value, 0, 1, pwmMin, pwmMax);
|
||||||
ledcWrite(MOTOR_3_PIN, getDutyCycle(motors[3]));
|
if (value == 0) pwm = pwmStop;
|
||||||
|
float duty = mapf(pwm, 0, 1000000 / pwmFrequency, 0, (1 << pwmResolution) - 1);
|
||||||
|
return round(duty);
|
||||||
|
} else { // duty cycle mode
|
||||||
|
return round(value * ((1 << pwmResolution) - 1));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool motorsActive() {
|
bool motorsActive() {
|
||||||
|
|||||||
@@ -4,50 +4,79 @@
|
|||||||
// Parameters storage in flash memory
|
// Parameters storage in flash memory
|
||||||
|
|
||||||
#include <Preferences.h>
|
#include <Preferences.h>
|
||||||
|
#include "util.h"
|
||||||
|
|
||||||
extern float channelZero[16];
|
extern int channelZero[16];
|
||||||
extern float channelMax[16];
|
extern int channelMax[16];
|
||||||
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
||||||
|
extern int wifiMode, udpLocalPort, udpRemotePort;
|
||||||
|
extern float rcLossTimeout, descendTime;
|
||||||
|
|
||||||
Preferences storage;
|
Preferences storage;
|
||||||
|
|
||||||
struct Parameter {
|
struct Parameter {
|
||||||
const char *name; // max length is 16
|
const char *name; // max length is 15
|
||||||
float *variable;
|
bool integer;
|
||||||
float value; // cache
|
union { float *f; int *i; }; // pointer to the variable
|
||||||
|
float cache; // what's stored in flash
|
||||||
|
void (*callback)(); // called after parameter change
|
||||||
|
Parameter(const char *name, float *variable, void (*callback)() = nullptr) : name(name), integer(false), f(variable), callback(callback) {};
|
||||||
|
Parameter(const char *name, int *variable, void (*callback)() = nullptr) : name(name), integer(true), i(variable), callback(callback) {};
|
||||||
|
float getValue() const { return integer ? *i : *f; };
|
||||||
|
void setValue(const float value) { if (integer) *i = value; else *f = value; };
|
||||||
};
|
};
|
||||||
|
|
||||||
Parameter parameters[] = {
|
Parameter parameters[] = {
|
||||||
// control
|
// control
|
||||||
{"ROLLRATE_P", &rollRatePID.p},
|
{"CTL_R_RATE_P", &rollRatePID.p},
|
||||||
{"ROLLRATE_I", &rollRatePID.i},
|
{"CTL_R_RATE_I", &rollRatePID.i},
|
||||||
{"ROLLRATE_D", &rollRatePID.d},
|
{"CTL_R_RATE_D", &rollRatePID.d},
|
||||||
{"ROLLRATE_I_LIM", &rollRatePID.windup},
|
{"CTL_R_RATE_WU", &rollRatePID.windup},
|
||||||
{"PITCHRATE_P", &pitchRatePID.p},
|
{"CTL_P_RATE_P", &pitchRatePID.p},
|
||||||
{"PITCHRATE_I", &pitchRatePID.i},
|
{"CTL_P_RATE_I", &pitchRatePID.i},
|
||||||
{"PITCHRATE_D", &pitchRatePID.d},
|
{"CTL_P_RATE_D", &pitchRatePID.d},
|
||||||
{"PITCHRATE_I_LIM", &pitchRatePID.windup},
|
{"CTL_P_RATE_WU", &pitchRatePID.windup},
|
||||||
{"YAWRATE_P", &yawRatePID.p},
|
{"CTL_Y_RATE_P", &yawRatePID.p},
|
||||||
{"YAWRATE_I", &yawRatePID.i},
|
{"CTL_Y_RATE_I", &yawRatePID.i},
|
||||||
{"YAWRATE_D", &yawRatePID.d},
|
{"CTL_Y_RATE_D", &yawRatePID.d},
|
||||||
{"ROLL_P", &rollPID.p},
|
{"CTL_R_P", &rollPID.p},
|
||||||
{"ROLL_I", &rollPID.i},
|
{"CTL_R_I", &rollPID.i},
|
||||||
{"ROLL_D", &rollPID.d},
|
{"CTL_R_D", &rollPID.d},
|
||||||
{"PITCH_P", &pitchPID.p},
|
{"CTL_P_P", &pitchPID.p},
|
||||||
{"PITCH_I", &pitchPID.i},
|
{"CTL_P_I", &pitchPID.i},
|
||||||
{"PITCH_D", &pitchPID.d},
|
{"CTL_P_D", &pitchPID.d},
|
||||||
{"YAW_P", &yawPID.p},
|
{"CTL_Y_P", &yawPID.p},
|
||||||
{"PITCHRATE_MAX", &maxRate.y},
|
{"CTL_P_RATE_MAX", &maxRate.y},
|
||||||
{"ROLLRATE_MAX", &maxRate.x},
|
{"CTL_R_RATE_MAX", &maxRate.x},
|
||||||
{"YAWRATE_MAX", &maxRate.z},
|
{"CTL_Y_RATE_MAX", &maxRate.z},
|
||||||
{"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
|
||||||
{"ACC_BIAS_X", &accBias.x},
|
{"IMU_ROT_ROLL", &imuRotation.x},
|
||||||
{"ACC_BIAS_Y", &accBias.y},
|
{"IMU_ROT_PITCH", &imuRotation.y},
|
||||||
{"ACC_BIAS_Z", &accBias.z},
|
{"IMU_ROT_YAW", &imuRotation.z},
|
||||||
{"ACC_SCALE_X", &accScale.x},
|
{"IMU_ACC_BIAS_X", &accBias.x},
|
||||||
{"ACC_SCALE_Y", &accScale.y},
|
{"IMU_ACC_BIAS_Y", &accBias.y},
|
||||||
{"ACC_SCALE_Z", &accScale.z},
|
{"IMU_ACC_BIAS_Z", &accBias.z},
|
||||||
|
{"IMU_ACC_SCALE_X", &accScale.x},
|
||||||
|
{"IMU_ACC_SCALE_Y", &accScale.y},
|
||||||
|
{"IMU_ACC_SCALE_Z", &accScale.z},
|
||||||
|
{"IMU_GYRO_BIAS_A", &gyroBiasFilter.alpha},
|
||||||
|
// estimate
|
||||||
|
{"EST_ACC_WEIGHT", &accWeight},
|
||||||
|
{"EST_RATES_LPF_A", &ratesFilter.alpha},
|
||||||
|
// motors
|
||||||
|
{"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT], setupMotors},
|
||||||
|
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT], setupMotors},
|
||||||
|
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT], setupMotors},
|
||||||
|
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT], setupMotors},
|
||||||
|
{"MOT_PWM_FREQ", &pwmFrequency, setupMotors},
|
||||||
|
{"MOT_PWM_RES", &pwmResolution, setupMotors},
|
||||||
|
{"MOT_PWM_STOP", &pwmStop},
|
||||||
|
{"MOT_PWM_MIN", &pwmMin},
|
||||||
|
{"MOT_PWM_MAX", &pwmMax},
|
||||||
// rc
|
// rc
|
||||||
{"RC_ZERO_0", &channelZero[0]},
|
{"RC_ZERO_0", &channelZero[0]},
|
||||||
{"RC_ZERO_1", &channelZero[1]},
|
{"RC_ZERO_1", &channelZero[1]},
|
||||||
@@ -70,17 +99,29 @@ Parameter parameters[] = {
|
|||||||
{"RC_THROTTLE", &throttleChannel},
|
{"RC_THROTTLE", &throttleChannel},
|
||||||
{"RC_YAW", &yawChannel},
|
{"RC_YAW", &yawChannel},
|
||||||
{"RC_MODE", &modeChannel},
|
{"RC_MODE", &modeChannel},
|
||||||
|
// wifi
|
||||||
|
{"WIFI_MODE", &wifiMode},
|
||||||
|
{"WIFI_LOC_PORT", &udpLocalPort},
|
||||||
|
{"WIFI_REM_PORT", &udpRemotePort},
|
||||||
|
// mavlink
|
||||||
|
{"MAV_SYS_ID", &mavlinkSysId},
|
||||||
|
{"MAV_RATE_SLOW", &telemetrySlow.rate},
|
||||||
|
{"MAV_RATE_FAST", &telemetryFast.rate},
|
||||||
|
// safety
|
||||||
|
{"SF_RC_LOSS_TIME", &rcLossTimeout},
|
||||||
|
{"SF_DESCEND_TIME", &descendTime},
|
||||||
};
|
};
|
||||||
|
|
||||||
void setupParameters() {
|
void setupParameters() {
|
||||||
storage.begin("flix", false);
|
print("Setup parameters\n");
|
||||||
|
storage.begin("flix");
|
||||||
// Read parameters from storage
|
// Read parameters from storage
|
||||||
for (auto ¶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();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -95,13 +136,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;
|
||||||
@@ -109,8 +150,10 @@ 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);
|
||||||
|
if (parameter.callback) parameter.callback();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -118,22 +161,22 @@ bool setParameter(const char *name, const float value) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void syncParameters() {
|
void syncParameters() {
|
||||||
static float lastSync = 0;
|
static Rate rate(1);
|
||||||
if (t - lastSync < 1) return; // sync once per second
|
if (!rate) return; // sync once per second
|
||||||
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
|
||||||
lastSync = t;
|
|
||||||
|
|
||||||
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);
|
|
||||||
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());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
38
flix/rc.ino
@@ -6,15 +6,17 @@
|
|||||||
#include <SBUS.h>
|
#include <SBUS.h>
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
SBUS rc(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
|
SBUS rc(Serial2);
|
||||||
|
|
||||||
uint16_t channels[16]; // raw rc channels
|
uint16_t channels[16]; // raw rc channels
|
||||||
float controlTime; // time of the last controls update
|
int channelZero[16]; // calibration zero values
|
||||||
float channelZero[16]; // calibration zero values
|
int channelMax[16]; // calibration max values
|
||||||
float channelMax[16]; // calibration max values
|
|
||||||
|
|
||||||
// Channels mapping (using float to store in parameters):
|
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
|
||||||
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
|
float controlMode = NAN;
|
||||||
|
float controlTime = NAN; // time of the last controls update
|
||||||
|
|
||||||
|
int rollChannel = -1, pitchChannel = -1, throttleChannel = -1, yawChannel = -1, modeChannel = -1; // channel mapping
|
||||||
|
|
||||||
void setupRC() {
|
void setupRC() {
|
||||||
print("Setup RC\n");
|
print("Setup RC\n");
|
||||||
@@ -38,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] : NAN;
|
controlRoll = rollChannel < 0 ? 0 : controls[rollChannel];
|
||||||
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN;
|
controlPitch = pitchChannel < 0 ? 0 : controls[pitchChannel];
|
||||||
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN;
|
controlYaw = yawChannel < 0 ? 0 : controls[yawChannel];
|
||||||
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN;
|
controlThrottle = throttleChannel < 0 ? 0 : controls[throttleChannel];
|
||||||
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN;
|
controlMode = modeChannel < 0 ? NAN : controls[modeChannel]; // mode control is ineffective if not mapped
|
||||||
}
|
}
|
||||||
|
|
||||||
void calibrateRC() {
|
void calibrateRC() {
|
||||||
@@ -61,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
|
||||||
@@ -82,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,12 +3,12 @@
|
|||||||
|
|
||||||
// Fail-safe functions
|
// Fail-safe functions
|
||||||
|
|
||||||
#define RC_LOSS_TIMEOUT 1
|
|
||||||
#define DESCEND_TIME 10
|
|
||||||
|
|
||||||
extern float controlTime;
|
extern float controlTime;
|
||||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
|
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
|
||||||
|
|
||||||
|
float rcLossTimeout = 1;
|
||||||
|
float descendTime = 10;
|
||||||
|
|
||||||
void failsafe() {
|
void failsafe() {
|
||||||
rcLossFailsafe();
|
rcLossFailsafe();
|
||||||
autoFailsafe();
|
autoFailsafe();
|
||||||
@@ -16,9 +16,8 @@ void failsafe() {
|
|||||||
|
|
||||||
// RC loss failsafe
|
// RC loss failsafe
|
||||||
void rcLossFailsafe() {
|
void rcLossFailsafe() {
|
||||||
if (controlTime == 0) return; // no RC at all
|
|
||||||
if (!armed) return;
|
if (!armed) return;
|
||||||
if (t - controlTime > RC_LOSS_TIMEOUT) {
|
if (t - controlTime > rcLossTimeout) {
|
||||||
descend();
|
descend();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -27,7 +26,7 @@ void rcLossFailsafe() {
|
|||||||
void descend() {
|
void descend() {
|
||||||
mode = AUTO;
|
mode = AUTO;
|
||||||
attitudeTarget = Quaternion();
|
attitudeTarget = Quaternion();
|
||||||
thrustTarget -= dt / DESCEND_TIME;
|
thrustTarget -= dt / descendTime;
|
||||||
if (thrustTarget < 0) {
|
if (thrustTarget < 0) {
|
||||||
thrustTarget = 0;
|
thrustTarget = 0;
|
||||||
armed = false;
|
armed = false;
|
||||||
|
|||||||
@@ -3,6 +3,8 @@
|
|||||||
|
|
||||||
// Time related functions
|
// Time related functions
|
||||||
|
|
||||||
|
float t = NAN; // current time, s
|
||||||
|
float dt; // time delta with the previous step, s
|
||||||
float loopRate; // Hz
|
float loopRate; // Hz
|
||||||
|
|
||||||
void step() {
|
void step() {
|
||||||
|
|||||||
26
flix/util.h
@@ -12,11 +12,7 @@
|
|||||||
const float ONE_G = 9.80665;
|
const float ONE_G = 9.80665;
|
||||||
extern float t;
|
extern float t;
|
||||||
|
|
||||||
float mapf(long x, long in_min, long 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 (float)(x - in_min) * (out_max - out_min) / (float)(in_max - in_min) + out_min;
|
|
||||||
}
|
|
||||||
|
|
||||||
float mapff(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;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -54,20 +50,34 @@ void splitString(String& str, String& token0, String& token1, String& token2) {
|
|||||||
token2 = strtok(NULL, "");
|
token2 = strtok(NULL, "");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Rate limiter
|
||||||
|
class Rate {
|
||||||
|
public:
|
||||||
|
float rate;
|
||||||
|
float last = 0;
|
||||||
|
Rate(float rate) : rate(rate) {}
|
||||||
|
|
||||||
|
operator bool() {
|
||||||
|
if (t - last >= 1 / rate) {
|
||||||
|
last = t;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
// Delay filter for boolean signals - ensures the signal is on for at least 'delay' seconds
|
// Delay filter for boolean signals - ensures the signal is on for at least 'delay' seconds
|
||||||
class Delay {
|
class Delay {
|
||||||
public:
|
public:
|
||||||
float delay;
|
float delay;
|
||||||
float start = NAN;
|
float start = NAN;
|
||||||
|
|
||||||
Delay(float delay) : delay(delay) {}
|
Delay(float delay) : delay(delay) {}
|
||||||
|
|
||||||
bool update(bool on) {
|
bool update(bool on) {
|
||||||
if (!on) {
|
if (!on) {
|
||||||
start = NAN;
|
start = NAN;
|
||||||
return false;
|
return false;
|
||||||
}
|
} else if (isnan(start)) {
|
||||||
if (isnan(start)) {
|
|
||||||
start = t;
|
start = t;
|
||||||
}
|
}
|
||||||
return t - start >= delay;
|
return t - start >= delay;
|
||||||
|
|||||||
@@ -35,7 +35,6 @@ public:
|
|||||||
z = NAN;
|
z = NAN;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
float norm() const {
|
float norm() const {
|
||||||
return sqrt(x * x + y * y + z * z);
|
return sqrt(x * x + y * y + z * z);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,38 +1,76 @@
|
|||||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||||
// Repository: https://github.com/okalachev/flix
|
// Repository: https://github.com/okalachev/flix
|
||||||
|
|
||||||
// Wi-Fi support
|
// Wi-Fi communication
|
||||||
|
|
||||||
#if WIFI_ENABLED
|
|
||||||
|
|
||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
#include <WiFiAP.h>
|
#include <WiFiAP.h>
|
||||||
#include <WiFiUdp.h>
|
#include <WiFiUdp.h>
|
||||||
|
#include "Preferences.h"
|
||||||
|
|
||||||
#define WIFI_SSID "flix"
|
extern Preferences storage; // use the main preferences storage
|
||||||
#define WIFI_PASSWORD "flixwifi"
|
|
||||||
#define WIFI_UDP_PORT 14550
|
const int W_DISABLED = 0, W_AP = 1, W_STA = 2;
|
||||||
#define WIFI_UDP_REMOTE_PORT 14550
|
int wifiMode = W_AP;
|
||||||
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
|
int udpLocalPort = 14550;
|
||||||
|
int udpRemotePort = 14550;
|
||||||
|
IPAddress udpRemoteIP = "255.255.255.255";
|
||||||
|
|
||||||
WiFiUDP udp;
|
WiFiUDP udp;
|
||||||
|
|
||||||
void setupWiFi() {
|
void setupWiFi() {
|
||||||
print("Setup Wi-Fi\n");
|
print("Setup Wi-Fi\n");
|
||||||
WiFi.softAP(WIFI_SSID, WIFI_PASSWORD);
|
if (wifiMode == W_AP) {
|
||||||
udp.begin(WIFI_UDP_PORT);
|
WiFi.softAP(storage.getString("WIFI_AP_SSID", "flix").c_str(), storage.getString("WIFI_AP_PASS", "flixwifi").c_str());
|
||||||
|
} else if (wifiMode == W_STA) {
|
||||||
|
WiFi.begin(storage.getString("WIFI_STA_SSID", "").c_str(), storage.getString("WIFI_STA_PASS", "").c_str());
|
||||||
|
}
|
||||||
|
udp.begin(udpLocalPort);
|
||||||
}
|
}
|
||||||
|
|
||||||
void sendWiFi(const uint8_t *buf, int len) {
|
void sendWiFi(const uint8_t *buf, int len) {
|
||||||
if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return;
|
if (WiFi.softAPgetStationNum() == 0 && !WiFi.isConnected()) return;
|
||||||
udp.beginPacket(udp.remoteIP() ? udp.remoteIP() : WIFI_UDP_REMOTE_ADDR, WIFI_UDP_REMOTE_PORT);
|
udp.beginPacket(udpRemoteIP, udpRemotePort);
|
||||||
udp.write(buf, len);
|
udp.write(buf, len);
|
||||||
udp.endPacket();
|
udp.endPacket();
|
||||||
}
|
}
|
||||||
|
|
||||||
int receiveWiFi(uint8_t *buf, int len) {
|
int receiveWiFi(uint8_t *buf, int len) {
|
||||||
udp.parsePacket();
|
udp.parsePacket();
|
||||||
|
if (udp.remoteIP()) udpRemoteIP = udp.remoteIP();
|
||||||
return udp.read(buf, len);
|
return udp.read(buf, len);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
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");
|
||||||
|
}
|
||||||
|
|||||||
@@ -165,6 +165,7 @@ void delay(uint32_t ms) {
|
|||||||
|
|
||||||
bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { return true; }
|
bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { return true; }
|
||||||
bool ledcWrite(uint8_t pin, uint32_t duty) { return true; }
|
bool ledcWrite(uint8_t pin, uint32_t duty) { return true; }
|
||||||
|
uint32_t ledcChangeFrequency(uint8_t pin, uint32_t freq, uint8_t resolution) { return freq; }
|
||||||
|
|
||||||
unsigned long __micros;
|
unsigned long __micros;
|
||||||
unsigned long __resetTime = 0;
|
unsigned long __resetTime = 0;
|
||||||
|
|||||||
@@ -1,15 +1,99 @@
|
|||||||
# Gazebo Simulation
|
# Simulation
|
||||||
|
|
||||||
<img src="../docs/img/simulator.png" width=500 alt="Flix simulator">
|
The Flix drone simulator is based on Gazebo 11 and runs the firmware code in virtual physical environment.
|
||||||
|
|
||||||
## Building and running
|
Gazebo 11 works on **Ubuntu 20.04** and used to work on macOS. However, on the recent macOS versions it seems to be broken, so Ubuntu 20.04 is recommended.
|
||||||
|
|
||||||
See [building and running instructions](../docs/usage.md#simulation).
|
<img src="../docs/img/simulator1.png" width=600 alt="Flix simulator running on macOS">
|
||||||
|
|
||||||
|
## Installation
|
||||||
|
|
||||||
|
1. Clone the Flix repository using it:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
git clone https://github.com/okalachev/flix.git && cd flix
|
||||||
|
```
|
||||||
|
|
||||||
|
2. Install Arduino CLI:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
|
||||||
|
```
|
||||||
|
|
||||||
|
3. Install Gazebo 11:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
|
||||||
|
wget https://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
|
||||||
|
sudo apt-get update
|
||||||
|
sudo apt-get install -y gazebo11 libgazebo11-dev
|
||||||
|
```
|
||||||
|
|
||||||
|
Set up your Gazebo environment variables:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
echo "source /usr/share/gazebo/setup.sh" >> ~/.bashrc
|
||||||
|
source ~/.bashrc
|
||||||
|
```
|
||||||
|
|
||||||
|
4. Install SDL2 and other dependencies:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
sudo apt-get update && sudo apt-get install build-essential libsdl2-dev
|
||||||
|
```
|
||||||
|
|
||||||
|
5. Add your user to the `input` group to enable joystick support (you need to re-login after this command):
|
||||||
|
|
||||||
|
```bash
|
||||||
|
sudo usermod -a -G input $USER
|
||||||
|
```
|
||||||
|
|
||||||
|
6. Run the simulation:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
make simulator
|
||||||
|
```
|
||||||
|
|
||||||
|
## Usage
|
||||||
|
|
||||||
|
Just like the real drone, the simulator can be controlled using a USB remote control or a smartphone.
|
||||||
|
|
||||||
|
### Control with smartphone
|
||||||
|
|
||||||
|
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone. For **iOS**, use [QGroundControl build from TAJISOFT](https://apps.apple.com/ru/app/qgc-from-tajisoft/id1618653051).
|
||||||
|
2. Connect your smartphone to the same Wi-Fi network as the machine running the simulator.
|
||||||
|
3. If you're using a virtual machine, make sure that its network is set to the **bridged** mode with Wi-Fi adapter selected.
|
||||||
|
4. Run the simulation.
|
||||||
|
5. Open QGroundControl app. It should connect and begin showing the virtual drone's telemetry automatically.
|
||||||
|
6. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
|
||||||
|
7. Use the virtual joystick to fly the drone!
|
||||||
|
|
||||||
|
> [!TIP]
|
||||||
|
> Decrease `CTL_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
|
||||||
|
|
||||||
|
### Control with USB remote control
|
||||||
|
|
||||||
|
1. Connect your USB remote control to the machine running the simulator.
|
||||||
|
2. Run the simulation.
|
||||||
|
3. Calibrate the RC using `cr` command in the command line interface.
|
||||||
|
4. Use the USB remote control to fly the drone!
|
||||||
|
|
||||||
|
### Piloting
|
||||||
|
|
||||||
|
To start the flight, arm the drone moving the throttle stick to the bottom right position:
|
||||||
|
|
||||||
|
<img src="../docs/img/arming.svg" width="150">
|
||||||
|
|
||||||
|
To disarm, move the throttle stick to the bottom left position:
|
||||||
|
|
||||||
|
<img src="../docs/img/disarming.svg" width="150">
|
||||||
|
|
||||||
|
See other piloting and usage details in general [usage article](../docs/usage.md).
|
||||||
|
|
||||||
## Code structure
|
## Code structure
|
||||||
|
|
||||||
Flix simulator is based on [Gazebo Classic](https://classic.gazebosim.org) and consists of the following components:
|
Flix simulator consists of the following components:
|
||||||
|
|
||||||
* Physical model of the drone: [`models/flix/flix.sdf`](models/flix/flix.sdf).
|
* Physical model of the drone in Gazebo format: [`models/flix/flix.sdf`](models/flix/flix.sdf).
|
||||||
* Plugin for Gazebo: [`simulator.cpp`](simulator.cpp). The plugin is attached to the physical model. It receives stick positions from the controller, gets the data from the virtual sensors, and then passes this data to the Arduino code.
|
* Plugin for Gazebo: [`simulator.cpp`](simulator.cpp). The plugin is attached to the physical model. It receives stick positions from the controller, gets the data from the virtual sensors, and then passes this data to the Arduino code.
|
||||||
* Arduino imitation: [`Arduino.h`](Arduino.h). This file contains partial implementation of the Arduino API, that is working within Gazebo plugin environment.
|
* Arduino emulation: [`Arduino.h`](Arduino.h). This file contains partial implementation of the Arduino API, that is working within Gazebo plugin environment.
|
||||||
|
|||||||
@@ -9,19 +9,18 @@
|
|||||||
#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 controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
||||||
|
extern Vector rates;
|
||||||
|
extern Quaternion attitude;
|
||||||
|
extern bool landed;
|
||||||
|
extern float motors[4];
|
||||||
|
|
||||||
float t = NAN;
|
Vector gyro, acc, imuRotation;
|
||||||
float dt;
|
Vector accBias, gyroBias, accScale(1, 1, 1);
|
||||||
float motors[4];
|
LowPassFilter<Vector> gyroBiasFilter(0);
|
||||||
float controlRoll, controlPitch, controlYaw, controlThrottle = NAN;
|
|
||||||
float controlMode = NAN;
|
|
||||||
Vector acc;
|
|
||||||
Vector gyro;
|
|
||||||
Vector rates;
|
|
||||||
Quaternion attitude;
|
|
||||||
bool landed;
|
|
||||||
|
|
||||||
// declarations
|
// declarations
|
||||||
void step();
|
void step();
|
||||||
@@ -35,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, ...);
|
||||||
@@ -43,9 +43,10 @@ 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 dumpLog();
|
void printLogHeader();
|
||||||
|
void printLogData();
|
||||||
void processMavlink();
|
void processMavlink();
|
||||||
void sendMavlink();
|
void sendMavlink();
|
||||||
void sendMessage(const void *msg);
|
void sendMessage(const void *msg);
|
||||||
@@ -72,4 +73,5 @@ void calibrateGyro() { print("Skip gyro calibrating\n"); };
|
|||||||
void calibrateAccel() { print("Skip accel calibrating\n"); };
|
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() {};
|
||||||
Vector accBias, gyroBias, accScale(1, 1, 1);
|
void printWiFiInfo() {};
|
||||||
|
void configWiFi(bool, const char*, const char*) { print("Skip WiFi config\n"); };
|
||||||
|
|||||||
@@ -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
tools/log.py
@@ -3,21 +3,50 @@
|
|||||||
# Download flight log remotely and save to file
|
# Download flight log remotely and save to file
|
||||||
|
|
||||||
import os
|
import os
|
||||||
|
import time
|
||||||
import datetime
|
import datetime
|
||||||
|
import struct
|
||||||
|
from pymavlink.dialects.v20.common import MAVLink_log_data_message
|
||||||
from pyflix import Flix
|
from pyflix import Flix
|
||||||
|
|
||||||
DIR = os.path.dirname(os.path.realpath(__file__))
|
DIR = os.path.dirname(os.path.realpath(__file__))
|
||||||
|
|
||||||
flix = Flix()
|
flix = Flix()
|
||||||
|
|
||||||
print('Downloading log...')
|
print('Downloading log...')
|
||||||
lines = flix.cli('log').splitlines()
|
|
||||||
|
|
||||||
# sort by timestamp
|
header = flix.cli('log')
|
||||||
header = lines.pop(0)
|
print('Received header:\n- ' + '\n- '.join(header.split(',')))
|
||||||
lines.sort(key=lambda line: float(line.split(',')[0]))
|
|
||||||
|
|
||||||
|
records = []
|
||||||
|
|
||||||
|
def on_record(msg: MAVLink_log_data_message):
|
||||||
|
global stop
|
||||||
|
stop = time.time() + 1 # extend timeout
|
||||||
|
records.append([])
|
||||||
|
i = 0
|
||||||
|
data = bytes(msg.data)
|
||||||
|
while i + 4 <= msg.count:
|
||||||
|
records[-1].append(struct.unpack('<f', data[i:i+4])[0])
|
||||||
|
i += 4
|
||||||
|
|
||||||
|
stop = time.time() + 3
|
||||||
|
flix.on('mavlink.LOG_DATA', on_record)
|
||||||
|
flix.mavlink.log_request_data_send(flix.system_id, 0, 0, 0, 0xFFFFFFFF)
|
||||||
|
|
||||||
|
while time.time() < stop:
|
||||||
|
time.sleep(1)
|
||||||
|
|
||||||
|
flix.off(on_record)
|
||||||
|
|
||||||
|
records.sort(key=lambda record: record[0])
|
||||||
|
records = [record for record in records if record[0] != 0]
|
||||||
|
|
||||||
|
print(f'Received records: {len(records)}')
|
||||||
|
|
||||||
|
os.makedirs(f'{DIR}/log', exist_ok=True)
|
||||||
log = open(f'{DIR}/log/{datetime.datetime.now().isoformat()}.csv', 'wb')
|
log = open(f'{DIR}/log/{datetime.datetime.now().isoformat()}.csv', 'wb')
|
||||||
content = header.encode() + b'\n' + b'\n'.join(line.encode() for line in lines)
|
log.write(header.encode() + b'\n')
|
||||||
log.write(content)
|
for record in records:
|
||||||
|
line = ','.join(f'{value}' for value in record)
|
||||||
|
log.write(line.encode() + b'\n')
|
||||||
print(f'Written {os.path.relpath(log.name, os.curdir)}')
|
print(f'Written {os.path.relpath(log.name, os.curdir)}')
|
||||||
|
|||||||
@@ -1,8 +1,8 @@
|
|||||||
# Flix Python library
|
# Flix Python library
|
||||||
|
|
||||||
The Flix Python library allows you to remotely connect to a Flix quadcopter. It provides access to telemetry data, supports executing CLI commands, and controlling the drone's flight.
|
The Flix Python library allows you to remotely connect to a Flix quadcopter. It provides access to telemetry data, supports executing console commands, and controlling the drone's flight.
|
||||||
|
|
||||||
To use the library, connect to the drone's Wi-Fi. To use it with the simulator, ensure the script runs on the same local network as the simulator.
|
To use the library, connect to the drone's Wi-Fi. To use it with the simulator, ensure the script runs on the same network as the simulator.
|
||||||
|
|
||||||
## Installation
|
## Installation
|
||||||
|
|
||||||
@@ -30,7 +30,7 @@ flix = Flix() # create a Flix object and wait for connection
|
|||||||
|
|
||||||
### Telemetry
|
### Telemetry
|
||||||
|
|
||||||
Basic telemetry is available through object properties. The properties names generally match the corresponding variables in the firmware itself:
|
Basic telemetry is available through object properties. The property names generally match the corresponding variables in the firmware itself:
|
||||||
|
|
||||||
```python
|
```python
|
||||||
print(flix.connected) # True if connected to the drone
|
print(flix.connected) # True if connected to the drone
|
||||||
@@ -41,13 +41,16 @@ print(flix.attitude) # attitude quaternion [w, x, y, z]
|
|||||||
print(flix.attitude_euler) # attitude as Euler angles [roll, pitch, yaw]
|
print(flix.attitude_euler) # attitude as Euler angles [roll, pitch, yaw]
|
||||||
print(flix.rates) # angular rates [roll_rate, pitch_rate, yaw_rate]
|
print(flix.rates) # angular rates [roll_rate, pitch_rate, yaw_rate]
|
||||||
print(flix.channels) # raw RC channels (list)
|
print(flix.channels) # raw RC channels (list)
|
||||||
print(flix.motors) # motors outputs (list)
|
print(flix.motors) # motor outputs (list)
|
||||||
print(flix.acc) # accelerometer output (list)
|
print(flix.acc) # accelerometer output (list)
|
||||||
print(flix.gyro) # gyroscope output (list)
|
print(flix.gyro) # gyroscope output (list)
|
||||||
```
|
```
|
||||||
|
|
||||||
> [!NOTE]
|
The library uses the Front-Left-Up coordinate system — the same as the firmware:
|
||||||
> The library uses the Front-Left-Up coordinate system — the same as in the firmware. All angles are in radians.
|
|
||||||
|
<img src="../../docs/img/drone-axes-rotate.svg" width="300">
|
||||||
|
|
||||||
|
All angles are in radians.
|
||||||
|
|
||||||
### Events
|
### Events
|
||||||
|
|
||||||
@@ -89,27 +92,27 @@ 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 sends 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`|Motors outputs update|Motors 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|
|
||||||
|`value`|Named value update (see below)|Name, value|
|
|`value`|Named value update (see below)|Name, value|
|
||||||
|`value.<name>`|Specific named value update (see bellow)|Value|
|
|`value.<name>`|Specific named value update (see below)|Value|
|
||||||
|
|
||||||
> [!NOTE]
|
> [!NOTE]
|
||||||
> Update events trigger on every new data from the drone, and do not mean the value is changed.
|
> Update events trigger on every new piece of data from the drone, and do not mean the value has changed.
|
||||||
|
|
||||||
### Common methods
|
### Basic methods
|
||||||
|
|
||||||
Get and set firmware parameters using `get_param` and `set_param` methods:
|
Get and set firmware parameters using `get_param` and `set_param` methods:
|
||||||
|
|
||||||
@@ -118,7 +121,7 @@ pitch_p = flix.get_param('PITCH_P') # get parameter value
|
|||||||
flix.set_param('PITCH_P', 5) # set parameter value
|
flix.set_param('PITCH_P', 5) # set parameter value
|
||||||
```
|
```
|
||||||
|
|
||||||
Execute CLI commands using `cli` method. This method returns command response:
|
Execute console commands using `cli` method. This method returns the command response:
|
||||||
|
|
||||||
```python
|
```python
|
||||||
imu = flix.cli('imu') # get detailed IMU data
|
imu = flix.cli('imu') # get detailed IMU data
|
||||||
@@ -136,7 +139,7 @@ flix.set_armed(True) # arm the drone
|
|||||||
flix.set_armed(False) # disarm the drone
|
flix.set_armed(False) # disarm the drone
|
||||||
```
|
```
|
||||||
|
|
||||||
You can imitate pilot's controls using `set_controls` method:
|
You can pass pilot's controls using `set_controls` method:
|
||||||
|
|
||||||
```python
|
```python
|
||||||
flix.set_controls(roll=0, pitch=0, yaw=0, throttle=0.6)
|
flix.set_controls(roll=0, pitch=0, yaw=0, throttle=0.6)
|
||||||
@@ -166,10 +169,10 @@ Setting angular rates target:
|
|||||||
flix.set_rates([0.1, 0.2, 0.3], 0.6) # set target roll rate, pitch rate, yaw rate and thrust
|
flix.set_rates([0.1, 0.2, 0.3], 0.6) # set target roll rate, pitch rate, yaw rate and thrust
|
||||||
```
|
```
|
||||||
|
|
||||||
You also can control raw motors outputs directly:
|
You also can control raw motor outputs directly:
|
||||||
|
|
||||||
```python
|
```python
|
||||||
flix.set_motors([0.5, 0.5, 0.5, 0.5]) # set motors outputs in range [0, 1]
|
flix.set_motors([0.5, 0.5, 0.5, 0.5]) # set motor outputs in range [0, 1]
|
||||||
```
|
```
|
||||||
|
|
||||||
In *AUTO* mode, the drone will arm automatically if the thrust is greater than zero, and disarm if thrust is zero. Therefore, to disarm the drone, set thrust to zero:
|
In *AUTO* mode, the drone will arm automatically if the thrust is greater than zero, and disarm if thrust is zero. Therefore, to disarm the drone, set thrust to zero:
|
||||||
@@ -183,7 +186,7 @@ The following methods are in development and are not functional yet:
|
|||||||
* `set_position` — set target position.
|
* `set_position` — set target position.
|
||||||
* `set_velocity` — set target velocity.
|
* `set_velocity` — set target velocity.
|
||||||
|
|
||||||
To exit from *AUTO* mode move control sticks and the drone will switch to *STAB* mode.
|
To exit *AUTO* mode move control sticks and the drone will switch to *STAB* mode.
|
||||||
|
|
||||||
## Usage alongside QGroundControl
|
## Usage alongside QGroundControl
|
||||||
|
|
||||||
@@ -274,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.
|
|
||||||
|
|||||||
@@ -17,7 +17,7 @@ from pymavlink.dialects.v20 import common as mavlink
|
|||||||
logger = logging.getLogger('flix')
|
logger = logging.getLogger('flix')
|
||||||
if not logger.hasHandlers():
|
if not logger.hasHandlers():
|
||||||
handler = logging.StreamHandler()
|
handler = logging.StreamHandler()
|
||||||
handler.setFormatter(logging.Formatter('%(name)s - %(levelname)s - %(message)s'))
|
handler.setFormatter(logging.Formatter('%(name)s: %(message)s'))
|
||||||
logger.addHandler(handler)
|
logger.addHandler(handler)
|
||||||
logger.setLevel(logging.INFO)
|
logger.setLevel(logging.INFO)
|
||||||
|
|
||||||
@@ -40,7 +40,7 @@ class Flix:
|
|||||||
|
|
||||||
_connection_timeout = 3
|
_connection_timeout = 3
|
||||||
_print_buffer: str = ''
|
_print_buffer: str = ''
|
||||||
_modes = ['MANUAL', 'ACRO', 'STAB', 'AUTO']
|
_modes = ['RAW', 'ACRO', 'STAB', 'AUTO']
|
||||||
|
|
||||||
def __init__(self, system_id: int=1, wait_connection: bool=True):
|
def __init__(self, system_id: int=1, wait_connection: bool=True):
|
||||||
if not (0 <= system_id < 256):
|
if not (0 <= system_id < 256):
|
||||||
@@ -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()
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
[project]
|
[project]
|
||||||
name = "pyflix"
|
name = "pyflix"
|
||||||
version = "0.9"
|
version = "0.11"
|
||||||
description = "Python API for Flix drone"
|
description = "Python API for Flix drone"
|
||||||
authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }]
|
authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }]
|
||||||
license = "MIT"
|
license = "MIT"
|
||||||
|
|||||||