43 Commits

Author SHA1 Message Date
Oleg Kalachev
f4e58a652a Add project logo 2026-01-08 17:58:59 +03:00
Oleg Kalachev
6c46328da1 Minor doc fixes 2026-01-04 15:01:53 +03:00
Oleg Kalachev
c8e5e08b03 Move all global variable declarations to the appropriate subsystems
As it makes the subsystems code easier to understand.
Declare the most used variables in main sketch file as forward declarations.
Make all control input zero by default (except controlMode).
Minor changes.
2026-01-03 13:28:18 +03:00
Oleg Kalachev
a5e3dfcf69 Some updates to the docs 2026-01-03 12:18:47 +03:00
Oleg Kalachev
d6e8be0c05 Add parameters for easier IMU orientation definition 2025-12-26 21:14:15 +03:00
Oleg Kalachev
68d16855df Add motors rotation diagram to usage article 2025-12-25 07:22:09 +03:00
Oleg Kalachev
0547ea548b Add parameters for acc weight and rates lpf alpha 2025-12-24 05:43:55 +03:00
Oleg Kalachev
c02dba6812 Rename gyroCalibrationFilter to gyroBiasFilter
Which seems a better name
2025-12-24 05:36:43 +03:00
Oleg Kalachev
f1dc4a0400 Updates to user builds article 2025-12-17 02:21:51 +03:00
Oleg Kalachev
158827ac55 Add new user builds, add school 548 course overview
+ minor doc fixes.
2025-12-13 21:09:33 +03:00
Oleg Kalachev
36ca30c3e4 Minor docs fix 2025-11-27 18:34:32 +03:00
Oleg Kalachev
48711b55e1 Add tip about CNT_TILT_MAX parameter to the simulator article 2025-11-26 17:34:08 +03:00
Oleg Kalachev
4d583185a9 Rename manual mode to raw mode
Make it callable from the console.
Increase the coefficient.
Corresponding change in pyflix.
pyflix@0.11.
2025-11-25 04:44:16 +03:00
Oleg Kalachev
d757ffa853 Move yaw dead zone handling from mavlink to control subsystem
So yaw dead zone works the same for rc and mavlink.
2025-11-22 05:11:46 +03:00
Oleg Kalachev
5352386486 Minor updates to pyflix library, pyflix@0.10
Fixes to documentation.
Improve logger format.
2025-11-22 05:07:46 +03:00
Oleg Kalachev
9b5872740f Add wifi cli command
To show wi-fi info.
2025-11-22 04:46:54 +03:00
Oleg Kalachev
31dbdaf241 Group control parameters
Also add IMU group to accelerometer calibration parameters.
2025-11-19 01:50:46 +03:00
Oleg Kalachev
f4b56262b1 Remove unneeded SERIAL_BAUDRATE define 2025-11-14 20:23:15 +03:00
Oleg Kalachev
49039f752d Refactor Wi-Fi log download
Use MAVLink LOG_REQUEST_DATA and LOG_DATA for download log instead of console.
Make Wi-Fi download default way of downloading the log.
Make `log` command only print the header and `log dump` dump the log.
2025-11-14 20:21:05 +03:00
Oleg Kalachev
348721acc9 Updates in documentation
Fixes, updates, new illustrations.
2025-11-10 20:16:14 +03:00
Oleg Kalachev
774144c430 Many updates to documentation
Updates to main readme.
Add much more info to usage article.
Move simulator building to simulation's readme.
Improve assembly article.
Many fixes.
Updates in diagrams.
2025-11-06 13:55:52 +03:00
Oleg Kalachev
0e6651ab82 Add Rate class for running the code at fixed rate 2025-11-06 13:41:33 +03:00
Oleg Kalachev
1a017ccb97 Keep only one floating point version of map function
Two variants are redundant
2025-11-02 00:02:28 +03:00
Oleg Kalachev
7170b20d1d Simplify command for command handling 2025-10-21 19:41:10 +03:00
Oleg Kalachev
dc9aed113b Minor code fixes 2025-10-21 19:41:05 +03:00
Oleg Kalachev
08b6123eb7 Fixes to troubleshooting 2025-10-21 19:40:54 +03:00
Oleg Kalachev
1a8b63ee04 Send only mavlink heartbeats until connected 2025-10-21 19:39:17 +03:00
Oleg Kalachev
8c49a40516 Skip attitude/rate control if thrustTarget is ineffective
To prevent i term windup.
2025-10-20 23:01:17 +03:00
Oleg Kalachev
ca595edce5 Refactor PID control to simplify the code and modifications
Each PID uses its internal dt, so may be various contexts with different rate.
PID has max dt, so no need to reset explicitly.
2025-10-20 22:54:18 +03:00
KiraFlux
d06eb2a1aa Quaternion::fromBetweenVectors: pass u and v as const references (#21) 2025-10-19 20:46:46 +03:00
Oleg Kalachev
e50a9d5fea Revert t variable type to float instead of double
For the sake of simplicity and consistency.
2025-10-19 20:46:38 +03:00
Oleg Kalachev
ebac78dc0f Minor change 2025-10-19 20:46:26 +03:00
Oleg Kalachev
186cf88d84 Add generic Delay filter 2025-10-19 20:46:11 +03:00
Oleg Kalachev
253aae2220 Lowercase imu and rc variables
To make it more obvious these are variables, not classes.
2025-10-19 20:45:56 +03:00
Oleg Kalachev
6f0964fac4 Rename failsafe.ino to safety.ino
To aggregate all the safety related functionality.
2025-10-19 20:44:54 +03:00
Oleg Kalachev
1d034f268d Add ESP32-S3 build to Actions 2025-10-19 20:44:46 +03:00
Oleg Kalachev
1ca7d32862 Update VSCode settings
Disable error squiggles as they often work incorrectly.
Decrease number of include libraries to index.
2025-10-14 11:43:55 +03:00
Oleg Kalachev
ab941e34fa Fix Gazebo installation
Installation script is deprecated, install using package on Ubuntu 20.04
2025-10-13 18:56:14 +03:00
Oleg Kalachev
7bee3d1751 Improve rc failsafe logic
Don't trigger failsafe if there's no RC at all
Use AUTO mode for descending, instead of STAB
Increase RC loss timeout and descend time
2025-10-12 21:27:08 +03:00
Oleg Kalachev
06ec5f3160 Disarm the drone on simulator plugin reset
In order to reset yaw target.
2025-10-07 15:45:48 +03:00
Oleg Kalachev
c4533e3ac8 Reset yaw target when drone disarmed
Prevent unexpected behavior when the drone tries to restore its old yaw on takeoff.
2025-10-07 15:43:28 +03:00
Oleg Kalachev
e673b50f52 Include FlixPeriph header instead of MPU9250
This simplifies choosing IMU model
2025-10-07 08:43:12 +03:00
Oleg Kalachev
5151bb9133 Ensure showing correct raw data in imu command
Some IMUs will reset acc and gyro buffer on whoAmI() call
2025-10-07 08:43:06 +03:00
75 changed files with 1116 additions and 464 deletions

View File

@@ -23,7 +23,9 @@ jobs:
with: with:
name: firmware-binary name: firmware-binary
path: flix/build path: flix/build
- name: Build firmware without Wi-Fi - name: Build firmware for ESP32-S3
run: make BOARD=esp32:esp32:esp32s3
- name: Build firmware with WiFi disabled
run: sed -i 's/^#define WIFI_ENABLED 1$/#define WIFI_ENABLED 0/' flix/flix.ino && make 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
@@ -53,15 +55,25 @@ jobs:
run: python3 tools/check_c_cpp_properties.py run: python3 tools/check_c_cpp_properties.py
build_simulator: build_simulator:
runs-on: ubuntu-22.04 runs-on: ubuntu-latest
container:
image: ubuntu:20.04
steps: steps:
- name: Install dependencies
run: |
apt-get update
DEBIAN_FRONTEND=noninteractive apt-get install -y curl wget build-essential cmake g++ pkg-config gnupg2 lsb-release sudo
- name: Install Arduino CLI - name: Install Arduino CLI
uses: arduino/setup-arduino-cli@v1.1.1 uses: arduino/setup-arduino-cli@v1.1.1
- uses: actions/checkout@v4 - uses: actions/checkout@v4
- name: Install Gazebo - name: Install Gazebo
run: curl -sSL http://get.gazebosim.org | sh run: |
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
- name: Install SDL2 - name: Install SDL2
run: sudo apt-get install libsdl2-dev run: sudo apt-get install -y libsdl2-dev
- name: Build simulator - name: Build simulator
run: make build_simulator run: make build_simulator
- uses: actions/upload-artifact@v4 - uses: actions/upload-artifact@v4

View File

@@ -7,6 +7,7 @@
"MD024": false, "MD024": false,
"MD033": false, "MD033": false,
"MD034": false, "MD034": false,
"MD059": false,
"MD044": { "MD044": {
"html_elements": false, "html_elements": false,
"code_blocks": false, "code_blocks": false,
@@ -64,5 +65,6 @@
"PX4" "PX4"
] ]
}, },
"MD045": false "MD045": false,
"MD060": false
} }

View File

@@ -5,13 +5,15 @@
"includePath": [ "includePath": [
"${workspaceFolder}/flix", "${workspaceFolder}/flix",
"${workspaceFolder}/gazebo", "${workspaceFolder}/gazebo",
"${workspaceFolder}/tools/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32", "~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**", "~/.arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32", "~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**", "~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include", "~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
"~/Arduino/libraries/**", "~/Arduino/libraries/**",
"/usr/include/**" "/usr/include/gazebo-11/",
"/usr/include/ignition/math6/"
], ],
"forcedInclude": [ "forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h", "${workspaceFolder}/.vscode/intellisense.h",
@@ -51,14 +53,14 @@
"name": "Mac", "name": "Mac",
"includePath": [ "includePath": [
"${workspaceFolder}/flix", "${workspaceFolder}/flix",
// "${workspaceFolder}/gazebo",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32", "~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**", "~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32", "~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/include/**", "~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/include/**",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/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/**" "/opt/homebrew/include/gazebo-11/",
"/opt/homebrew/include/ignition/math6/"
], ],
"forcedInclude": [ "forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h", "${workspaceFolder}/.vscode/intellisense.h",
@@ -100,6 +102,7 @@
"includePath": [ "includePath": [
"${workspaceFolder}/flix", "${workspaceFolder}/flix",
"${workspaceFolder}/gazebo", "${workspaceFolder}/gazebo",
"${workspaceFolder}/tools/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32", "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**", "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32", "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",

View File

@@ -1,5 +1,6 @@
{ {
"C_Cpp.intelliSenseEngineFallback": "enabled", "C_Cpp.intelliSenseEngineFallback": "enabled",
"C_Cpp.errorSquiggles": "disabled",
"files.associations": { "files.associations": {
"*.sdf": "xml", "*.sdf": "xml",
"*.ino": "cpp", "*.ino": "cpp",

View File

@@ -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)

View File

@@ -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>
@@ -52,25 +55,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|GY91, MPU-9265 (or other MPU9250/MPU6500 board)<br>ICM20948V2 (ICM20948)³<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|GY91, MPU-9265 (or other MPU9250/MPU6500 board)<br>ICM20948V2 (ICM20948)³<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 +85,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` in `imu.ino` file if using ICM-20948 board.*<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 +105,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 +113,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 +121,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 +138,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 +154,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. Theres 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!

View File

@@ -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>

View File

@@ -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)* — целевые угловые скорости, *рад/с*.

View File

@@ -1 +0,0 @@
usage.md

2
docs/build.md Normal file
View File

@@ -0,0 +1,2 @@
<!-- markdownlint-disable MD041 -->
Build instructions are moved to [usage article](usage.md).

View File

@@ -6,20 +6,20 @@ 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` *(double)* — 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*.
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*. * `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
* `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

Binary file not shown.

After

Width:  |  Height:  |  Size: 70 KiB

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 140 KiB

After

Width:  |  Height:  |  Size: 15 KiB

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 101 KiB

After

Width:  |  Height:  |  Size: 13 KiB

View 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
View 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
View File

@@ -0,0 +1,38 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 718.86 362.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="443.12" y1="283.88" x2="641.43" y2="84.58"/>
<line class="a" x1="444.12" y1="85.58" x2="642.42" y2="284.87"/>
<circle class="b" cx="542.77" cy="184.23" r="41.15"/>
<circle class="c" cx="443.69" cy="85.08" r="77.29"/>
<circle class="c" cx="641.55" cy="84.87" r="77.29"/>
<circle class="c" cx="640.56" cy="284.16" r="77.29"/>
<circle class="c" cx="443.25" cy="284.16" r="77.29"/>
</g>
<path class="d" d="M0,153.93q0-17.85,22.36-17.85h4.81V92.57Q27.17.48,123.23,0h1q36.87,0,47.31,7.48L173,9.41l1,2.41V42q0,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.74H93.64V336.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.93H49.08q-10.47,0-15.7-4.71t-5.73-8.44a77.31,77.31,0,0,1-.48-9.53V172.27H21.4Q0,172.27,0,153.93Z"/>
<path class="d" d="M193.21,340.2V29q0-23.16,20.86-23.4h22.81q22.8,0,22.8,22.44V338.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.17H217q-11.4,0-17.58-4.47T193.21,340.2Z"/>
<path class="d" d="M276.9,54.08V29.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.22V55.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.48H299.7q-10.43,0-16.61-4.7T276.9,54.08Zm1.94,284.71V159.28q0-22.2,21.83-22.2h20.38q10.92,0,16.62,4t6.67,8.45a60.47,60.47,0,0,1,1,12.18V341.2q0,22.2-21.83,22.2H300.67q-10.43,0-15.64-4.95t-5.7-8.81A90.93,90.93,0,0,1,278.84,338.79Z"/>
</g>
</svg>

After

Width:  |  Height:  |  Size: 2.2 KiB

BIN
docs/img/imu-axes.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 23 KiB

BIN
docs/img/imu-rot-1.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 18 KiB

BIN
docs/img/imu-rot-2.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 18 KiB

BIN
docs/img/imu-rot-3.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

BIN
docs/img/imu-rot-4.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

BIN
docs/img/imu-rot-5.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 10 KiB

BIN
docs/img/imu-rot-6.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 9.6 KiB

BIN
docs/img/imu-rot-7.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 10 KiB

BIN
docs/img/imu-rot-8.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 10 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 38 KiB

After

Width:  |  Height:  |  Size: 46 KiB

BIN
docs/img/motor-tape.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 61 KiB

89
docs/img/motors.svg Normal file
View 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

Binary file not shown.

After

Width:  |  Height:  |  Size: 16 KiB

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 18 KiB

After

Width:  |  Height:  |  Size: 18 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 68 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 35 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 32 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 108 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 93 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 65 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 31 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 42 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 43 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 76 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 44 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 32 KiB

View File

@@ -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

View File

@@ -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*.
@@ -15,7 +15,7 @@ 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 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 board, change `MPU9250` to `ICM20948` everywhere 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 CLI is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the CLI using QGroundControl (*Vehicle Setup* ⇒ *Analyze Tools**MAVLink Console*).
* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**. * **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
* **If QGroundControl doesn't connect**, you might need to disable the firewall and/or VPN on your computer. * **If QGroundControl doesn't connect**, you might need to disable the firewall and/or VPN on your computer.
@@ -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).
* **Calibrate the RC** if you use it. Type `cr` command in Serial Monitor and follow the instructions. * **Check the propeller directions are correct**. Make sure your propeller types (A or B) are installed as on the picture:
* **Check the RC data** if you use it. Use `rc` command, `Control` should show correct values between -1 and 1, and between 0 and 1 for the throttle. <img src="img/user/peter_ukhov-2/1.jpg" width="200">
* **Check the remote control**. Using `rc` command, check the control values reflect your sticks movement. All the controls should change between -1 and 1, and throttle between 0 and 1.
* If using SBUS receiver, **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.

View File

@@ -1,127 +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 22.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
curl -sSL http://get.gazebosim.org | sh
```
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.2.0. See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library): 4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
* `FlixPeriph`, the latest version. * `FlixPeriph`, the latest version.
* `MAVLink`, version 2.0.16. * `MAVLink`, version 2.0.16.
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
@@ -146,19 +57,115 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 22.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.
### 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 ### Check everything works
1. Check the IMU is working: perform `imu` command and check its output:
* The `status` field should be `OK`.
* The `rate` field should be about 1000 (Hz).
* The `accel` and `gyro` fields should change as you move the drone.
* The `landed` field should be `1` when the drone is still on the ground and `0` when you lift it up.
2. Check the attitude estimation: connect to the drone using QGroundControl, rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. Attitude indicator in QGroundControl is shown below:
<img src="img/qgc-attitude.png" height="200">
3. Perform motor tests in the console. Use the following commands **— remove the propellers before running the tests!**
* `mfr` — should rotate front right motor (counter-clockwise).
* `mfl` — should rotate front left motor (clockwise).
* `mrl` — should rotate rear left motor (counter-clockwise).
* `mrr` — should rotate rear right motor (clockwise).
Rotation 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.
@@ -168,17 +175,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.
@@ -190,9 +197,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:
@@ -211,6 +215,9 @@ 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 or using the command line.
@@ -226,9 +233,9 @@ 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
@@ -236,14 +243,12 @@ In this mode, the pilot inputs are ignored (except the mode switch, if configure
If the pilot moves the control sticks, the drone will switch back to *STAB* mode. If the pilot moves the control sticks, the drone will switch back to *STAB* mode.
## Adjusting parameters ## Flight log
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*. After the flight, you can download the flight log for analysis wirelessly. Use the following for that:
<img src="img/parameters.png" width="400"> ```bash
make log
```
## CLI access See more details about log analysis in the [log analysis](log.md) article.
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*.
<img src="img/cli.png" width="400">

View File

@@ -4,12 +4,67 @@ This page contains user-built drones based on the Flix project. Publish your pro
--- ---
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.

View File

@@ -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|||

View File

@@ -8,11 +8,10 @@
#include "util.h" #include "util.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 loopRate, dt; extern float t, dt, loopRate;
extern double t;
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;
@@ -36,10 +35,11 @@ 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"
"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"
@@ -60,7 +60,7 @@ void print(const char* format, ...) {
} }
void pause(float duration) { void pause(float duration) {
double start = t; float start = t;
while (t - start < duration) { while (t - start < duration) {
step(); step();
handleInput(); handleInput();
@@ -75,9 +75,10 @@ void doCommand(String str, bool echo = false) {
// parse command // parse command
String command, arg0, arg1; String command, arg0, arg1;
splitString(str, command, arg0, arg1); splitString(str, command, arg0, arg1);
if (command.isEmpty()) return;
// echo command // echo command
if (echo && !command.isEmpty()) { if (echo) {
print("> %s\n", str.c_str()); print("> %s\n", str.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,19 @@ 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") {
#if WIFI_ENABLED
printWiFiInfo();
#endif
} 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") {
@@ -171,8 +180,6 @@ void doCommand(String str, bool echo = false) {
attitude = Quaternion(); attitude = Quaternion();
} else if (command == "reboot") { } else if (command == "reboot") {
ESP.restart(); ESP.restart();
} else if (command == "") {
// do nothing
} else { } else {
print("Invalid command: %s\n", command.c_str()); print("Invalid command: %s\n", command.c_str());
} }

View File

@@ -9,7 +9,6 @@
#include "lpf.h" #include "lpf.h"
#include "util.h" #include "util.h"
#define ARMED_THRUST 0.1 // thrust to indicate armed state
#define PITCHRATE_P 0.05 #define PITCHRATE_P 0.05
#define PITCHRATE_I 0.2 #define PITCHRATE_I 0.2
#define PITCHRATE_D 0.001 #define PITCHRATE_D 0.001
@@ -35,7 +34,7 @@
#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;
@@ -66,7 +65,6 @@ void control() {
} }
void interpretControls() { void interpretControls() {
// NOTE: put ACRO or MANUAL modes there if you want to use them
if (controlMode < 0.25) mode = STAB; if (controlMode < 0.25) mode = STAB;
if (controlMode < 0.75) mode = STAB; if (controlMode < 0.75) mode = STAB;
if (controlMode > 0.75) mode = STAB; if (controlMode > 0.75) mode = STAB;
@@ -76,11 +74,13 @@ void interpretControls() {
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) {
float yawTarget = attitudeTarget.getYaw(); float yawTarget = attitudeTarget.getYaw();
if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or pilot commands yaw rate if (!armed || invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target
attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget)); attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget));
ratesExtra = Vector(0, 0, -controlYaw * maxRate.z); // positive yaw stick means clockwise rotation in FLU ratesExtra = Vector(0, 0, -controlYaw * maxRate.z); // positive yaw stick means clockwise rotation in FLU
} }
@@ -92,20 +92,15 @@ 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;
} }
} }
void controlAttitude() { void controlAttitude() {
if (!armed || attitudeTarget.invalid()) { // skip attitude control if (!armed || attitudeTarget.invalid() || thrustTarget < 0.1) return; // skip attitude control
rollPID.reset();
pitchPID.reset();
yawPID.reset();
return;
}
const Vector up(0, 0, 1); const Vector up(0, 0, 1);
Vector upActual = Quaternion::rotateVector(up, attitude); Vector upActual = Quaternion::rotateVector(up, attitude);
@@ -113,28 +108,23 @@ void controlAttitude() {
Vector error = Vector::rotationVectorBetween(upTarget, upActual); Vector error = Vector::rotationVectorBetween(upTarget, upActual);
ratesTarget.x = rollPID.update(error.x, dt) + ratesExtra.x; ratesTarget.x = rollPID.update(error.x) + ratesExtra.x;
ratesTarget.y = pitchPID.update(error.y, dt) + ratesExtra.y; ratesTarget.y = pitchPID.update(error.y) + ratesExtra.y;
float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw()); float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw());
ratesTarget.z = yawPID.update(yawError, dt) + ratesExtra.z; ratesTarget.z = yawPID.update(yawError) + ratesExtra.z;
} }
void controlRates() { void controlRates() {
if (!armed || ratesTarget.invalid()) { // skip rates control if (!armed || ratesTarget.invalid() || thrustTarget < 0.1) return; // skip rates control
rollRatePID.reset();
pitchRatePID.reset();
yawRatePID.reset();
return;
}
Vector error = ratesTarget - rates; Vector error = ratesTarget - rates;
// Calculate desired torque, where 0 - no torque, 1 - maximum possible torque // Calculate desired torque, where 0 - no torque, 1 - maximum possible torque
torqueTarget.x = rollRatePID.update(error.x, dt); torqueTarget.x = rollRatePID.update(error.x);
torqueTarget.y = pitchRatePID.update(error.y, dt); torqueTarget.y = pitchRatePID.update(error.y);
torqueTarget.z = yawRatePID.update(error.z, dt); torqueTarget.z = yawRatePID.update(error.z);
} }
void controlTorque() { void controlTorque() {
@@ -145,12 +135,11 @@ void controlTorque() {
return; return;
} }
if (thrustTarget < 0.05) { if (thrustTarget < 0.1) {
// minimal thrust to indicate armed state motors[0] = 0.1; // idle thrust
motors[0] = ARMED_THRUST; motors[1] = 0.1;
motors[1] = ARMED_THRUST; motors[2] = 0.1;
motors[2] = ARMED_THRUST; motors[3] = 0.1;
motors[3] = ARMED_THRUST;
return; return;
} }
@@ -167,7 +156,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";

View File

@@ -8,8 +8,12 @@
#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));

View File

@@ -7,22 +7,18 @@
#include "quaternion.h" #include "quaternion.h"
#include "util.h" #include "util.h"
#define SERIAL_BAUDRATE 115200
#define WIFI_ENABLED 1 #define WIFI_ENABLED 1
double t = NAN; // current step time, s extern float t, dt;
float dt; // time delta from previous step, s extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1] extern Vector gyro, acc;
float controlMode = NAN; extern Vector rates;
Vector gyro; // gyroscope data extern Quaternion attitude;
Vector acc; // accelerometer data, m/s/s extern bool landed;
Vector rates; // filtered angular rates, rad/s extern float motors[4];
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();

View File

@@ -4,62 +4,60 @@
// Work with the IMU sensor // Work with the IMU sensor
#include <SPI.h> #include <SPI.h>
#include <MPU9250.h> #include <FlixPeriph.h>
#include "vector.h"
#include "lpf.h" #include "lpf.h"
#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;
void setupIMU() { void setupIMU() {
print("Setup IMU\n"); print("Setup IMU\n");
IMU.begin(); imu.begin();
configureIMU(); configureIMU();
} }
void configureIMU() { void configureIMU() {
IMU.setAccelRange(IMU.ACCEL_RANGE_4G); imu.setAccelRange(imu.ACCEL_RANGE_4G);
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS); imu.setGyroRange(imu.GYRO_RANGE_2000DPS);
IMU.setDLPF(IMU.DLPF_MAX); imu.setDLPF(imu.DLPF_MAX);
IMU.setRate(IMU.RATE_1KHZ_APPROX); imu.setRate(imu.RATE_1KHZ_APPROX);
IMU.setupInterrupt(); imu.setupInterrupt();
} }
void readIMU() { void readIMU() {
IMU.waitForData(); imu.waitForData();
IMU.getGyro(gyro.x, gyro.y, gyro.z); imu.getGyro(gyro.x, gyro.y, gyro.z);
IMU.getAccel(acc.x, acc.y, acc.z); imu.getAccel(acc.x, acc.y, acc.z);
calibrateGyroOnce(); calibrateGyroOnce();
// 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 float landedTime = 0; static Delay landedDelay(2);
landedTime = landed ? landedTime + dt : 0; if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary
if (landedTime < 2) return; // calibrate only if definitely stationary
static LowPassFilter<Vector> gyroCalibrationFilter(0.001); static LowPassFilter<Vector> gyroBiasFilter(0.001);
gyroBias = gyroCalibrationFilter.update(gyro); gyroBias = gyroBiasFilter.update(gyro);
} }
void calibrateAccel() { void calibrateAccel() {
print("Calibrating accelerometer\n"); print("Calibrating accelerometer\n");
IMU.setAccelRange(IMU.ACCEL_RANGE_2G); // the most sensitive mode imu.setAccelRange(imu.ACCEL_RANGE_2G); // the most sensitive mode
print("1/6 Place level [8 sec]\n"); print("1/6 Place level [8 sec]\n");
pause(8); pause(8);
@@ -93,9 +91,9 @@ void calibrateAccelOnce() {
// Compute the average of the accelerometer readings // Compute the average of the accelerometer readings
acc = Vector(0, 0, 0); acc = Vector(0, 0, 0);
for (int i = 0; i < samples; i++) { for (int i = 0; i < samples; i++) {
IMU.waitForData(); imu.waitForData();
Vector sample; Vector sample;
IMU.getAccel(sample.x, sample.y, sample.z); imu.getAccel(sample.x, sample.y, sample.z);
acc = acc + sample; acc = acc + sample;
} }
acc = acc / samples; acc = acc / samples;
@@ -119,15 +117,16 @@ void printIMUCalibration() {
} }
void printIMUInfo() { void printIMUInfo() {
IMU.status() ? print("status: ERROR %d\n", IMU.status()) : print("status: OK\n"); imu.status() ? print("status: ERROR %d\n", imu.status()) : print("status: OK\n");
print("model: %s\n", IMU.getModel()); print("model: %s\n", imu.getModel());
print("who am I: 0x%02X\n", IMU.whoAmI()); print("who am I: 0x%02X\n", imu.whoAmI());
print("rate: %.0f\n", loopRate); print("rate: %.0f\n", loopRate);
print("gyro: %f %f %f\n", rates.x, rates.y, rates.z); print("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
print("acc: %f %f %f\n", acc.x, acc.y, acc.z); print("acc: %f %f %f\n", acc.x, acc.y, acc.z);
imu.waitForData();
Vector rawGyro, rawAcc; Vector rawGyro, rawAcc;
IMU.getGyro(rawGyro.x, rawGyro.y, rawGyro.z); imu.getGyro(rawGyro.x, rawGyro.y, rawGyro.z);
IMU.getAccel(rawAcc.x, rawAcc.y, rawAcc.z); imu.getAccel(rawAcc.x, rawAcc.y, rawAcc.z);
print("raw gyro: %f %f %f\n", rawGyro.x, rawGyro.y, rawGyro.z); print("raw gyro: %f %f %f\n", rawGyro.x, rawGyro.y, rawGyro.z);
print("raw acc: %f %f %f\n", rawAcc.x, rawAcc.y, rawAcc.z); print("raw acc: %f %f %f\n", rawAcc.x, rawAcc.y, rawAcc.z);
} }

View File

@@ -4,13 +4,12 @@
// 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
float tFloat;
Vector attitudeEuler; Vector attitudeEuler;
Vector attitudeTargetEuler; Vector attitudeTargetEuler;
@@ -20,7 +19,7 @@ struct LogEntry {
}; };
LogEntry logEntries[] = { LogEntry logEntries[] = {
{"t", &tFloat}, {"t", &t},
{"rates.x", &rates.x}, {"rates.x", &rates.x},
{"rates.y", &rates.y}, {"rates.y", &rates.y},
{"rates.z", &rates.z}, {"rates.z", &rates.z},
@@ -40,7 +39,6 @@ const int logColumns = sizeof(logEntries) / sizeof(logEntries[0]);
float logBuffer[LOG_SIZE][logColumns]; float logBuffer[LOG_SIZE][logColumns];
void prepareLogData() { void prepareLogData() {
tFloat = t;
attitudeEuler = attitude.toEuler(); attitudeEuler = attitude.toEuler();
attitudeTargetEuler = attitudeTarget.toEuler(); attitudeTargetEuler = attitudeTarget.toEuler();
} }
@@ -48,9 +46,8 @@ void prepareLogData() {
void logData() { void logData() {
if (!armed) return; if (!armed) return;
static int logPointer = 0; static int logPointer = 0;
static double logTime = 0; static Rate period(LOG_RATE);
if (t - logTime < LOG_PERIOD) return; if (!period) return;
logTime = t;
prepareLogData(); prepareLogData();
@@ -64,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++) {

View File

@@ -6,17 +6,17 @@
#if WIFI_ENABLED #if WIFI_ENABLED
#include <MAVLink.h> #include <MAVLink.h>
#include "util.h"
#define SYSTEM_ID 1 #define SYSTEM_ID 1
#define PERIOD_SLOW 1.0 #define MAVLINK_RATE_SLOW 1
#define PERIOD_FAST 0.1 #define MAVLINK_RATE_FAST 10
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
extern float controlTime;
bool mavlinkConnected = false;
String mavlinkPrintBuffer; String mavlinkPrintBuffer;
extern double controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
void processMavlink() { void processMavlink() {
sendMavlink(); sendMavlink();
receiveMavlink(); receiveMavlink();
@@ -25,15 +25,12 @@ void processMavlink() {
void sendMavlink() { void sendMavlink() {
sendMavlinkPrint(); sendMavlinkPrint();
static double lastSlow = 0;
static double 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) { static Rate slow(MAVLINK_RATE_SLOW), fast(MAVLINK_RATE_FAST);
lastSlow = t;
if (slow) {
mavlink_msg_heartbeat_pack(SYSTEM_ID, 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) |
@@ -41,14 +38,14 @@ void sendMavlink() {
mode, MAV_STATE_STANDBY); mode, MAV_STATE_STANDBY);
sendMessage(&msg); sendMessage(&msg);
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(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
MAV_VTOL_STATE_UNDEFINED, landed ? MAV_LANDED_STATE_ON_GROUND : MAV_LANDED_STATE_IN_AIR); MAV_VTOL_STATE_UNDEFINED, landed ? MAV_LANDED_STATE_ON_GROUND : MAV_LANDED_STATE_IN_AIR);
sendMessage(&msg); sendMessage(&msg);
} }
if (t - lastFast >= PERIOD_FAST) { if (fast && mavlinkConnected) {
lastFast = t;
const float zeroQuat[] = {0, 0, 0, 0}; const float zeroQuat[] = {0, 0, 0, 0};
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd
@@ -80,6 +77,7 @@ void sendMessage(const void *msg) {
void receiveMavlink() { void receiveMavlink() {
uint8_t buf[MAVLINK_MAX_PACKET_LEN]; uint8_t buf[MAVLINK_MAX_PACKET_LEN];
int len = receiveWiFi(buf, MAVLINK_MAX_PACKET_LEN); int len = receiveWiFi(buf, MAVLINK_MAX_PACKET_LEN);
if (len) mavlinkConnected = true;
// New packet, parse it // New packet, parse it
mavlink_message_t msg; mavlink_message_t msg;
@@ -105,8 +103,6 @@ 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) {
@@ -210,6 +206,20 @@ 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 != SYSTEM_ID) return;
// Send all log records
for (int i = 0; i < sizeof(logBuffer) / sizeof(logBuffer[0]); i++) {
mavlink_message_t msg;
mavlink_msg_log_data_pack(SYSTEM_ID, 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;

View File

@@ -17,7 +17,8 @@
#define PWM_MIN 0 #define PWM_MIN 0
#define PWM_MAX 1000000 / PWM_FREQUENCY #define PWM_MAX 1000000 / PWM_FREQUENCY
// Motors array indexes: float motors[4]; // normalized motor thrusts in range [0..1]
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;
@@ -38,9 +39,9 @@ void setupMotors() {
int getDutyCycle(float value) { int getDutyCycle(float value) {
value = constrain(value, 0, 1); value = constrain(value, 0, 1);
float pwm = mapff(value, 0, 1, PWM_MIN, PWM_MAX); float pwm = mapf(value, 0, 1, PWM_MIN, PWM_MAX);
if (value == 0) pwm = PWM_STOP; if (value == 0) pwm = PWM_STOP;
float duty = mapff(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1); float duty = mapf(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
return round(duty); return round(duty);
} }

View File

@@ -4,51 +4,57 @@
// Parameters storage in flash memory // Parameters storage in flash memory
#include <Preferences.h> #include <Preferences.h>
#include "util.h"
extern float channelZero[16]; extern float channelZero[16];
extern float channelMax[16]; extern float channelMax[16];
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel; extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern float mavlinkControlScale;
Preferences storage; Preferences storage;
struct Parameter { struct Parameter {
const char *name; // max length is 16 const char *name; // max length is 15 (Preferences key limit)
float *variable; float *variable;
float value; // cache float value; // cache
}; };
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},
// 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},
// estimate
{"EST_ACC_WEIGHT", &accWeight},
{"EST_RATES_LPF_A", &ratesFilter.alpha},
// rc // rc
{"RC_ZERO_0", &channelZero[0]}, {"RC_ZERO_0", &channelZero[0]},
{"RC_ZERO_1", &channelZero[1]}, {"RC_ZERO_1", &channelZero[1]},
@@ -119,10 +125,9 @@ bool setParameter(const char *name, const float value) {
} }
void syncParameters() { void syncParameters() {
static double 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 &parameter : parameters) { for (auto &parameter : parameters) {
if (parameter.value == *parameter.variable) continue; if (parameter.value == *parameter.variable) continue;

View File

@@ -9,40 +9,44 @@
class PID { class PID {
public: public:
float p = 0; float p, i, d;
float i = 0; float windup;
float d = 0; float dtMax;
float windup = 0;
float derivative = 0; float derivative = 0;
float integral = 0; float integral = 0;
LowPassFilter<float> lpf; // low pass filter for derivative term LowPassFilter<float> lpf; // low pass filter for derivative term
PID(float p, float i, float d, float windup = 0, float dAlpha = 1) : p(p), i(i), d(d), windup(windup), lpf(dAlpha) {}; PID(float p, float i, float d, float windup = 0, float dAlpha = 1, float dtMax = 0.1) :
p(p), i(i), d(d), windup(windup), lpf(dAlpha), dtMax(dtMax) {}
float update(float error, float dt) { float update(float error) {
integral += error * dt; float dt = t - prevTime;
if (isfinite(prevError) && dt > 0) { if (dt > 0 && dt < dtMax) {
// calculate derivative if both dt and prevError are valid integral += error * dt;
derivative = (error - prevError) / dt; derivative = lpf.update((error - prevError) / dt); // compute derivative and apply low-pass filter
} else {
// apply low pass filter to derivative integral = 0;
derivative = lpf.update(derivative); derivative = 0;
} }
prevError = error; prevError = error;
prevTime = t;
return p * error + constrain(i * integral, -windup, windup) + d * derivative; // PID return p * error + constrain(i * integral, -windup, windup) + d * derivative; // PID
} }
void reset() { void reset() {
prevError = NAN; prevError = NAN;
prevTime = NAN;
integral = 0; integral = 0;
derivative = 0; derivative = 0;
lpf.reset();
} }
private: private:
float prevError = NAN; float prevError = NAN;
float prevTime = NAN;
}; };

View File

@@ -45,7 +45,7 @@ public:
cx * cy * sz - sx * sy * cz); cx * cy * sz - sx * sy * cz);
} }
static Quaternion fromBetweenVectors(Vector u, Vector v) { static Quaternion fromBetweenVectors(const Vector& u, const Vector& v) {
float dot = u.x * v.x + u.y * v.y + u.z * v.z; float dot = u.x * v.x + u.y * v.y + u.z * v.z;
float w1 = u.y * v.z - u.z * v.y; float w1 = u.y * v.z - u.z * v.y;
float w2 = u.z * v.x - u.x * v.z; float w2 = u.z * v.x - u.x * v.z;

View File

@@ -6,24 +6,27 @@
#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
double controlTime; // time of the last controls update
float channelZero[16]; // calibration zero values float channelZero[16]; // calibration zero values
float channelMax[16]; // calibration max values float channelMax[16]; // calibration max values
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN; //
float controlTime; // time of the last controls update (0 when no RC)
// Channels mapping (using float to store in parameters): // Channels mapping (using float to store in parameters):
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN; float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
void setupRC() { void setupRC() {
print("Setup RC\n"); print("Setup RC\n");
RC.begin(); rc.begin();
} }
bool readRC() { bool readRC() {
if (RC.read()) { if (rc.read()) {
SBUSData data = RC.data(); SBUSData data = rc.data();
for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data
normalizeRC(); normalizeRC();
controlTime = t; controlTime = t;
@@ -38,11 +41,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 ? controls[(int)rollChannel] : 0;
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN; controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : 0;
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN; controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : 0;
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN; controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : 0;
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN; controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN; // mode switch should not have affect if not set
} }
void calibrateRC() { void calibrateRC() {

View File

@@ -3,10 +3,10 @@
// Fail-safe functions // Fail-safe functions
#define RC_LOSS_TIMEOUT 0.5 #define RC_LOSS_TIMEOUT 1
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero #define DESCEND_TIME 10
extern double controlTime; extern float controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw; extern float controlRoll, controlPitch, controlThrottle, controlYaw;
void failsafe() { void failsafe() {
@@ -16,7 +16,7 @@ void failsafe() {
// RC loss failsafe // RC loss failsafe
void rcLossFailsafe() { void rcLossFailsafe() {
if (mode == AUTO) return; if (controlTime == 0) return; // no RC at all
if (!armed) return; if (!armed) return;
if (t - controlTime > RC_LOSS_TIMEOUT) { if (t - controlTime > RC_LOSS_TIMEOUT) {
descend(); descend();
@@ -25,14 +25,12 @@ void rcLossFailsafe() {
// Smooth descend on RC lost // Smooth descend on RC lost
void descend() { void descend() {
mode = STAB; mode = AUTO;
controlRoll = 0; attitudeTarget = Quaternion();
controlPitch = 0; thrustTarget -= dt / DESCEND_TIME;
controlYaw = 0; if (thrustTarget < 0) {
controlThrottle -= dt / DESCEND_TIME; thrustTarget = 0;
if (controlThrottle < 0) {
armed = false; armed = false;
controlThrottle = 0;
} }
} }

View File

@@ -3,10 +3,12 @@
// 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() {
double now = micros() / 1000000.0; float now = micros() / 1000000.0;
dt = now - t; dt = now - t;
t = now; t = now;
@@ -18,7 +20,7 @@ void step() {
} }
void computeLoopRate() { void computeLoopRate() {
static double windowStart = 0; static float windowStart = 0;
static uint32_t rate = 0; static uint32_t rate = 0;
rate++; rate++;
if (t - windowStart >= 1) { // 1 second window if (t - windowStart >= 1) { // 1 second window

View File

@@ -10,12 +10,9 @@
#include <soc/rtc_cntl_reg.h> #include <soc/rtc_cntl_reg.h>
const float ONE_G = 9.80665; const float ONE_G = 9.80665;
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;
} }
@@ -52,3 +49,37 @@ void splitString(String& str, String& token0, String& token1, String& token2) {
token1 = strtok(NULL, " "); // String(NULL) creates empty string token1 = strtok(NULL, " "); // String(NULL) creates empty string
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
class Delay {
public:
float delay;
float start = NAN;
Delay(float delay) : delay(delay) {}
bool update(bool on) {
if (!on) {
start = NAN;
return false;
} else if (isnan(start)) {
start = t;
}
return t - start >= delay;
}
};

View File

@@ -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);
} }

View File

@@ -35,4 +35,15 @@ int receiveWiFi(uint8_t *buf, int len) {
return udp.read(buf, len); return udp.read(buf, len);
} }
void printWiFiInfo() {
print("MAC: %s\n", WiFi.softAPmacAddress().c_str());
print("SSID: %s\n", WiFi.softAPSSID().c_str());
print("Password: %s\n", WIFI_PASSWORD);
print("Clients: %d\n", WiFi.softAPgetStationNum());
print("Status: %d\n", WiFi.status());
print("IP: %s\n", WiFi.softAPIP().toString().c_str());
print("Remote IP: %s\n", udp.remoteIP().toString().c_str());
print("MAVLink connected: %d\n", mavlinkConnected);
}
#endif #endif

View File

@@ -1,7 +1,7 @@
cmake_minimum_required(VERSION 3.5 FATAL_ERROR) cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
project(flix_gazebo) project(flix_gazebo)
# === gazebo plugin # Gazebo plugin
find_package(gazebo REQUIRED) find_package(gazebo REQUIRED)
find_package(SDL2 REQUIRED) find_package(SDL2 REQUIRED)
include_directories(${GAZEBO_INCLUDE_DIRS}) include_directories(${GAZEBO_INCLUDE_DIRS})

View File

@@ -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.

View File

@@ -12,16 +12,15 @@
#define WIFI_ENABLED 1 #define WIFI_ENABLED 1
double t = NAN; extern float t, dt;
float dt; extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
float motors[4]; extern Vector rates;
float controlRoll, controlPitch, controlYaw, controlThrottle = NAN; extern Quaternion attitude;
float controlMode = NAN; extern bool landed;
Vector acc; extern float motors[4];
Vector gyro;
Vector rates; Vector gyro, acc, imuRotation;
Quaternion attitude; Vector accBias, gyroBias, accScale(1, 1, 1);
bool landed;
// declarations // declarations
void step(); void step();
@@ -45,7 +44,8 @@ void normalizeRC();
void calibrateRC(); void calibrateRC();
void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str); void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str);
void printRCCalibration(); void 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 +72,4 @@ 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() {};

View File

@@ -21,7 +21,7 @@
#include "cli.ino" #include "cli.ino"
#include "control.ino" #include "control.ino"
#include "estimate.ino" #include "estimate.ino"
#include "failsafe.ino" #include "safety.ino"
#include "log.ino" #include "log.ino"
#include "lpf.h" #include "lpf.h"
#include "mavlink.ino" #include "mavlink.ino"
@@ -59,6 +59,7 @@ public:
void OnReset() { void OnReset() {
attitude = Quaternion(); // reset estimated attitude attitude = Quaternion(); // reset estimated attitude
armed = false;
__resetTime += __micros; __resetTime += __micros;
gzmsg << "Flix plugin reset" << endl; gzmsg << "Flix plugin reset" << endl;
} }

View File

@@ -49,6 +49,8 @@ for configuration in props['configurations']:
print('Check configuration', configuration['name']) print('Check configuration', configuration['name'])
for include_path in configuration.get('includePath', []): for include_path in configuration.get('includePath', []):
if include_path.startswith('/opt/') or include_path.startswith('/usr/'): # don't check non-Arduino libs
continue
check_path(include_path) check_path(include_path)
for forced_include in configuration.get('forcedInclude', []): for forced_include in configuration.get('forcedInclude', []):

View File

@@ -3,21 +3,49 @@
# 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)}')
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)}')

View File

@@ -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
@@ -92,24 +95,24 @@ Full list of events:
|`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

View File

@@ -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):

View File

@@ -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"