28 Commits

Author SHA1 Message Date
Oleg Kalachev
3104410bb9 Group control parameters
Also add IMU group to accelerometer calibration parameters.
2025-11-19 01:30:02 +03:00
Oleg Kalachev
1551d096fc Merge changes from master 2025-11-14 20:27:02 +03:00
Oleg Kalachev
80f23ab016 Update log analysis documentation 2025-11-14 20:17:34 +03:00
Oleg Kalachev
e6fb264499 Remove unneeded SERIAL_BAUDRATE define 2025-11-14 13:46:02 +03:00
Oleg Kalachev
4d0871b00b Updates in documentation
Fixes, updates, new illustrations.
2025-11-10 20:13:39 +03:00
Oleg Kalachev
f1b993d719 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:46:25 +03:00
Oleg Kalachev
2e7330d2f5 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-02 00:24:38 +03:00
Oleg Kalachev
e22df3ab01 Simplify rate limiter code 2025-11-02 00:03:37 +03:00
Oleg Kalachev
8484854576 Keep only one floating point version of map function
Two variants are redundant
2025-11-01 23:55:55 +03:00
Oleg Kalachev
b9d5624f30 Add some excludes to sloc 2025-10-29 03:35:31 +03:00
Oleg Kalachev
205270b8ec Add Rate class for running the code at fixed rate 2025-10-29 03:25:05 +03:00
Oleg Kalachev
f1bedb2b10 Count sloc in Actions 2025-10-29 02:20:50 +03:00
Oleg Kalachev
46d1749a8c Minor code fixes 2025-10-21 19:33:57 +03:00
Oleg Kalachev
66fb7a13c3 Simplify command for command handling 2025-10-21 19:33:57 +03:00
Oleg Kalachev
cfef3b9c36 Fixes to troubleshooting 2025-10-21 19:33:57 +03:00
KiraFlux
1338a9ea79 Quaternion::fromBetweenVectors: pass u and v as const references (#21) 2025-10-19 10:17:38 +03:00
Oleg Kalachev
b60757ec1d Minor code style change 2025-10-18 12:36:20 +03:00
Oleg Kalachev
491e054534 Revert t variable type to float instead of double
For the sake of simplicity and consistency.
2025-10-18 12:28:01 +03:00
Oleg Kalachev
3eaf24f89d Minor change 2025-10-17 19:22:48 +03:00
Oleg Kalachev
dc09459613 Add generic Delay filter 2025-10-17 19:19:27 +03:00
Oleg Kalachev
59c9ea8cb3 Lowercase imu and rc variables
To make it more obvious these are variables, not classes.
2025-10-17 19:02:46 +03:00
Oleg Kalachev
5bdd46c6ad Increase thrust to ARMED_THRUST if it's less 2025-10-17 18:54:01 +03:00
Oleg Kalachev
5b37c87166 Refactor PID controllers
Use t variable instead of passing dt argument.
Reset PID automatically on large dts.
2025-10-17 18:53:15 +03:00
Oleg Kalachev
48ba55aa7e Rename failsafe.ino to safety.ino
To aggregate all the safety related functionality.
2025-10-17 01:09:23 +03:00
Oleg Kalachev
2708c1eafd Add ESP32-S3 build to Actions 2025-10-14 16:56:48 +03:00
Oleg Kalachev
b2c9dfe6ef Fix Gazebo installation
Installation script is deprecated, install using package on Ubuntu 20.04
2025-10-14 11:44:27 +03:00
Oleg Kalachev
0579118dd5 Update VSCode settings
Disable error squiggles as they often work incorrectly.
Decrease number of include libraries to index.
2025-10-14 11:31:47 +03:00
Oleg Kalachev
05818349d8 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:20:46 +03:00
45 changed files with 889 additions and 378 deletions

View File

@@ -23,7 +23,9 @@ jobs:
with:
name: firmware-binary
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
- name: Check c_cpp_properties.json
run: tools/check_c_cpp_properties.py
@@ -53,15 +55,25 @@ jobs:
run: python3 tools/check_c_cpp_properties.py
build_simulator:
runs-on: ubuntu-22.04
runs-on: ubuntu-latest
container:
image: ubuntu:20.04
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
uses: arduino/setup-arduino-cli@v1.1.1
- uses: actions/checkout@v4
- 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
run: sudo apt-get install libsdl2-dev
run: sudo apt-get install -y libsdl2-dev
- name: Build simulator
run: make build_simulator
- uses: actions/upload-artifact@v4

View File

@@ -46,3 +46,14 @@ jobs:
echo -e "t,x,y,z\n0,1,2,3\n1,4,5,6" > log.csv
./csv_to_mcap.py log.csv
test $(stat -c %s log.mcap) -eq 883
sloc:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- name: Install cloc
run: sudo apt-get install -y cloc
- name: Firmware source lines count
run: cloc --by-file-by-lang flix
- name: Overall source lines count
run: cloc --by-file-by-lang --exclude-ext=svg,dae,css,hbs,md,json,yaml,yml,toml .

View File

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

View File

@@ -32,7 +32,7 @@ simulator: build_simulator
gazebo --verbose ${CURDIR}/gazebo/flix.world
log:
PORT=$(PORT) tools/grab_log.py
tools/log.py
plot:
plotjuggler -d $(shell ls -t tools/log/*.csv | head -n1)

View File

@@ -1,6 +1,6 @@
# Flix
**Flix** (*flight + X*) — making an open source ESP32-based quadcopter from scratch.
**Flix** (*flight + X*) — open source ESP32-based quadcopter made from scratch.
<table>
<tr>
@@ -52,25 +52,29 @@ The simulator is implemented using Gazebo and runs the original Arduino code:
<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).
* [Firmware architectural overview](docs/firmware.md).
* [Troubleshooting](docs/troubleshooting.md).
* [Log analysis](docs/log.md).
## Components
|Type|Part|Image|Quantity|
|-|-|:-:|:-:|
|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|
|<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|
|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|
|Propeller|Hubsan 55 mm|<img src="docs/img/prop.jpg" width=100>|4|
|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|
|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.<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|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|
|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|
@@ -78,19 +82,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|
|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|
|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 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|
|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|
|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: [`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: [`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|
|*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>||
|Tape, double-sided tape||||
*² barometer is not used for now.*<br>
*³ — change `MPU9250` to `ICM20948` or `MPU6050` in `imu.ino` file for using the appropriate boards.*<br>
*³⁻¹ — MPU-6050 supports I²C interface only (not recommended). To use it change IMU declaration to `MPU6050 IMU(Wire)`.*<br>
*⁴ — 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.*
*¹ barometer is not used for now.*<br>
*² — 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:
@@ -100,7 +102,7 @@ Tools required for assembly:
* Screwdrivers.
* 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
@@ -108,7 +110,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">
*(Dashed is optional).*
*(Dashed elements are optional).*
Motor connection scheme:
@@ -116,8 +118,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.
See [assembly guide](docs/assembly.md) for instructions on assembling the drone.
### Notes
* Power ESP32 Mini with Li-Po battery using VCC (+) and GND (-) pins.
@@ -135,14 +135,15 @@ See [assembly guide](docs/assembly.md) for instructions on assembling the drone.
* Solder pull-down resistors to the MOSFETs.
* Connect the motors to the ESP32 Mini using MOSFETs, by following scheme:
|Motor|Position|Direction|Wires|GPIO|
|-|-|-|-|-|
|Motor 0|Rear left|Counter-clockwise|Black & White|GPIO12 (*TDI*)|
|Motor 1|Rear right|Clockwise|Blue & Red|GPIO13 (*TCK*)|
|Motor 2|Front right|Counter-clockwise|Black & White|GPIO14 (*TMS*)|
|Motor 3|Front left|Clockwise|Blue & Red|GPIO15 (*TD0*)|
|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*)|
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:
@@ -150,32 +151,18 @@ See [assembly guide](docs/assembly.md) for instructions on assembling the drone.
|-|-|
|GND|GND|
|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):
<img src="docs/img/gy91-lfd.svg" width=400 alt="GY-91 axes">
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).
* Telegram channel on developing the drone and the flight controller (in Russian): https://t.me/opensourcequadcopter.
* 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/.
## 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!

View File

@@ -27,3 +27,27 @@ Soldered components ([schematics variant](https://miro.com/app/board/uXjVN-dTjoo
<br>Assembled drone:
<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>*.
* `rates` *(Vector)* — отфильтрованные угловые скорости, *рад/с*.
* `attitude` *(Quaternion)* — оценка ориентации (положения) дрона.
* `controlRoll`, `controlPitch`, ... *(float[])* — команды управления от пилота, в диапазоне [-1, 1].
* `motors` *(float[])* — выходные сигналы на моторы, в диапазоне [0, 1].
* `controlRoll`, `controlPitch`, `controlYaw`, `controlThrottle`, `controlMode` *(float)* — команды управления от пилота, в диапазоне [-1, 1].
* `motors` *(float[4])* — выходные сигналы на моторы, в диапазоне [0, 1].
## Исходные файлы

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">
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*.
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*.
* `rates` *(Vector)* — filtered angular rates, *rad/s*.
* `attitude` *(Quaternion)* — estimated attitude (orientation) of drone.
* `controlRoll`, `controlPitch`, ... *(float[])* — pilot control inputs, range [-1, 1].
* `motors` *(float[])* — motor outputs, range [0, 1].
* `controlRoll`, `controlPitch`, `controlYaw`, `controlThrottle`, `controlMode` *(float)* — pilot control inputs, range [-1, 1].
* `motors` *(float[4])* — motor outputs, range [0, 1].
## 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.
* [`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.
* [`motors.ino`](../flix/motors.ino) — PWM motor output control.
* [`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:
@@ -45,12 +46,22 @@ Pilot inputs are interpreted in `interpretControls()`, and then converted to the
* `torqueTarget` *(Vector)* — target torque, range [-1, 1].
* `thrustTarget` *(float)* — collective 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">
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.
## Building the firmware
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

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

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.
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.
## Log download
To download the log, connect the ESP32 using USB right after the flight and run the following command:
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:
```bash
make log

View File

@@ -32,6 +32,8 @@ Do the following:
* `mfl` — should rotate front left motor (clockwise).
* `mrl` — should rotate rear left motor (counter-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 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.
* **Check the propeller directions are correct**. Make sure your propeller types (A or B) are installed as on the picture:
<img src="img/user/peter_ukhov-2/1.jpg" width="200">
* **Check the remote control**. Using `rc` command, check the control values reflect your sticks movement. All the controls should change between -1 and 1, and throttle between 0 and 1.
* If using SBUS receiver, **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.

View File

@@ -1,127 +1,38 @@
# 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
git clone https://github.com/okalachev/flix.git
cd flix
git clone https://github.com/okalachev/flix.git && 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.
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
You can build and upload the firmware using either **Arduino IDE** (easier for beginners) or a **command line**.
### 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).
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.
4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
* `FlixPeriph`, the latest version.
* `MAVLink`, version 2.0.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).
6. Open the downloaded Arduino sketch `flix/flix.ino` in Arduino IDE.
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.
8. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
5. Open the `flix/flix.ino` sketch from downloaded firmware sources in Arduino IDE.
6. Connect your ESP32 board to the computer and choose correct board type in Arduino IDE (*WEMOS D1 MINI ESP32* for ESP32 Mini) and the port.
7. [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)
1. [Install Arduino CLI](https://arduino.github.io/arduino-cli/installation/).
On Linux, use:
On Linux, install it like this:
```bash
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
@@ -146,19 +57,93 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you h
make upload monitor
```
See other available Make commands in the [Makefile](../Makefile).
See other available Make commands in [Makefile](../Makefile).
> [!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
```
### Setup the IMU orientation
The IMU orientation is defined in `rotateIMU` function in the `imu.ino` file. Change it so it converts the IMU axes to the drone's axes correctly. **Drone axes are X forward, Y left, Z up**:
<img src="img/drone-axes.svg" width="200">
See various [IMU boards axes orientations table](https://github.com/okalachev/flixperiph/?tab=readme-ov-file#imu-axes-orientation) to help you set up the correct orientation.
### Connect using QGroundControl
QGroundControl is a ground control station software that can be used to monitor and control the drone.
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.
### Calibrate 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.
#### 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).
> [!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 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.
@@ -168,17 +153,17 @@ Before flight you need to calibrate the accelerometer:
6. Use the virtual joystick to fly the drone!
> [!TIP]
> Decrease `TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
> Decrease `CNT_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
#### Control with remote control
### Control with 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).
2. Type `cr` command there and follow the instructions.
1. Access the console using QGroundControl (recommended) or Serial Monitor.
2. Type `cr` command and follow the instructions.
3. Use the remote control to fly the drone!
#### Control with USB remote control (Wi-Fi)
### Control with USB remote control
If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it.
@@ -190,9 +175,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.
7. Use the USB remote control to fly the drone!
> [!NOTE]
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.
## 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:
@@ -211,6 +193,9 @@ When finished flying, **disarm** the drone, moving the left stick to the bottom
<img src="img/disarming.svg" width="150">
> [!NOTE]
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.
### Flight modes
Flight mode is changed using mode switch on the remote control or using the command line.
@@ -238,12 +223,16 @@ If the pilot moves the control sticks, the drone will switch back to *STAB* mode
## Adjusting parameters
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl app. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup**Parameters*.
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*.
<img src="img/parameters.png" width="400">
## CLI access
## Flight log
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*.
After the flight, you can download the flight log for analysis wirelessly. Use the following for that:
<img src="img/cli.png" width="400">
```bash
make log
```
See more details about log analysis in the [log analysis](log.md) article.

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|
|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|
|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|
|~~SBUS inverter~~*||<img src="img/inv.jpg" width=100>|~~1~~|
|Battery|3.7 Li-Po 850 MaH 60C|||

View File

@@ -9,8 +9,7 @@
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern const int ACRO, STAB, AUTO;
extern float loopRate, dt;
extern double t;
extern float t, dt, loopRate;
extern uint16_t channels[16];
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
extern int mode;
@@ -39,7 +38,7 @@ const char* motd =
"stab/acro/auto - set mode\n"
"rc - show RC data\n"
"mot - show motor output\n"
"log - dump in-RAM log\n"
"log [dump] - print log header [and data]\n"
"cr - calibrate RC\n"
"ca - calibrate accel\n"
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
@@ -60,7 +59,7 @@ void print(const char* format, ...) {
}
void pause(float duration) {
double start = t;
float start = t;
while (t - start < duration) {
step();
handleInput();
@@ -75,9 +74,10 @@ void doCommand(String str, bool echo = false) {
// parse command
String command, arg0, arg1;
splitString(str, command, arg0, arg1);
if (command.isEmpty()) return;
// echo command
if (echo && !command.isEmpty()) {
if (echo) {
print("> %s\n", str.c_str());
}
@@ -135,7 +135,8 @@ void doCommand(String str, bool echo = false) {
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]);
} else if (command == "log") {
dumpLog();
printLogHeader();
if (arg0 == "dump") printLogData();
} else if (command == "cr") {
calibrateRC();
} else if (command == "ca") {
@@ -171,8 +172,6 @@ void doCommand(String str, bool echo = false) {
attitude = Quaternion();
} else if (command == "reboot") {
ESP.restart();
} else if (command == "") {
// do nothing
} else {
print("Invalid command: %s\n", command.c_str());
}

View File

@@ -9,7 +9,6 @@
#include "lpf.h"
#include "util.h"
#define ARMED_THRUST 0.1 // thrust to indicate armed state
#define PITCHRATE_P 0.05
#define PITCHRATE_I 0.2
#define PITCHRATE_D 0.001
@@ -100,12 +99,7 @@ void interpretControls() {
}
void controlAttitude() {
if (!armed || attitudeTarget.invalid()) { // skip attitude control
rollPID.reset();
pitchPID.reset();
yawPID.reset();
return;
}
if (!armed || attitudeTarget.invalid() || thrustTarget < 0.1) return; // skip attitude control
const Vector up(0, 0, 1);
Vector upActual = Quaternion::rotateVector(up, attitude);
@@ -113,28 +107,23 @@ void controlAttitude() {
Vector error = Vector::rotationVectorBetween(upTarget, upActual);
ratesTarget.x = rollPID.update(error.x, dt) + ratesExtra.x;
ratesTarget.y = pitchPID.update(error.y, dt) + ratesExtra.y;
ratesTarget.x = rollPID.update(error.x) + ratesExtra.x;
ratesTarget.y = pitchPID.update(error.y) + ratesExtra.y;
float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw());
ratesTarget.z = yawPID.update(yawError, dt) + ratesExtra.z;
ratesTarget.z = yawPID.update(yawError) + ratesExtra.z;
}
void controlRates() {
if (!armed || ratesTarget.invalid()) { // skip rates control
rollRatePID.reset();
pitchRatePID.reset();
yawRatePID.reset();
return;
}
if (!armed || ratesTarget.invalid() || thrustTarget < 0.1) return; // skip rates control
Vector error = ratesTarget - rates;
// Calculate desired torque, where 0 - no torque, 1 - maximum possible torque
torqueTarget.x = rollRatePID.update(error.x, dt);
torqueTarget.y = pitchRatePID.update(error.y, dt);
torqueTarget.z = yawRatePID.update(error.z, dt);
torqueTarget.x = rollRatePID.update(error.x);
torqueTarget.y = pitchRatePID.update(error.y);
torqueTarget.z = yawRatePID.update(error.z);
}
void controlTorque() {
@@ -145,12 +134,11 @@ void controlTorque() {
return;
}
if (thrustTarget < 0.05) {
// minimal thrust to indicate armed state
motors[0] = ARMED_THRUST;
motors[1] = ARMED_THRUST;
motors[2] = ARMED_THRUST;
motors[3] = ARMED_THRUST;
if (thrustTarget < 0.1) {
motors[0] = 0.1; // idle thrust
motors[1] = 0.1;
motors[2] = 0.1;
motors[3] = 0.1;
return;
}

View File

@@ -7,10 +7,9 @@
#include "quaternion.h"
#include "util.h"
#define SERIAL_BAUDRATE 115200
#define WIFI_ENABLED 1
double t = NAN; // current step time, s
float t = NAN; // current step time, s
float dt; // time delta from previous step, s
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN;
@@ -22,7 +21,7 @@ bool landed; // are we landed and stationary
float motors[4]; // normalized motors thrust in range [0..1]
void setup() {
Serial.begin(SERIAL_BAUDRATE);
Serial.begin(115200);
print("Initializing flix\n");
disableBrownOut();
setupParameters();

View File

@@ -5,10 +5,11 @@
#include <SPI.h>
#include <FlixPeriph.h>
#include "vector.h"
#include "lpf.h"
#include "util.h"
MPU9250 IMU(SPI);
MPU9250 imu(SPI);
Vector accBias;
Vector accScale(1, 1, 1);
@@ -16,22 +17,22 @@ Vector gyroBias;
void setupIMU() {
print("Setup IMU\n");
IMU.begin();
imu.begin();
configureIMU();
}
void configureIMU() {
IMU.setAccelRange(IMU.ACCEL_RANGE_4G);
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
IMU.setDLPF(IMU.DLPF_MAX);
IMU.setRate(IMU.RATE_1KHZ_APPROX);
IMU.setupInterrupt();
imu.setAccelRange(imu.ACCEL_RANGE_4G);
imu.setGyroRange(imu.GYRO_RANGE_2000DPS);
imu.setDLPF(imu.DLPF_MAX);
imu.setRate(imu.RATE_1KHZ_APPROX);
imu.setupInterrupt();
}
void readIMU() {
IMU.waitForData();
IMU.getGyro(gyro.x, gyro.y, gyro.z);
IMU.getAccel(acc.x, acc.y, acc.z);
imu.waitForData();
imu.getGyro(gyro.x, gyro.y, gyro.z);
imu.getAccel(acc.x, acc.y, acc.z);
calibrateGyroOnce();
// apply scale and bias
acc = (acc - accBias) / accScale;
@@ -49,9 +50,8 @@ void rotateIMU(Vector& data) {
}
void calibrateGyroOnce() {
static float landedTime = 0;
landedTime = landed ? landedTime + dt : 0;
if (landedTime < 2) return; // calibrate only if definitely stationary
static Delay landedDelay(2);
if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary
static LowPassFilter<Vector> gyroCalibrationFilter(0.001);
gyroBias = gyroCalibrationFilter.update(gyro);
@@ -59,7 +59,7 @@ void calibrateGyroOnce() {
void calibrateAccel() {
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");
pause(8);
@@ -93,9 +93,9 @@ void calibrateAccelOnce() {
// Compute the average of the accelerometer readings
acc = Vector(0, 0, 0);
for (int i = 0; i < samples; i++) {
IMU.waitForData();
imu.waitForData();
Vector sample;
IMU.getAccel(sample.x, sample.y, sample.z);
imu.getAccel(sample.x, sample.y, sample.z);
acc = acc + sample;
}
acc = acc / samples;
@@ -119,16 +119,16 @@ void printIMUCalibration() {
}
void printIMUInfo() {
IMU.status() ? print("status: ERROR %d\n", IMU.status()) : print("status: OK\n");
print("model: %s\n", IMU.getModel());
print("who am I: 0x%02X\n", IMU.whoAmI());
imu.status() ? print("status: ERROR %d\n", imu.status()) : print("status: OK\n");
print("model: %s\n", imu.getModel());
print("who am I: 0x%02X\n", imu.whoAmI());
print("rate: %.0f\n", loopRate);
print("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
print("acc: %f %f %f\n", acc.x, acc.y, acc.z);
IMU.waitForData();
imu.waitForData();
Vector rawGyro, rawAcc;
IMU.getGyro(rawGyro.x, rawGyro.y, rawGyro.z);
IMU.getAccel(rawAcc.x, rawAcc.y, rawAcc.z);
imu.getGyro(rawGyro.x, rawGyro.y, rawGyro.z);
imu.getAccel(rawAcc.x, rawAcc.y, rawAcc.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);
}

View File

@@ -4,13 +4,12 @@
// In-RAM logging
#include "vector.h"
#include "util.h"
#define LOG_RATE 100
#define LOG_DURATION 10
#define LOG_PERIOD 1.0 / LOG_RATE
#define LOG_SIZE LOG_DURATION * LOG_RATE
float tFloat;
Vector attitudeEuler;
Vector attitudeTargetEuler;
@@ -20,7 +19,7 @@ struct LogEntry {
};
LogEntry logEntries[] = {
{"t", &tFloat},
{"t", &t},
{"rates.x", &rates.x},
{"rates.y", &rates.y},
{"rates.z", &rates.z},
@@ -40,7 +39,6 @@ const int logColumns = sizeof(logEntries) / sizeof(logEntries[0]);
float logBuffer[LOG_SIZE][logColumns];
void prepareLogData() {
tFloat = t;
attitudeEuler = attitude.toEuler();
attitudeTargetEuler = attitudeTarget.toEuler();
}
@@ -48,9 +46,8 @@ void prepareLogData() {
void logData() {
if (!armed) return;
static int logPointer = 0;
static double logTime = 0;
if (t - logTime < LOG_PERIOD) return;
logTime = t;
static Rate period(LOG_RATE);
if (!period) return;
prepareLogData();
@@ -64,12 +61,13 @@ void logData() {
}
}
void dumpLog() {
// Print header
void printLogHeader() {
for (int i = 0; i < logColumns; i++) {
print("%s%s", logEntries[i].name, i < logColumns - 1 ? "," : "\n");
}
// Print data
}
void printLogData() {
for (int i = 0; i < LOG_SIZE; i++) {
if (logBuffer[i][0] == 0) continue; // skip empty records
for (int j = 0; j < logColumns; j++) {

View File

@@ -6,16 +6,17 @@
#if WIFI_ENABLED
#include <MAVLink.h>
#include "util.h"
#define SYSTEM_ID 1
#define PERIOD_SLOW 1.0
#define PERIOD_FAST 0.1
#define MAVLINK_RATE_SLOW 1
#define MAVLINK_RATE_FAST 10
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
extern double controlTime;
extern float controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
void processMavlink() {
@@ -26,15 +27,12 @@ void processMavlink() {
void sendMavlink() {
sendMavlinkPrint();
static double lastSlow = 0;
static double lastFast = 0;
mavlink_message_t msg;
uint32_t time = t * 1000;
if (t - lastSlow >= PERIOD_SLOW) {
lastSlow = t;
static Rate slow(MAVLINK_RATE_SLOW), fast(MAVLINK_RATE_FAST);
if (slow) {
mavlink_msg_heartbeat_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
(armed ? MAV_MODE_FLAG_SAFETY_ARMED : 0) |
((mode == STAB) ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0) |
@@ -49,9 +47,7 @@ void sendMavlink() {
sendMessage(&msg);
}
if (t - lastFast >= PERIOD_FAST && mavlinkConnected) {
lastFast = t;
if (fast && mavlinkConnected) {
const float zeroQuat[] = {0, 0, 0, 0};
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd
@@ -214,6 +210,20 @@ void handleMavlink(const void *_msg) {
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
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
mavlink_command_long_t m;

View File

@@ -38,9 +38,9 @@ void setupMotors() {
int getDutyCycle(float value) {
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;
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);
}

View File

@@ -4,51 +4,51 @@
// Parameters storage in flash memory
#include <Preferences.h>
#include "util.h"
extern float channelZero[16];
extern float channelMax[16];
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern float mavlinkControlScale;
Preferences storage;
struct Parameter {
const char *name; // max length is 16
const char *name; // max length is 15 (Preferences key limit)
float *variable;
float value; // cache
};
Parameter parameters[] = {
// control
{"ROLLRATE_P", &rollRatePID.p},
{"ROLLRATE_I", &rollRatePID.i},
{"ROLLRATE_D", &rollRatePID.d},
{"ROLLRATE_I_LIM", &rollRatePID.windup},
{"PITCHRATE_P", &pitchRatePID.p},
{"PITCHRATE_I", &pitchRatePID.i},
{"PITCHRATE_D", &pitchRatePID.d},
{"PITCHRATE_I_LIM", &pitchRatePID.windup},
{"YAWRATE_P", &yawRatePID.p},
{"YAWRATE_I", &yawRatePID.i},
{"YAWRATE_D", &yawRatePID.d},
{"ROLL_P", &rollPID.p},
{"ROLL_I", &rollPID.i},
{"ROLL_D", &rollPID.d},
{"PITCH_P", &pitchPID.p},
{"PITCH_I", &pitchPID.i},
{"PITCH_D", &pitchPID.d},
{"YAW_P", &yawPID.p},
{"PITCHRATE_MAX", &maxRate.y},
{"ROLLRATE_MAX", &maxRate.x},
{"YAWRATE_MAX", &maxRate.z},
{"TILT_MAX", &tiltMax},
{"CTL_R_RATE_P", &rollRatePID.p},
{"CTL_R_RATE_I", &rollRatePID.i},
{"CTL_R_RATE_D", &rollRatePID.d},
{"CTL_R_RATE_WU", &rollRatePID.windup},
{"CTL_P_RATE_P", &pitchRatePID.p},
{"CTL_P_RATE_I", &pitchRatePID.i},
{"CTL_P_RATE_D", &pitchRatePID.d},
{"CTL_P_RATE_WU", &pitchRatePID.windup},
{"CTL_Y_RATE_P", &yawRatePID.p},
{"CTL_Y_RATE_I", &yawRatePID.i},
{"CTL_Y_RATE_D", &yawRatePID.d},
{"CTL_R_P", &rollPID.p},
{"CTL_R_I", &rollPID.i},
{"CTL_R_D", &rollPID.d},
{"CTL_P_P", &pitchPID.p},
{"CTL_P_I", &pitchPID.i},
{"CTL_P_D", &pitchPID.d},
{"CTL_Y_P", &yawPID.p},
{"CTL_P_RATE_MAX", &maxRate.y},
{"CTL_R_RATE_MAX", &maxRate.x},
{"CTL_Y_RATE_MAX", &maxRate.z},
{"CTL_TILT_MAX", &tiltMax},
// imu
{"ACC_BIAS_X", &accBias.x},
{"ACC_BIAS_Y", &accBias.y},
{"ACC_BIAS_Z", &accBias.z},
{"ACC_SCALE_X", &accScale.x},
{"ACC_SCALE_Y", &accScale.y},
{"ACC_SCALE_Z", &accScale.z},
{"IMU_ACC_BIAS_X", &accBias.x},
{"IMU_ACC_BIAS_Y", &accBias.y},
{"IMU_ACC_BIAS_Z", &accBias.z},
{"IMU_ACC_SCALE_X", &accScale.x},
{"IMU_ACC_SCALE_Y", &accScale.y},
{"IMU_ACC_SCALE_Z", &accScale.z},
// rc
{"RC_ZERO_0", &channelZero[0]},
{"RC_ZERO_1", &channelZero[1]},
@@ -119,10 +119,9 @@ bool setParameter(const char *name, const float value) {
}
void syncParameters() {
static double lastSync = 0;
if (t - lastSync < 1) return; // sync once per second
static Rate rate(1);
if (!rate) return; // sync once per second
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
lastSync = t;
for (auto &parameter : parameters) {
if (parameter.value == *parameter.variable) continue;

View File

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

View File

@@ -45,7 +45,7 @@ public:
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 w1 = u.y * v.z - u.z * v.y;
float w2 = u.z * v.x - u.x * v.z;

View File

@@ -6,10 +6,10 @@
#include <SBUS.h>
#include "util.h"
SBUS RC(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
SBUS rc(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
uint16_t channels[16]; // raw rc channels
double controlTime; // time of the last controls update
float controlTime; // time of the last controls update
float channelZero[16]; // calibration zero values
float channelMax[16]; // calibration max values
@@ -18,12 +18,12 @@ float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel =
void setupRC() {
print("Setup RC\n");
RC.begin();
rc.begin();
}
bool readRC() {
if (RC.read()) {
SBUSData data = RC.data();
if (rc.read()) {
SBUSData data = rc.data();
for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data
normalizeRC();
controlTime = t;

View File

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

View File

@@ -6,7 +6,7 @@
float loopRate; // Hz
void step() {
double now = micros() / 1000000.0;
float now = micros() / 1000000.0;
dt = now - t;
t = now;
@@ -18,7 +18,7 @@ void step() {
}
void computeLoopRate() {
static double windowStart = 0;
static float windowStart = 0;
static uint32_t rate = 0;
rate++;
if (t - windowStart >= 1) { // 1 second window

View File

@@ -10,12 +10,9 @@
#include <soc/rtc_cntl_reg.h>
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) {
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) {
float mapf(float x, float in_min, float in_max, float out_min, float out_max) {
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
@@ -52,3 +49,37 @@ void splitString(String& str, String& token0, String& token1, String& token2) {
token1 = strtok(NULL, " "); // String(NULL) creates empty string
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

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

View File

@@ -1,15 +1,96 @@
# 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!
### 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
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.
* 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,7 +12,7 @@
#define WIFI_ENABLED 1
double t = NAN;
float t = NAN;
float dt;
float motors[4];
float controlRoll, controlPitch, controlYaw, controlThrottle = NAN;
@@ -45,7 +45,8 @@ void normalizeRC();
void calibrateRC();
void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str);
void printRCCalibration();
void dumpLog();
void printLogHeader();
void printLogData();
void processMavlink();
void sendMavlink();
void sendMessage(const void *msg);

View File

@@ -21,7 +21,7 @@
#include "cli.ino"
#include "control.ino"
#include "estimate.ino"
#include "failsafe.ino"
#include "safety.ino"
#include "log.ino"
#include "lpf.h"
#include "mavlink.ino"

View File

@@ -49,6 +49,8 @@ for configuration in props['configurations']:
print('Check configuration', configuration['name'])
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)
for forced_include in configuration.get('forcedInclude', []):

View File

@@ -3,21 +3,49 @@
# Download flight log remotely and save to file
import os
import time
import datetime
import struct
from pymavlink.dialects.v20.common import MAVLink_log_data_message
from pyflix import Flix
DIR = os.path.dirname(os.path.realpath(__file__))
flix = Flix()
print('Downloading log...')
lines = flix.cli('log').splitlines()
# sort by timestamp
header = lines.pop(0)
lines.sort(key=lambda line: float(line.split(',')[0]))
header = flix.cli('log')
print('Received header:\n- ' + '\n- '.join(header.split(',')))
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')
content = header.encode() + b'\n' + b'\n'.join(line.encode() for line in lines)
log.write(content)
log.write(header.encode() + b'\n')
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)}')

View File

@@ -46,8 +46,11 @@ print(flix.acc) # accelerometer output (list)
print(flix.gyro) # gyroscope output (list)
```
> [!NOTE]
> The library uses the Front-Left-Up coordinate system — the same as in the firmware. All angles are in radians.
The library uses the Front-Left-Up coordinate system — the same as the firmware:
<img src="../../docs/img/drone-axes-rotate.svg" width="300">
All angles are in radians.
### Events
@@ -107,7 +110,7 @@ Full list of events:
|`value.<name>`|Specific named value update (see bellow)|Value|
> [!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 data from the drone, and do not mean the value has changed.
### Common methods
@@ -118,7 +121,7 @@ pitch_p = flix.get_param('PITCH_P') # get 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 command response:
```python
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
```
You can imitate pilot's controls using `set_controls` method:
You can pass pilot's controls using `set_controls` method:
```python
flix.set_controls(roll=0, pitch=0, yaw=0, throttle=0.6)