73 Commits

Author SHA1 Message Date
Oleg Kalachev
a5504cc550 Fix rates, acc and gyro coordinate frame in mavlink
All of them should be in frd.
Get rid of fluToFrd function - there is no big need for it.
2025-07-20 07:59:00 +03:00
Oleg Kalachev
cfb0f17a9a Minor cli change 2025-07-15 01:29:25 +03:00
Oleg Kalachev
d61948ec9c Rename printIMUCal to printIMUCalibration for consistency with rc 2025-07-15 01:25:10 +03:00
Oleg Kalachev
0c87d4d634 Port changes from commit 52819e4 2025-07-15 01:22:18 +03:00
Oleg Kalachev
4d1f9de872 Remove unnecessary documentation files 2025-07-10 06:14:22 +03:00
Oleg Kalachev
cf3d4d7ced Increase motors pwm frequency to 78Khz
1000 Hz is too low frequency considering the update loop for motors signal is also 1000 Hz.
Decrease resolution as it's required to set larger pwm frequencies.
This change should vastly improve control jitter and remove audible motors noise.
2025-07-10 06:08:37 +03:00
Oleg Kalachev
443e5213f0 Return zero rotation vector when converting neutral quaternion
Previously it would return nans
2025-07-10 06:07:16 +03:00
Oleg Kalachev
f24db96b50 Add missing equals and non-equals operators for quaternion lib 2025-07-10 06:07:08 +03:00
Oleg Kalachev
86305a08f8 Add missing newlines to initialization prints 2025-07-10 06:06:46 +03:00
Oleg Kalachev
21dcb39b7e Improve vector and quaternion libraries
Make the order or basic methods consistent between Vector and Quaternion.
Remove `ZYX` from Euler method names as this is standard for robotics.
Rename angular rates to rotation vector, which is more correct.
Make rotation methods static, to keep the arguments order consistent.
Make `Quaternion::fromAxisAngle` accept Vector for axis.
Minor fixes.
2025-07-10 06:02:38 +03:00
Oleg Kalachev
c08c89f667 Minor code updates 2025-07-10 05:58:50 +03:00
Oleg Kalachev
114d2305de Make wi-fi code more consistent between the firmware and simulation 2025-07-10 05:54:52 +03:00
Oleg Kalachev
a93e046117 Make sending udp packets much faster
Turns out parsing IP address string is very slow
2025-05-07 17:43:43 +03:00
Oleg Kalachev
e6e4db0c4f Update ESP32-Core to 3.2.0 2025-05-07 17:41:48 +03:00
Oleg Kalachev
d8fbc193c1 Make accelerometer calibration more verbose
Print the number of each calibration step
2025-05-07 17:40:31 +03:00
Oleg Kalachev
dcd95176b4 Make low pass filter formula more straightforward 2025-04-30 00:16:16 +03:00
Oleg Kalachev
b7cebbb3d6 Add some missing operator for vector library 2025-04-30 00:16:02 +03:00
Oleg Kalachev
a6ccd236de Fix simulation build in Actions
Switched runner to Ubuntu 22.04 since Gazebo 11 now has binaries for 22.04 (amd64 only).
Changed the building tutorial to reflect that.
2025-04-29 23:02:56 +03:00
Oleg Kalachev
e7a06b9413 Minor code simplifications 2025-04-29 23:01:59 +03:00
Oleg Kalachev
678bc7238e Update MAVLink-Arduino to 2.0.16 2025-04-29 23:01:46 +03:00
Oleg Kalachev
6670b4f358 Simplify and improve acc calibration command output 2025-04-29 23:01:09 +03:00
Oleg Kalachev
7f80a8a58d Remove twxs.cmake from the list of recommended extensions 2025-04-29 22:59:32 +03:00
Oleg Kalachev
2bd74e7f6f Minor code style fix 2025-04-29 22:59:09 +03:00
Oleg Kalachev
d378d01dbc Encode if the mode in stabilized in heartbeat message 2025-04-29 22:58:54 +03:00
Oleg Kalachev
e8341976f6 Cleanup 2025-03-01 00:02:44 +03:00
Oleg Kalachev
f2aae92f1e Cleanups and updates 2025-02-28 23:58:31 +03:00
Oleg Kalachev
0a7ed1039f Rename flu to frd function to match the code style 2025-02-28 23:39:03 +03:00
Oleg Kalachev
d4d1797ffc Update main readme for the minimal version 2025-02-28 23:22:03 +03:00
Oleg Kalachev
209986b9cd Change accel calibration code style a bit 2025-02-28 23:15:02 +03:00
Oleg Kalachev
32cdbba2a1 Remove dt multiplier from acc correction and increase acc weight
More classical complementary filter implementation
Increase effective accelerometer weight for faster convergence
2025-02-28 23:13:44 +03:00
Oleg Kalachev
dd1ea4f604 Cleanup mavlink subsystem code 2025-02-28 23:12:57 +03:00
Oleg Kalachev
5fc30dbd8a Put last control time in RC control mavlink message instead of send time 2025-02-28 23:08:40 +03:00
Oleg Kalachev
51fa5a6cac Simplify and fix code 2025-02-28 23:07:37 +03:00
Oleg Kalachev
75127eb6f8 Remove non-nessesary printArray function 2025-02-28 23:06:12 +03:00
Oleg Kalachev
89c1ada005 Remove command parsing to simplify the code 2025-02-28 23:02:02 +03:00
Oleg Kalachev
6058e8ecab Refactor CLI submodule
Move command parsing to doCommand
Parse command with splitString instead of stringToken
Trim commands
Move cliTestMotor to the bottom
Rename parseInput to handleInput, which is more clear
Move motor test function to motors.ino
Remove parameters table functionality to simplify the code
2025-02-28 22:49:37 +03:00
Oleg Kalachev
67e4a95697 Minor fix in joystick support for simulation
Don't use channels variable as it breaks code isolation
2025-02-28 22:30:29 +03:00
Oleg Kalachev
fafe630e4c Improve RC reading in calibration process 2025-02-28 22:29:36 +03:00
Oleg Kalachev
5ff44db8dd Simplify WIFI_ENABLED macro test 2025-02-28 22:28:44 +03:00
Zatupitel
2b15812483 Fix working on ESP32-S3 (#8)
Disable brown-out detector in a more correct way: clear only enable bit instead of clearing the whole register.

---------

Co-authored-by: Oleg Kalachev <okalachev@gmail.com>
2025-02-28 22:28:10 +03:00
Oleg Kalachev
dbfbe11478 Add test on building the firmware without Wi-Fi to Actions 2025-02-28 22:26:05 +03:00
Oleg Kalachev
41b5932a5d Move SBUS RC declaration to the top 2025-02-28 22:25:27 +03:00
Oleg Kalachev
add03482aa Minor cleanups and fixes 2025-02-28 22:24:15 +03:00
Oleg Kalachev
32c4875ca1 Increase pwm frequency and resolution 2025-02-28 22:22:39 +03:00
Oleg Kalachev
07c5ae19dd Update upload-artifact action to fix build 2025-02-28 22:21:53 +03:00
Oleg Kalachev
d60968ea25 Remove RC_CHANNELS macro 2025-02-28 22:19:52 +03:00
Oleg Kalachev
03c6576b72 Move controlsTime variable to rc.ino 2025-01-11 01:17:11 +03:00
Oleg Kalachev
59a8a80cce Minor cleanup 2025-01-10 07:15:38 +03:00
Oleg Kalachev
5530ad2981 Move loopRate to time.ino 2025-01-10 07:15:15 +03:00
Oleg Kalachev
f9e1802bc0 Make util module header instead of .ino-file 2025-01-10 07:02:00 +03:00
Oleg Kalachev
ddc46c049f Make ONE_G definition const and move to utils.ino 2025-01-09 11:31:33 +03:00
Oleg Kalachev
8c9bff0813 Make motor indexes definition const int and move them to motors.ino
Remove motor indexes definitions from flix.ino
Add motors.ino to simulation code and implement required mocks
2025-01-09 11:17:44 +03:00
Oleg Kalachev
e3873c99c5 Fix getDutyCycle return type to make it possible to increase resolution 2025-01-09 11:02:57 +03:00
Oleg Kalachev
fd437b96d3 Add missing const qualifiers to some quaternion methods 2025-01-09 10:03:08 +03:00
Oleg Kalachev
9a977e85c8 Implement rotate method for quaternions as replace for multiplication
Vector rotating method is renamed from `rotate` to `rotateVector` to avoid inconsistent object and argument order in different `rotate` methods
2025-01-09 10:00:16 +03:00
Oleg Kalachev
e66cadbb57 Some fixes and updates to readme and other articles 2025-01-09 10:00:05 +03:00
Oleg Kalachev
abfb3fea05 Update ESP32-core to 3.1.0 2025-01-09 09:59:51 +03:00
Oleg Kalachev
672149bd34 Use ubuntu-20.04 runner to build simulator in CI
The latest Ubuntu Gazebo 11 officially supports is Ubuntu 20.04
2025-01-09 09:59:40 +03:00
Oleg Kalachev
6c76d339e0 Add battery connector cable to components list 2025-01-09 09:59:31 +03:00
Oleg Kalachev
a76f5a2299 Remove redundant inline specifiers
In-class defined methods are specified as inline by default
2025-01-09 09:59:10 +03:00
Oleg Kalachev
8e8c8d05bb Some minor cleanups and fixes 2025-01-09 09:58:56 +03:00
Oleg Kalachev
1582238abc Various minor fixes 2024-12-27 21:53:23 +03:00
Oleg Kalachev
f7434921e5 Fix joystick work in simulation
Logic was broken as joystickGet never got called
2024-12-27 15:38:44 +03:00
Oleg Kalachev
3c28d0e950 Minor fix 2024-12-25 02:21:40 +03:00
Oleg Kalachev
77c621100f Increase motors output frequency 2024-12-25 02:19:06 +03:00
Oleg Kalachev
1ef1ed5fc4 Simplify motors duty cycle computation 2024-12-25 02:19:00 +03:00
Oleg Kalachev
ce67baae89 Minor fixes 2024-12-25 02:18:52 +03:00
Oleg Kalachev
ad9259810f Fix SBUS simulation logic
Don't consider zero values from not connected joystick
2024-12-25 02:17:58 +03:00
Oleg Kalachev
c43624734d Move ONE_G definition to flix.ino 2024-12-25 02:17:50 +03:00
Oleg Kalachev
292b10197f Improve logic of passing channels data in simulated SBUS
Return the data the same way as on the real drone without touching channels global vairable
2024-12-25 02:17:43 +03:00
Oleg Kalachev
16c9d8fe8a Minor change 2024-12-25 02:17:28 +03:00
Oleg Kalachev
931f46b92d Don't let throttle be less than 0 in failsafe 2024-12-25 02:17:16 +03:00
Oleg Kalachev
441f82af95 Add notice on removing props in motor test commands in help 2024-12-25 02:16:34 +03:00
142 changed files with 839 additions and 9514 deletions

View File

@@ -5,7 +5,6 @@ on:
branches: [ '*' ]
pull_request:
branches: [ master ]
workflow_dispatch:
jobs:
build_linux:
@@ -15,14 +14,7 @@ jobs:
- name: Install Arduino CLI
run: curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=/usr/local/bin sh
- name: Build firmware
env:
ARDUINO_SKETCH_ALWAYS_EXPORT_BINARIES: 1
run: make
- name: Upload binaries
uses: actions/upload-artifact@v4
with:
name: firmware-binary
path: flix/build
- name: Build firmware without Wi-Fi
run: sed -i 's/^#define WIFI_ENABLED 1$/#define WIFI_ENABLED 0/' flix/flix.ino && make
- name: Check c_cpp_properties.json
@@ -70,23 +62,22 @@ jobs:
path: gazebo/build/*.so
retention-days: 1
build_simulator_macos:
runs-on: macos-latest
if: github.event_name == 'workflow_dispatch'
steps:
- name: Install Arduino CLI
run: brew install arduino-cli
- uses: actions/checkout@v4
- name: Clean up python binaries # Workaround for https://github.com/actions/setup-python/issues/577
run: |
rm -f /usr/local/bin/2to3*
rm -f /usr/local/bin/idle3*
rm -f /usr/local/bin/pydoc3*
rm -f /usr/local/bin/python3*
rm -f /usr/local/bin/python3*-config
- name: Install Gazebo
run: brew update && brew tap osrf/simulation && brew install gazebo11
- name: Install SDL2
run: brew install sdl2
- name: Build simulator
run: make build_simulator
# build_simulator_macos:
# runs-on: macos-latest
# steps:
# - name: Install Arduino CLI
# run: brew install arduino-cli
# - uses: actions/checkout@v4
# - name: Clean up python binaries # Workaround for https://github.com/actions/setup-python/issues/577
# run: |
# rm -f /usr/local/bin/2to3*
# rm -f /usr/local/bin/idle3*
# rm -f /usr/local/bin/pydoc3*
# rm -f /usr/local/bin/python3*
# rm -f /usr/local/bin/python3*-config
# - name: Install Gazebo
# run: brew update && brew tap osrf/simulation && brew install gazebo11
# - name: Install SDL2
# run: brew install sdl2
# - name: Build simulator
# run: make build_simulator

View File

@@ -1,51 +0,0 @@
name: Docs
on:
push:
branches: [ '*' ]
pull_request:
branches: [ master ]
permissions:
contents: read
pages: write
id-token: write
jobs:
markdownlint:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- name: Install markdownlint
run: npm install -g markdownlint-cli2
- name: Run markdownlint
run: markdownlint-cli2 "**/*.md"
build_book:
runs-on: ubuntu-latest
needs: markdownlint
steps:
- uses: actions/checkout@v4
- name: Install mdBook
run: cargo install mdbook --vers 0.4.43 --locked
- name: Build book
run: cd docs && mdbook build
- name: Upload artifact
uses: actions/upload-pages-artifact@v3
with:
path: docs/build
deploy:
if: ${{ github.event_name == 'push' && github.ref == 'refs/heads/master' }}
concurrency:
group: "pages"
cancel-in-progress: true
environment:
name: github-pages
url: ${{ steps.deployment.outputs.page_url }}
runs-on: ubuntu-latest
needs: build_book
steps:
- name: Deploy to GitHub Pages
id: deployment
uses: actions/deploy-pages@v4

View File

@@ -19,21 +19,6 @@ jobs:
echo -e "t,x,y,z\n0,1,2,3\n1,4,5,6" > log.csv
./csv_to_ulog log.csv
test $(stat -c %s log.ulg) -eq 196
pyflix:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- name: Install Python build tools
run: pip install build
- name: Build pyflix
run: python3 -m build tools
- name: Upload artifacts
uses: actions/upload-artifact@v4
with:
name: pyflix
path: |
tools/dist/pyflix-*.tar.gz
tools/dist/pyflix-*.whl
python_tools:
runs-on: ubuntu-latest
steps:

2
.gitignore vendored
View File

@@ -2,8 +2,6 @@
*.elf
build/
tools/log/
tools/dist/
*.egg-info/
.dependencies
.vscode/*
!.vscode/settings.json

View File

@@ -1,68 +0,0 @@
{
"MD004": {
"style": "asterisk"
},
"MD010": false,
"MD013": false,
"MD024": false,
"MD033": false,
"MD034": false,
"MD044": {
"html_elements": false,
"code_blocks": false,
"names": [
"FlixPeriph",
"Wi-Fi",
"STM",
"Li-ion",
"GitHub",
"github.com",
"PPM",
"PWM",
"Futaba",
"S.Bus",
"C++",
"PID",
"Arduino IDE",
"Arduino",
"Arduino Nano",
"ESP32",
"IMU",
"MEMS",
"imu.ino",
"InvenSense",
"MPU-6050",
"MPU-9250",
"GY-91",
"GY-521",
"ICM-20948",
"Linux",
"Windows",
"macOS",
"iOS",
"Android",
"Bluetooth",
"GPS",
"GPIO",
"USB",
"SPI",
"I²C",
"UART",
"GND",
"3V3",
"VCC",
"SCL",
"SDA",
"SAO",
"AD0",
"MOSI",
"MISO",
"NCS",
"MOSFET",
"ArduPilot",
"Betaflight",
"PX4"
]
},
"MD045": false
}

View File

@@ -28,8 +28,7 @@
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
"${workspaceFolder}/flix/wifi.ino"
],
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
"cStandard": "c11",
@@ -75,8 +74,7 @@
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
"${workspaceFolder}/flix/wifi.ino"
],
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
"cStandard": "c11",
@@ -122,8 +120,7 @@
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
"${workspaceFolder}/flix/wifi.ino"
],
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++.exe",
"cStandard": "c11",

178
README.md
View File

@@ -1,179 +1,7 @@
# Flix
**Flix** (*flight + X*) — making an open source ESP32-based quadcopter from scratch.
Minimal **Flix** quadcopter firmware implementation for the [book](https://quadcopter.dev).
<table>
<tr>
<td align=center><strong>Version 1.1</strong> (3D-printed frame)</td>
<td align=center><strong>Version 0</strong></td>
</tr>
<tr>
<td><img src="docs/img/flix1.1.jpg" width=500 alt="Flix quadcopter"></td>
<td><img src="docs/img/flix.jpg" width=500 alt="Flix quadcopter"></td>
</tr>
</table>
See the full code and documentation in the main branch: https://github.com/okalachev/flix.
## Features
* Dedicated for education and research.
* Made from general-purpose components.
* Simple and clean source code in Arduino (<2k lines firmware).
* Control using USB gamepad, remote control or smartphone.
* Wi-Fi and MAVLink support.
* Wireless command line interface and analyzing.
* Precise simulation with Gazebo.
* Python library.
* Textbook on flight control theory and practice ([in development](https://quadcopter.dev)).
* *Position control (using external camera) and autonomous flights¹*.
*¹ — planned.*
## It actually flies
See detailed demo video: https://youtu.be/hT46CZ1CgC4.
<a href="https://youtu.be/hT46CZ1CgC4"><img width=500 src="https://i3.ytimg.com/vi/hT46CZ1CgC4/maxresdefault.jpg"></a>
Version 0 demo video: https://youtu.be/8GzzIQ3C6DQ.
<a href="https://youtu.be/8GzzIQ3C6DQ"><img width=500 src="https://i3.ytimg.com/vi/8GzzIQ3C6DQ/maxresdefault.jpg"></a>
Usage in education (RoboCamp): https://youtu.be/Wd3yaorjTx0.
<a href="https://youtu.be/Wd3yaorjTx0"><img width=500 src="https://i3.ytimg.com/vi/Wd3yaorjTx0/sddefault.jpg"></a>
See the [user builds gallery](docs/user.md):
<a href="docs/user.md"><img src="docs/img/user/user.jpg" width=500></a>
## Simulation
The simulator is implemented using Gazebo and runs the original Arduino code:
<img src="docs/img/simulator1.png" width=500 alt="Flix simulator">
## 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).
## 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|
|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|
|Battery connector cable|MX2.0 2P female|<img src="docs/img/mx.png" 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 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|
|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|
|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` in `imu.ino` file if using ICM-20948 board.*<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.*
Tools required for assembly:
* 3D printer.
* Soldering iron.
* Solder wire (with flux).
* 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)).
## Schematics
### Simplified connection diagram
<img src="docs/img/schematics1.svg" width=800 alt="Flix version 1 schematics">
Motor connection scheme:
<img src="docs/img/mosfet-connection.png" height=400 alt="MOSFET 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.
* Connect the IMU board to the ESP32 Mini using VSPI, power it using 3.3V and GND pins:
|IMU pin|ESP32 pin|
|-|-|
|GND|GND|
|3.3V|3.3V|
|SCL *(SCK)*|SVP (GPIO18)|
|SDA *(MOSI)*|GPIO23|
|SAO *(MISO)*|GPIO19|
|NCS|GPIO5|
* 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*)|
Counter-clockwise motors have black and white wires and clockwise motors have blue and red wires.
* Optionally connect the RC receiver to the ESP32's UART2:
|Receiver pin|ESP32 pin|
|-|-|
|GND|GND|
|VIN|VCC (or 3.3V depending on the receiver)|
|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.*
### IMU placement
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).
## 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.
⚠️ The author is not responsible for any damage, injury, or loss resulting from the use of this project. Use at your own risk!
<img src="docs/img/flix1.jpg" width=500 alt="Flix quadcopter">

View File

@@ -1,5 +1,3 @@
board_manager:
additional_urls:
- https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json
network:
connection_timeout: 1h

View File

@@ -1,10 +0,0 @@
build:
mdbook build
serve:
mdbook serve
clean:
mdbook clean
.PHONY: build serve clean

View File

@@ -1,31 +0,0 @@
# https://rust-lang.github.io/mdBook/format/configuration/preprocessors.html
# https://rust-lang.github.io/mdBook/for_developers/preprocessors.html
import json
import sys
import re
def transform_markdown_to_html(markdown_text):
def replace_blockquote(match):
tag = match.group(1).lower()
content = match.group(2).strip().replace('\n> ', ' ')
return f'<div class="alert alert-{tag}">{content}</div>\n'
pattern = re.compile(r'> \[!(NOTE|TIP|IMPORTANT|WARNING|CAUTION)\]\n>(.*?)\n?(?=(\n[^>]|\Z))', re.DOTALL)
transformed_text = pattern.sub(replace_blockquote, markdown_text)
return transformed_text
if __name__ == '__main__':
if len(sys.argv) > 1:
if sys.argv[1] == 'supports':
sys.exit(0)
context, book = json.load(sys.stdin)
for section in book['sections']:
if 'Chapter' in section:
section['Chapter']['content'] = transform_markdown_to_html(section['Chapter']['content'])
print(json.dumps(book))

View File

@@ -1,29 +0,0 @@
# Brief assembly guide
Soldered components ([schematics variant](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612338222067&cot=14)):
<img src="img/assembly/1.jpg" width=600>
<br>Use double-sided tape to attach ESP32 to the top frame part (ESP32 holder):
<img src="img/assembly/2.jpg" width=600>
<br>Use two washers to screw the IMU board to the frame:
<img src="img/assembly/3.jpg" width=600>
<br>Screw the IMU with M3x5 screws as shown:
<img src="img/assembly/4.jpg" width=600>
<br>Install the motors, attach MOSFETs to the frame using tape:
<img src="img/assembly/5.jpg" width=600>
<br>Screw the ESP32 holder with M1.4x5 screws to the frame:
<img src="img/assembly/6.jpg" width=600>
<br>Assembled drone:
<img src="img/assembly/7.jpg" width=600>

File diff suppressed because it is too large Load Diff

Binary file not shown.

View File

@@ -1,116 +0,0 @@
.sidebar-resize-handle { display: none !important; }
footer {
contain: content;
border-top: 3px solid #f4f4f4;
}
footer a.telegram, footer a.github {
display: block;
margin-bottom: 10px;
margin-top: 10px;
display: flex;
align-items: center;
text-decoration: none;
}
.content .github, .content .telegram {
display: flex;
align-items: center;
text-align: center;
justify-content: center;
}
.telegram::before, .github::before {
font-family: FontAwesome;
margin-right: 0.3em;
font-size: 1.6em;
color: black;
}
.github::before {
content: "\f09b";
}
.telegram::before {
font-size: 1.4em;
color: #0084c5;
content: "\f2c6";
}
.content hr {
border: none;
border-top: 2px solid #c9c9c9;
margin: 2em 0;
}
.content img {
display: block;
margin: 0 auto;
}
.content img.border {
border: 1px solid #c9c9c9;
}
@media (max-width: 600px) {
.MathJax_Display {
overflow-x: auto;
}
}
.firmware {
position: relative;
margin: 20px 0;
padding: 20px 20px;
padding-left: 60px;
color: var(--fg);
background-color: var(--quote-bg);
border-block-start: .1em solid var(--quote-border);
border-block-end: .1em solid var(--quote-border);
}
.firmware::before {
font-family: FontAwesome;
font-size: 1.5em;
content: "\f15b";
position: absolute;
width: 20px;
text-align: center;
left: 20px;
}
.alert {
margin-top: 20px;
margin-bottom: 20px;
position: relative;
border-left: 2px solid #0a69da;
padding: 20px;
padding-left: 60px;
}
.alert::before {
font-family: FontAwesome;
font-size: 1.5em;
color: #0a69da;
content: "\f05a";
position: absolute;
width: 20px;
text-align: center;
left: 20px;
}
.alert-tip { border-left-color: #1b7f37; }
.alert-tip::before { color: #1b7f37; content: '\f0eb'; }
.alert-caution { border-left-color: #cf212e; }
.alert-caution::before { color: #cf212e; content: '\f071'; }
.alert-important { border-left-color: #8250df; }
.alert-important::before { color: #8250df; content: '\f06a'; }
.alert-warning { border-left-color: #f0ad4e; }
.alert-warning::before { color: #f0ad4e; content: '\f071'; }
.alert-code { border-left-color: #333; }
.alert-code::before { color: #333; content: '\f121'; }

View File

@@ -1,22 +0,0 @@
[book]
authors = ["Oleg Kalachev"]
language = "ru"
multilingual = false
src = "book"
title = "Полетный контроллер с нуля"
description = "Учебник по разработке полетного контроллера квадрокоптера"
[build]
build-dir = "build"
[output.html]
additional-css = ["book.css", "zoom.css", "rotation.css"]
additional-js = ["zoom.js", "js.js"]
edit-url-template = "https://github.com/okalachev/flix/blob/master/docs/{path}?plain=1"
mathjax-support = true
[output.html.code.hidelines]
cpp = "//~"
[preprocessor.alerts]
command = "python3 alerts.py"

View File

@@ -1,10 +0,0 @@
# Flix
> [!IMPORTANT]
> Flix — это проект по созданию открытого квадрокоптера на базе ESP32 с нуля и учебника по разработке полетных контроллеров.
<img src="img/flix1.1.jpg" class="border" width=500 alt="Flix quadcopter">
<p class="github">GitHub:&nbsp;<a href="https://github.com/okalachev/flix">github.com/okalachev/flix</a>.</p>
<p class="telegram">Telegram-канал:&nbsp;<a href="https://t.me/opensourcequadcopter">@opensourcequadcopter</a>.</p>

View File

@@ -1,23 +0,0 @@
<!-- markdownlint-disable MD041 -->
<!-- markdownlint-disable MD042 -->
[Главная](./README.md)
* [Архитектура прошивки](firmware.md)
# Учебник
* [Основы]()
* [Светодиод]()
* [Моторы]()
* [Радиоуправление]()
* [Вектор, кватернион](geometry.md)
* [Гироскоп](gyro.md)
* [Акселерометр]()
* [Оценка состояния]()
* [PID-регулятор]()
* [Режим ACRO]()
* [Режим STAB]()
* [Wi-Fi]()
* [MAVLink]()
* [Симуляция]()

View File

@@ -1,50 +0,0 @@
# Архитектура прошивки
Прошивка Flix это обычный скетч Arduino, реализованный в однопоточном стиле. Код инициализации находится в функции `setup()`, а главный цикл — в функции `loop()`. Скетч состоит из нескольких файлов, каждый из которых отвечает за определенную подсистему.
<img src="img/dataflow.svg" width=600 alt="Firmware dataflow diagram">
Главный цикл `loop()` работает на частоте 1000 Гц. Передача данных между подсистемами происходит через глобальные переменные:
* `t` *(float)* — текущее время шага, *с*.
* `dt` *(float)* — дельта времени между текущим и предыдущим шагами, *с*.
* `gyro` *(Vector)* — данные с гироскопа, *рад/с*.
* `acc` *(Vector)* — данные с акселерометра, *м/с<sup>2</sup>*.
* `rates` *(Vector)* — отфильтрованные угловые скорости, *рад/с*.
* `attitude` *(Quaternion)* — оценка ориентации (положения) дрона.
* `controlRoll`, `controlPitch`, ... *(float[])* — команды управления от пилота, в диапазоне [-1, 1].
* `motors` *(float[])* — выходные сигналы на моторы, в диапазоне [0, 1].
## Исходные файлы
Исходные файлы прошивки находятся в директории `flix`. Основные файлы:
* [`flix.ino`](https://github.com/okalachev/flix/blob/master/flix/flix.ino) — основной файл Arduino-скетча. Определяет некоторые глобальные переменные и главный цикл.
* [`imu.ino`](https://github.com/okalachev/flix/blob/master/flix/imu.ino) — чтение данных с датчика IMU (гироскоп и акселерометр), калибровка IMU.
* [`rc.ino`](https://github.com/okalachev/flix/blob/master/flix/rc.ino) — чтение данных с RC-приемника, калибровка RC.
* [`estimate.ino`](https://github.com/okalachev/flix/blob/master/flix/estimate.ino) — оценка ориентации дрона, комплементарный фильтр.
* [`control.ino`](https://github.com/okalachev/flix/blob/master/flix/control.ino) — подсистема управления, трехмерный двухуровневый каскадный ПИД-регулятор.
* [`motors.ino`](https://github.com/okalachev/flix/blob/master/flix/motors.ino) — выход PWM на моторы.
* [`mavlink.ino`](https://github.com/okalachev/flix/blob/master/flix/mavlink.ino) — взаимодействие с QGroundControl или [pyflix](https://github.com/okalachev/flix/tree/master/tools/pyflix) через протокол MAVLink.
Вспомогательные файлы:
* [`vector.h`](https://github.com/okalachev/flix/blob/master/flix/vector.h), [`quaternion.h`](https://github.com/okalachev/flix/blob/master/flix/quaternion.h) — библиотеки векторов и кватернионов.
* [`pid.h`](https://github.com/okalachev/flix/blob/master/flix/pid.h) — ПИД-регулятор.
* [`lpf.h`](https://github.com/okalachev/flix/blob/master/flix/lpf.h) — фильтр нижних частот.
### Подсистема управления
Состояние органов управления обрабатывается в функции `interpretControls()` и преобразуется в *команду управления*, которая включает следующее:
* `attitudeTarget` *(Quaternion)* — целевая ориентация дрона.
* `ratesTarget` *(Vector)* — целевые угловые скорости, *рад/с*.
* `ratesExtra` *(Vector)* — дополнительные (feed-forward) угловые скорости, для управления рысканием в режиме STAB, *рад/с*.
* `torqueTarget` *(Vector)* — целевой крутящий момент, диапазон [-1, 1].
* `thrustTarget` *(float)* — целевая общая тяга, диапазон [0, 1].
Команда управления обрабатывается в функциях `controlAttitude()`, `controlRates()`, `controlTorque()`. Если значение одной из переменных установлено в `NAN`, то соответствующая функция пропускается.
<img src="img/control.svg" width=300 alt="Control subsystem diagram">
Состояние *armed* хранится в переменной `armed`, а текущий режим — в переменной `mode`.

View File

@@ -1,309 +0,0 @@
# Вектор, кватернион
В алгоритме управления квадрокоптером широко применяются геометрические (и алгебраические) объекты, такие как **векторы** и **кватернионы**. Они позволяют упростить математические вычисления и улучшить читаемость кода. В этой главе мы рассмотрим именно те геометрические объекты, которые используются в алгоритме управления квадрокоптером Flix, причем акцент будет сделан на практических аспектах их использования.
## Система координат
### Оси координат
Для работы с объектами в трехмерном пространстве необходимо определить *систему координат*. Как известно, система координат задается тремя взаимно перпендикулярными осями, которые обозначаются как *X*, *Y* и *Z*. Порядок обозначения этих осей зависит от того, какую систему координат мы выбрали — *левую* или *правую*:
|Левая система координат|Правая система координат|
|-----------------------|------------------------|
|<img src="img/left-axes.svg" alt="Левая система координат" width="200">|<img src="img/right-axes.svg" alt="Правая система координат" width="200">|
В Flix для всех математических расчетов используется **правая система координат**, что является стандартом в робототехнике и авиации.
Также необходимо выбрать направление осей — в Flix они выбраны в соответствии со стандартом [REP-103](https://www.ros.org/reps/rep-0103.html). Для величин, заданных в подвижной системе координат, связанной с корпусом дрона, применяется порядок <abbr title="Forward Left Up">FLU</abbr>:
* ось X — направлена **вперед**;
* ось Y — направлена **влево**;
* ось Z — направлена **вверх**.
Для величин, заданных в *мировой* системе координат (относительно фиксированной точки в пространстве) — <abbr title="East North Up">ENU</abbr>:
* ось X — направлена на **восток** (условный);
* ось Y — направлена на **север** (условный);
* ось Z — направлена **вверх**.
> [!NOTE]
> Для системы ENU важно только взаимное направление осей. Если доступен магнитометр, то используются реальные восток и север, но если нет — то произвольно выбранные.
Углы и угловые скорости определяются в соответствии с правилами математики: значения увеличиваются против часовой стрелки, если смотреть в сторону начала координат. Общий вид системы координат:
<img src="img/axes-rotation.svg" alt="Система координат" width="200">
> [!TIP]
> Оси координат <i>X</i>, <i>Y</i> и <i>Z</i> часто обозначаются красными, зелеными и синими цветами соответственно. Запомнить это можно с помощью сокращения <abbr title="Red Green Blue">RGB</abbr>.
## Вектор
<div class="firmware">
<strong>Файл прошивки:</strong>
<a href="https://github.com/okalachev/flix/blob/master/flix/vector.h"><code>vector.h</code></a>.<br>
</div>
**Вектор** — простой геометрический объект, который содержит три значения, соответствующие координатам *X*, *Y* и *Z*. Эти значения называются *компонентами вектора*. Вектор может описывать точку в пространстве, направление или ось вращения, скорость, ускорение, угловые скорости и другие физические величины. В Flix векторы задаются объектами `Vector` из библиотеки `vector.h`:
```cpp
Vector v(1, 2, 3);
v.x = 5;
v.y = 10;
v.z = 15;
```
> [!TIP]
> Не следует путать геометрический вектор — <code>vector</code> и динамический массив в стандартной библиотеке C++ — <code>std::vector</code>.
В прошивке в виде векторов представлены, например:
* `acc` собственное ускорение с акселерометра.
* `gyro` — угловые скорости с гироскопа.
* `rates` — рассчитанная угловая скорость дрона.
* `accBias`, `accScale`, `gyroBias` — параметры калибровки IMU.
### Операции с векторами
**Длина вектора** рассчитывается при помощи теоремы Пифагора; в прошивке используется метод `norm()`:
```cpp
Vector v(3, 4, 5);
float length = v.norm(); // 7.071
```
Любой вектор можно привести к **единичному вектору** (сохранить направление, но сделать длину равной 1) при помощи метода `normalize()`:
```cpp
Vector v(3, 4, 5);
v.normalize(); // 0.424, 0.566, 0.707
```
**Сложение и вычитание** векторов реализуется через простое покомпонентное сложение и вычитание. Геометрически сумма векторов представляет собой вектор, который соединяет начало первого вектора с концом второго. Разность векторов представляет собой вектор, который соединяет конец первого вектора с концом второго. Это удобно для расчета относительных позиций, суммарных скоростей и решения других задач. В коде эти операции интуитивно понятны:
```cpp
Vector a(1, 2, 3);
Vector b(4, 5, 6);
Vector sum = a + b; // 5, 7, 9
Vector diff = a - b; // -3, -3, -3
```
Операция **умножения на число** `n` увеличивает (или уменьшает) длину вектора в `n` раз (сохраняя направление):
```cpp
Vector a(1, 2, 3);
Vector b = a * 2; // 2, 4, 6
```
В некоторых случаях полезна операция **покомпонентного умножения** (или деления) векторов. Например, для применения коэффициентов калибровки к данным с IMU. В разных библиотеках эта операция обозначается по разному, но в библиотеке `vector.h` используется простые знаки `*` и `/`:
```cpp
acc = acc / accScale;
```
**Угол между векторами** можно найти при помощи статического метода `Vector::angleBetween()`:
```cpp
Vector a(1, 0, 0);
Vector b(0, 1, 0);
float angle = Vector::angleBetween(a, b); // 1.57 (90 градусов)
```
#### Скалярное произведение
Скалярное произведение векторов (*dot product*) — это произведение длин двух векторов на косинус угла между ними. В математике оно обозначается знаком `·` или слитным написанием векторов. Интуитивно, результат скалярного произведения показывает, насколько два вектора *сонаправлены*.
В Flix используется статический метод `Vector::dot()`:
```cpp
Vector a(1, 2, 3);
Vector b(4, 5, 6);
float dotProduct = Vector::dot(a, b); // 32
```
Операция скалярного произведения может помочь, например, при расчете проекции одного вектора на другой.
#### Векторное произведение
Векторное произведение (*cross product*) позволяет найти вектор, перпендикулярный двум другим векторам. В математике оно обозначается знаком `×`, а в прошивке используется статический метод `Vector::cross()`:
```cpp
Vector a(1, 2, 3);
Vector b(4, 5, 6);
Vector crossProduct = Vector::cross(a, b); // -3, 6, -3
```
## Кватернион
### Ориентация в трехмерном пространстве
В отличие от позиции и скорости, у ориентации в трехмерном пространстве нет универсального для всех случаев способа представления. В зависимости от задачи ориентация может быть представлена в виде *углов Эйлера*, *матрицы поворота*, *вектора вращения* или *кватерниона*. Рассмотрим используемые в полетной прошивке способы представления ориентации.
### Углы Эйлера
**Углы Эйлера***крен*, *тангаж* и *рыскание* — это наиболее «естественный» для человека способ представления ориентации. Они описывают последовательные вращения объекта вокруг трех осей координат.
В прошивке углы Эйлера сохраняются в обычный объект `Vector` (хоть и, строго говоря, не являются вектором):
* Угол по крену (*roll*) — `vector.x`.
* Угол по тангажу (*pitch*) — `vector.y`.
* Угол по рысканию (*yaw*) — `vector.z`.
Особенности углов Эйлера:
1. Углы Эйлера зависят от порядка применения вращений, то есть существует 6 типов углов Эйлера. Порядок вращений, принятый в Flix (и в роботехнике в целом) — рыскание, тангаж, крен (ZYX).
2. Для некоторых ориентаций углы Эйлера «вырождаются». Так, если объект «смотрит» строго вниз, то угол по рысканию и угол по крену становятся неразличимыми. Эта ситуация называется *gimbal lock* — потеря одной степени свободы.
Ввиду этих особенности для углов Эйлера не существует общих формул для самых базовых задач с ориентациями, таких как применение одного вращения (ориентации) к другому, расчет разницы между ориентациями и подобных. Поэтому в основном углы Эйлера применяются в пользовательском интерфейсе, но редко используются в математических расчетах.
> [!IMPORTANT]
> Для углов Эйлера не существует общих формул для самых базовых операций с ориентациями.
### Axis-angle
Помимо углов Эйлера, любую ориентацию в трехмерном пространстве можно представить в виде вращения вокруг некоторой оси на некоторый угол. В геометрии это доказывается, как **теорема вращения Эйлера**. В таком представлении ориентация задается двумя величинами:
* **Ось вращения** (*axis*) — единичный вектор, определяющий ось вращения.
* **Угол поворота** (*angle* или *θ*) — угол, на который нужно повернуть объект вокруг этой оси.
В Flix ось вращения задается объектом `Vector`, а угол поворота — числом типа `float` в радианах:
```cpp
// Вращение на 45 градусов вокруг оси (1, 2, 3)
Vector axis(1, 2, 3);
float angle = radians(45);
```
Этот способ более удобен для расчетов, чем углы Эйлера, но все еще не является оптимальным.
### Вектор вращения
Если умножить вектор *axis* на угол поворота *θ*, то получится **вектор вращения** (*rotation vector*). Этот вектор играет важную роль в алгоритмах управления ориентацией летательного аппарата.
Вектор вращения обладает замечательным свойством: если угловые скорости объекта (в собственной системе координат) в каждый момент времени совпадают с компонентами этого вектора, то за единичное время объект придет к заданной этим вектором ориентации. Это свойство позволяет использовать вектор вращения для управления ориентацией объекта посредством управления угловыми скоростями.
> [!IMPORTANT]
> Чтобы за единичное время прийти к заданной ориентации, собственные угловые скорости объекта должны быть равны компонентам вектора вращения.
Вектора вращения в Flix представляются в виде объектов `Vector`:
```cpp
// Вращение на 45 градусов вокруг оси (1, 2, 3)
Vector rotation = radians(45) * Vector(1, 2, 3);
```
### Кватернион
<div class="firmware">
<strong>Файл прошивки:</strong>
<a href="https://github.com/okalachev/flix/blob/master/flix/quaternion.h"><code>quaternion.h</code></a>.<br>
</div>
Вектор вращения удобен, но еще удобнее использовать **кватернион**. В Flix кватернионы задаются объектами `Quaternion` из библиотеки `quaternion.h`. Кватернион состоит из четырех значений: *w*, *x*, *y*, *z* и рассчитывается из вектора оси вращения (*axis*) и угла поворота (*θ*) по формуле:
\\[ q = \left( \begin{array}{c} w \\\\ x \\\\ y \\\\ z \end{array} \right) = \left( \begin{array}{c} \cos\left(\frac{\theta}{2}\right) \\\\ axis\_x \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_y \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_z \cdot \sin\left(\frac{\theta}{2}\right) \end{array} \right) \\]
На практике оказывается, что **именно такое представление наиболее удобно для математических расчетов**.
Проиллюстрируем кватернион и описанные выше способы представления ориентации на интерактивной визуализации. Изменяйте угол поворота *θ* с помощью ползунка (ось вращения константна) и изучите, как меняется ориентация объекта, вектор вращения и кватернион:
<div id="rotation-diagram" class="diagram">
<p>
<label class="angle" for="angle-range"></label>
<input type="range" name="angle" id="angle-range" min="0" max="360" value="0" step="1">
</p>
<p class="axis"></p>
<p class="rotation-vector"></p>
<p class="quaternion"></p>
<p class="euler"></p>
</div>
<script type="importmap">
{
"imports": {
"three": "https://cdn.jsdelivr.net/npm/three@0.176.0/build/three.module.js",
"three/addons/": "https://cdn.jsdelivr.net/npm/three@0.176.0/examples/jsm/"
}
}
</script>
<script type="module" src="js/rotation.js"></script>
> [!IMPORTANT]
> В контексте управляющих алгоритмов кватернион — это оптимизированный для расчетов аналог вектора вращения.
Кватернион это наиболее часто используемый способ представления ориентации в алгоритмах. Кроме этого, у кватерниона есть большое значение в теории чисел и алгебре, как у расширения понятия комплексного числа, но рассмотрение этого аспекта выходит за рамки описания работы с вращениями с практической точки зрения.
В прошивке в виде кватернионов представлены, например:
* `attitude` — текущая ориентация квадрокоптера.
* `attitudeTarget` — целевая ориентация квадрокоптера.
### Операции с кватернионами
Кватернион создается напрямую из четырех его компонент:
```cpp
// Кватернион, представляющий нулевую (исходную) ориентацию
Quaternion q(1, 0, 0, 0);
```
Кватернион можно создать из оси вращения и угла поворота, вектора вращения или углов Эйлера:
```cpp
Quaternion q1 = Quaternion::fromAxisAngle(axis, angle);
Quaternion q2 = Quaternion::fromRotationVector(rotation);
Quaternion q3 = Quaternion::fromEuler(Vector(roll, pitch, yaw));
```
И наоборот:
```cpp
q1.toAxisAngle(axis, angle);
Vector rotation = q2.toRotationVector();
Vector euler = q3.toEuler();
```
Возможно рассчитать вращение между двумя обычными векторами:
```cpp
Quaternion q = Quaternion::fromBetweenVectors(v1, v2); // в виде кватерниона
Vector rotation = Vector::rotationVectorBetween(v1, v2); // в виде вектора вращения
```
Шорткаты для работы с углом Эйлера по рысканью (удобно для алгоритмов управления полетом):
```cpp
float yaw = q.getYaw();
q.setYaw(yaw);
```
#### Применения вращений
Чтобы применить вращение, выраженное в кватернионе, к другому кватерниону, в математике используется операция **умножения кватернионов**. При использовании этой операции, необходимо учитывать, что она не является коммутативной, то есть порядок операндов имеет значение. Формула умножения кватернионов выглядит так:
\\[ q_1 \times q_2 = \left( \begin{array}{c} w_1 \\\\ x_1 \\\\ y_1 \\\\ z_1 \end{array} \right) \times \left( \begin{array}{c} w_2 \\\\ x_2 \\\\ y_2 \\\\ z_2 \end{array} \right) = \left( \begin{array}{c} w_1 w_2 - x_1 x_2 - y_1 y_2 - z_1 z_2 \\\\ w_1 x_2 + x_1 w_2 + y_1 z_2 - z_1 y_2 \\\\ w_1 y_2 - x_1 z_2 + y_1 w_2 + z_1 x_2 \\\\ w_1 z_2 + x_1 y_2 - y_1 x_2 + z_1 w_2 \end{array} \right) \\]
В библиотеке `quaternion.h` для этой операции используется статический метод `Quaternion::rotate()`:
```cpp
// Композиция вращений q1 и q2
Quaternion result = Quaternion::rotate(q1, q2);
```
Также полезной является операция применения вращения к вектору, которая делается похожим образом:
```cpp
// Вращение вектора v кватернионом q
Vector result = Quaternion::rotateVector(v, q);
```
Для расчета разницы между двумя ориентациями используется метод `Quaternion::between()`:
```cpp
// Расчет вращения от q1 к q2
Quaternion q = Quaternion::between(q1, q2);
```
## Дополнительные материалы
* [Интерактивный учебник по кватернионам](https://eater.net/quaternions).
* [Визуализация вращения вектора с помощью кватернионов](https://quaternions.online).

View File

@@ -1,262 +0,0 @@
# Гироскоп
<div class="firmware">
<strong>Файл прошивки:</strong>
<a href="https://github.com/okalachev/flix/blob/canonical/flix/imu.ino"><code>imu.ino</code></a> <small>(каноничная версия)</small>.<br>
Текущая версия: <a href="https://github.com/okalachev/flix/blob/master/flix/imu.ino"><code>imu.ino</code></a>.
</div>
Поддержание стабильного полета квадрокоптера невозможно без датчиков обратной связи. Важнейший из них — это **MEMS-гироскоп**. MEMS-гироскоп это микроэлектромеханический аналог классического механического гироскопа.
Механический гироскоп состоит из вращающегося диска, который сохраняет свою ориентацию в пространстве. Благодаря этому эффекту возможно определить ориентацию объекта в пространстве.
В MEMS-гироскопе нет вращающихся частей, и он помещается в крошечную микросхему. Он может измерять только текущую угловую скорость вращения объекта вокруг трех осей: X, Y и Z.
|Механический гироскоп|MEMS-гироскоп|
|-|-|
|<img src="img/gyroscope.jpg" width="300" alt="Механический гироскоп">|<img src="img/mpu9250.jpg" width="100" alt="MEMS-гироскоп MPU-9250">|
MEMS-гироскоп обычно интегрирован в инерциальный модуль (IMU), в котором также находятся акселерометр и магнитометр. Модуль IMU часто называют 9-осевым датчиком, потому что он измеряет:
* Угловую скорость вращения по трем осям (гироскоп).
* Ускорение по трем осям (акселерометр).
* Магнитное поле по трем осям (магнитометр).
Flix поддерживает следующие модели IMU:
* InvenSense MPU-9250.
* InvenSense MPU-6500.
* InvenSense ICM-20948.
> [!NOTE]
> MEMS-гироскоп измеряет угловую скорость вращения объекта.
## Интерфейс подключения
Большинство модулей IMU подключаются к микроконтроллеру через интерфейсы I²C и SPI. Оба этих интерфейса являются *шинами данных*, то есть позволяют подключить к одному микроконтроллеру несколько устройств.
**Интерфейс I²C** использует два провода для передачи данных и тактового сигнала. Выбор устройства для коммуникации происходит при помощи передачи адреса устройства на шину. Разные устройства имеют разные адреса, и микроконтроллер может последовательно общаться с несколькими устройствами.
**Интерфейс SPI** использует два провода для передачи данных, еще один для тактового сигнала и еще один для выбора устройства. При этом для каждого устройства на шине выделяется отдельный GPIO-пин для выбора. В разных реализациях этот пин называется CS/NCS (Chip Select) или SS (Slave Select). Когда CS-пин устройства активен (напряжение на нем низкое), устройство выбрано для общения.
В полетных контроллерах IMU обычно подключают через SPI, потому что он обеспечивает значительно бо́льшую скорость передачи данных и меньшую задержку. Подключение IMU через интерфейс I²C (например, в случае нехватки пинов микроконтроллера) возможно, но не рекомендуется.
Подключение IMU к микроконтроллеру ESP32 через интерфейс SPI выглядит так:
|Пин платы IMU|Пин ESP32|
|-|-|
|VCC/3V3|3V3|
|GND|GND|
|SCL|IO18|
|SDA *(MOSI)*|IO23|
|SAO/AD0 *(MISO)*|IO19|
|NCS|IO5|
Кроме того, многие IMU могут «будить» микроконтроллер при наличии новых данных. Для этого используется пин INT, который подключается к любому GPIO-пину микроконтроллера. При такой конфигурации можно использовать прерывания для обработки новых данных с IMU, вместо периодического опроса датчика. Это позволяет снизить нагрузку на микроконтроллер в сложных алгоритмах управления.
> [!WARNING]
> На некоторых платах IMU, например, на ICM-20948, отсутствует стабилизатор напряжения, поэтому их нельзя подключать к пину VIN ESP32, который подает напряжение 5 В. Допустимо питание только от пина 3V3.
## Работа с гироскопом
Для взаимодействия с IMU, включая работу с гироскопом, в Flix используется библиотека *FlixPeriph*. Библиотека устанавливается через менеджер библиотек Arduino IDE:
<img src="img/flixperiph.png" width="300">
Чтобы работать с IMU, используется класс, соответствующий модели IMU: `MPU9250`, `MPU6500` или `ICM20948`. Классы для работы с разными IMU имеют единообразный интерфейс для основных операций, поэтому возможно легко переключаться между разными моделями IMU. Датчик MPU-6500 практически полностью совместим с MPU-9250, поэтому фактически класс `MPU9250` поддерживает обе модели.
## Ориентация осей гироскопа
Данные с гироскопа представляют собой угловую скорость вокруг трех осей: X, Y и Z. Ориентацию этих осей у IMU InvenSense можно легко определить по небольшой точке в углу чипа. Оси координат и направление вращения для измерений гироскопа обозначены на диаграмме:
<img src="img/imu-axes.svg" width="300" alt="Оси координат IMU">
Расположение осей координат в популярных платах IMU:
|GY-91|MPU-92/65|ICM-20948|
|-|-|-|
|<img src="https://github.com/okalachev/flixperiph/raw/refs/heads/master/img/gy91-axes.svg" width="200" alt="Оси координат платы GY-91">|<img src="https://github.com/okalachev/flixperiph/raw/refs/heads/master/img/mpu9265-axes.svg" width="200" alt="Оси координат платы MPU-9265">|<img src="https://github.com/okalachev/flixperiph/raw/refs/heads/master/img/icm20948-axes.svg" width="200" alt="Оси координат платы ICM-20948">|
Магнитометр IMU InvenSense обычно является отдельным устройством, интегрированным в чип, поэтому его оси координат могут отличаться. Библиотека FlixPeriph скрывает это различие и приводит данные с магнитометра к системе координат гироскопа и акселерометра.
## Чтение данных
Интерфейс библиотеки FlixPeriph соответствует стилю, принятому в Arduino. Для начала работы с IMU необходимо создать объект соответствующего класса и вызвать метод `begin()`. В конструктор класса передается интерфейс, по которому подключен IMU (SPI или I²C):
```cpp
#include <FlixPeriph.h>
#include <SPI.h>
MPU9250 IMU(SPI);
void setup() {
Serial.begin(115200);
bool success = IMU.begin();
if (!success) {
Serial.println("Failed to initialize IMU");
}
}
```
Для однократного считывания данных используется метод `read()`. Затем данные с гироскопа получаются при помощи метода `getGyro(x, y, z)`. Этот метод записывает в переменные `x`, `y` и `z` угловые скорости вокруг соответствующих осей в радианах в секунду.
Если нужно гарантировать, что будут считаны новые данные, можно использовать метод `waitForData()`. Этот метод блокирует выполнение программы до тех пор, пока в IMU не появятся новые данные. Метод `waitForData()` позволяет привязать частоту главного цикла `loop` к частоте обновления данных IMU. Это удобно для организации главного цикла управления квадрокоптером.
Программа для чтения данных с гироскопа и вывода их в консоль для построения графиков в Serial Plotter выглядит так:
```cpp
#include <FlixPeriph.h>
#include <SPI.h>
MPU9250 IMU(SPI);
void setup() {
Serial.begin(115200);
bool success = IMU.begin();
if (!success) {
Serial.println("Failed to initialize IMU");
}
}
void loop() {
IMU.waitForData();
float gx, gy, gz;
IMU.getGyro(gx, gy, gz);
Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
delay(50); // замедление вывода
}
```
После запуска программы в Serial Plotter можно увидеть графики угловых скоростей. Например, при вращениях IMU вокруг вертикальной оси Z графики будут выглядеть так:
<img src="img/gyro-plotter.png">
## Конфигурация гироскопа
В коде Flix настройка IMU происходит в функции `configureIMU`. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплов и частота LPF-фильтра.
### Частота сэмплов
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер.
Частота сэмплов устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
```cpp
IMU.setRate(IMU.RATE_1KHZ_APPROX);
```
Поскольку не все поддерживаемые IMU могут работать строго на частоте 1 кГц, в библиотеке FlixPeriph существует возможность приближенной настройки частоты сэмплов. Например, у IMU ICM-20948 при такой настройке реальная частота сэмплирования будет равна 1125 Гц.
Другие доступные для установки в библиотеке FlixPeriph частоты сэмплирования:
* `RATE_MIN` — минимальная частота сэмплов для конкретного IMU.
* `RATE_50HZ_APPROX` — значение, близкое к 50 Гц.
* `RATE_1KHZ_APPROX` — значение, близкое к 1 кГц.
* `RATE_8KHZ_APPROX` — значение, близкое к 8 кГц.
* `RATE_MAX` — максимальная частота сэмплов для конкретного IMU.
#### Диапазон измерений
Большинство MEMS-гироскопов поддерживают несколько диапазонов измерений угловой скорости. Главное преимущество выбора меньшего диапазона — бо́льшая чувствительность. В полетных контроллерах обычно выбирается максимальный диапазон измерений от 2000 до 2000 градусов в секунду, чтобы обеспечить возможность динамичных маневров.
В библиотеке FlixPeriph диапазон измерений гироскопа устанавливается методом `setGyroRange()`:
```cpp
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
```
### LPF-фильтр
IMU InvenSense могут фильтровать измерения на аппаратном уровне при помощи фильтра нижних частот (LPF). Flix реализует собственный фильтр для гироскопа, чтобы иметь больше гибкости при поддержке разных IMU. Поэтому для встроенного LPF устанавливается максимальная частота среза:
```cpp
IMU.setDLPF(IMU.DLPF_MAX);
```
## Калибровка гироскопа
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения (*bias*) и случайный шум (*noise*):
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]
Для качественной работы подсистемы оценки ориентации и управления дроном необходимо оценить *bias* гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции `calibrateGyro()`. Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются *bias* гироскопа и в дальнейшем вычитаются из измерений.
Программа для вывода данных с гироскопа с калибровкой:
```cpp
#include <FlixPeriph.h>
#include <SPI.h>
MPU9250 IMU(SPI);
float gyroBiasX, gyroBiasY, gyroBiasZ; // bias гироскопа
void setup() {
Serial.begin(115200);
bool success = IMU.begin();
if (!success) {
Serial.println("Failed to initialize IMU");
}
calibrateGyro();
}
void loop() {
float gx, gy, gz;
IMU.waitForData();
IMU.getGyro(gx, gy, gz);
// Устранение bias гироскопа
gx -= gyroBiasX;
gy -= gyroBiasY;
gz -= gyroBiasZ;
Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
delay(50); // замедление вывода
}
void calibrateGyro() {
const int samples = 1000;
Serial.println("Calibrating gyro, stand still");
gyroBiasX = 0;
gyroBiasY = 0;
gyroBiasZ = 0;
// Получение 1000 измерений гироскопа
for (int i = 0; i < samples; i++) {
IMU.waitForData();
float gx, gy, gz;
IMU.getGyro(gx, gy, gz);
gyroBiasX += gx;
gyroBiasY += gy;
gyroBiasZ += gz;
}
// Усреднение значений
gyroBiasX = gyroBiasX / samples;
gyroBiasY = gyroBiasY / samples;
gyroBiasZ = gyroBiasZ / samples;
Serial.printf("Gyro bias X: %f\n", gyroBiasX);
Serial.printf("Gyro bias Y: %f\n", gyroBiasY);
Serial.printf("Gyro bias Z: %f\n", gyroBiasZ);
}
```
График данных с гироскопа в состоянии покоя без калибровки. Можно увидеть статическую ошибку каждой из осей:
<img src="img/gyro-uncalibrated-plotter.png">
График данных с гироскопа в состоянии покоя после калибровки:
<img src="img/gyro-calibrated-plotter.png">
Откалиброванные данные с гироскопа вместе с данными с акселерометра поступают в *подсистему оценки состояния*.
## Дополнительные материалы
* [MPU-9250 datasheet](https://invensense.tdk.com/wp-content/uploads/2015/02/PS-MPU-9250A-01-v1.1.pdf).
* [MPU-6500 datasheet](https://invensense.tdk.com/wp-content/uploads/2020/06/PS-MPU-6500A-01-v1.3.pdf).
* [ICM-20948 datasheet](https://invensense.tdk.com/wp-content/uploads/2016/06/DS-000189-ICM-20948-v1.3.pdf).

View File

@@ -1 +0,0 @@
../img

View File

@@ -1,262 +0,0 @@
import * as THREE from 'three';
import { SVGRenderer, SVGObject } from 'three/addons/renderers/SVGRenderer.js';
import { OrbitControls } from 'three/addons/controls/OrbitControls.js';
const diagramEl = document.getElementById('rotation-diagram');
const scene = new THREE.Scene();
scene.background = new THREE.Color(0xffffff);
const camera = new THREE.OrthographicCamera();
camera.position.set(9, 26, 20);
camera.up.set(0, 0, 1);
camera.lookAt(0, 0, 0);
const renderer = new SVGRenderer();
diagramEl.prepend(renderer.domElement);
const controls = new OrbitControls(camera, renderer.domElement);
controls.enableZoom = false;
const LINE_WIDTH = 4;
function createLabel(text, x, y, z, min = false) {
const label = document.createElementNS('http://www.w3.org/2000/svg', 'text');
label.setAttribute('class', 'label' + (min ? ' min' : ''));
label.textContent = text;
label.setAttribute('y', -15);
const object = new SVGObject(label);
object.position.x = x;
object.position.y = y;
object.position.z = z;
return object;
}
function createLine(x1, y1, z1, x2, y2, z2, color) {
const geometry = new THREE.BufferGeometry().setFromPoints([
new THREE.Vector3(x1, y1, z1),
new THREE.Vector3(x2, y2, z2)
]);
const material = new THREE.LineBasicMaterial({ color: color, linewidth: LINE_WIDTH, transparent: true, opacity: 0.8 });
const line = new THREE.Line(geometry, material);
scene.add(line);
return line;
}
function changeLine(line, x1, y1, z1, x2, y2, z2) {
line.geometry.setFromPoints([new THREE.Vector3(x1, y1, z1), new THREE.Vector3(x2, y2, z2)]);
return line;
}
function createVector(x1, y1, z1, x2, y2, z2, color, label = '') {
const HEAD_LENGTH = 1;
const HEAD_WIDTH = 0.2;
const group = new THREE.Group();
const direction = new THREE.Vector3(x2 - x1, y2 - y1, z2 - z1).normalize();
const norm = new THREE.Vector3(x2 - x1, y2 - y1, z2 - z1).length();
let end = new THREE.Vector3(x2, y2, z2);
if (norm > HEAD_LENGTH) {
end = new THREE.Vector3(x2 - direction.x * HEAD_LENGTH / 2, y2 - direction.y * HEAD_LENGTH / 2, z2 - direction.z * HEAD_LENGTH / 2);
}
// create line
const geometry = new THREE.BufferGeometry().setFromPoints([new THREE.Vector3(x1, y1, z1), end]);
const material = new THREE.LineBasicMaterial({ color: color, linewidth: LINE_WIDTH, transparent: true, opacity: 0.8 });
const line = new THREE.Line(geometry, material);
group.add(line);
if (norm > HEAD_LENGTH) {
// Create arrow
const arrowGeometry = new THREE.ConeGeometry(HEAD_WIDTH, HEAD_LENGTH, 16);
const arrowMaterial = new THREE.MeshBasicMaterial({ color: color });
const arrow = new THREE.Mesh(arrowGeometry, arrowMaterial);
arrow.position.set(x2 - direction.x * HEAD_LENGTH / 2, y2 - direction.y * HEAD_LENGTH / 2, z2 - direction.z * HEAD_LENGTH / 2);
arrow.lookAt(new THREE.Vector3(x1, y1, z1));
arrow.rotateX(-Math.PI / 2);
group.add(arrow);
}
// create label
if (label) group.add(createLabel(label, x2, y2, z2));
scene.add(group);
return group;
}
function changeVector(vector, x1, y1, z1, x2, y2, z2, color, label = '') {
vector.removeFromParent();
return createVector(x1, y1, z1, x2, y2, z2, color, label);
}
function createDrone(x, y, z) {
const group = new THREE.Group();
// Fuselage and wing triangle (main body)
const fuselageGeometry = new THREE.BufferGeometry();
const fuselageVertices = new Float32Array([
1, 0, 0,
-1, 0.6, 0,
-1, -0.6, 0
]);
fuselageGeometry.setAttribute('position', new THREE.BufferAttribute(fuselageVertices, 3));
const fuselageMaterial = new THREE.MeshBasicMaterial({ color: 0xb3b3b3, side: THREE.DoubleSide, transparent: true, opacity: 0.8 });
const fuselage = new THREE.Mesh(fuselageGeometry, fuselageMaterial);
group.add(fuselage);
// Tail triangle
const tailGeometry = new THREE.BufferGeometry();
const tailVertices = new Float32Array([
-0.2, 0, 0,
-1, 0, 0,
-1, 0, 0.5,
]);
tailGeometry.setAttribute('position', new THREE.BufferAttribute(tailVertices, 3));
const tailMaterial = new THREE.MeshBasicMaterial({ color: 0xd80100, side: THREE.DoubleSide, transparent: true, opacity: 0.9 });
const tail = new THREE.Mesh(tailGeometry, tailMaterial);
group.add(tail);
group.position.set(x, y, z);
group.scale.set(2, 2, 2);
scene.add(group);
return group;
}
// Create axes
const AXES_LENGTH = 10;
createVector(0, 0, 0, AXES_LENGTH, 0, 0, 0xd80100, 'x');
createVector(0, 0, 0, 0, AXES_LENGTH, 0, 0x0076ba, 'y');
createVector(0, 0, 0, 0, 0, AXES_LENGTH, 0x57ed00, 'z');
// Rotation values
const rotationAxisSrc = new THREE.Vector3(2, 1, 3);
let rotationAngle = 0;
let rotationAxis = rotationAxisSrc.clone().normalize();
let rotationVector = new THREE.Vector3(rotationAxis.x * rotationAngle, rotationAxis.y * rotationAngle, rotationAxis.z * rotationAngle);
let rotationVectorObj = createVector(0, 0, 0, rotationVector.x, rotationVector.y, rotationVector.z, 0xff9900);
let axisObj = createLine(0, 0, 0, rotationAxis.x * AXES_LENGTH, rotationAxis.y * AXES_LENGTH, rotationAxis.z * AXES_LENGTH, 0xe8e8e8);
const drone = createDrone(0, 0, 0);
// UI
const angleInput = diagramEl.querySelector('input[name=angle]');
const rotationVectorEl = diagramEl.querySelector('.rotation-vector');
const angleEl = diagramEl.querySelector('.angle');
const quaternionEl = diagramEl.querySelector('.quaternion');
const eulerEl = diagramEl.querySelector('.euler');
diagramEl.querySelector('.axis').innerHTML = `<b style='color:#b6b6b6'>Ось вращения:</b> (${rotationAxisSrc.x}, ${rotationAxisSrc.y}, ${rotationAxisSrc.z}) ∥ (${rotationAxis.x.toFixed(1)}, ${rotationAxis.y.toFixed(1)}, ${rotationAxis.z.toFixed(1)})`;
function updateScene() {
rotationAngle = parseFloat(angleInput.value) * Math.PI / 180;
rotationVector.set(rotationAxis.x * rotationAngle, rotationAxis.y * rotationAngle, rotationAxis.z * rotationAngle);
rotationVectorObj = changeVector(rotationVectorObj, 0, 0, 0, rotationVector.x, rotationVector.y, rotationVector.z, 0xff9900);
// rotate drone
drone.rotation.set(0, 0, 0);
drone.rotateOnAxis(rotationAxis, rotationAngle);
// update labels
angleEl.innerHTML = `<b>Угол вращения:</b> ${parseFloat(angleInput.value).toFixed(0)}° = ${(rotationAngle).toFixed(2)} рад`;
rotationVectorEl.innerHTML = `<b style='color:#e49a44'>Вектор вращения:</b> (${rotationVector.x.toFixed(1)}, ${rotationVector.y.toFixed(1)}, ${rotationVector.z.toFixed(1)}) рад`;
let quaternion = new THREE.Quaternion();
quaternion.setFromAxisAngle(rotationAxis, rotationAngle);
quaternionEl.innerHTML = `<b>Кватернион:</b>
<math xmlns="http://www.w3.org/1998/Math/MathML">
<mrow>
<mo>(</mo>
<mrow>
<mi>cos</mi>
<mo>(</mo>
<mfrac>
<mi>${rotationAngle.toFixed(2)}</mi>
<mn>2</mn>
</mfrac>
<mo>)</mo>
</mrow>
<mo>, </mo>
<mrow>
<mi>${rotationAxis.x.toFixed(1)}</mi>
<mo>·</mo>
<mi>sin</mi>
<mo>(</mo>
<mfrac>
<mi>${rotationAngle.toFixed(2)}</mi>
<mn>2</mn>
</mfrac>
<mo>)</mo>
</mrow>
<mo>, </mo>
<mrow>
<mi>${rotationAxis.y.toFixed(1)}</mi>
<mo>·</mo>
<mi>sin</mi>
<mo>(</mo>
<mfrac>
<mi>${rotationAngle.toFixed(2)}</mi>
<mn>2</mn>
</mfrac>
<mo>)</mo>
</mrow>
<mo>,</mo>
<mrow>
<mi>${rotationAxis.z.toFixed(1)}</mi>
<mo>·</mo>
<mi>sin</mi>
<mo>(</mo>
<mfrac>
<mi>${rotationAngle.toFixed(2)}</mi>
<mn>2</mn>
</mfrac>
<mo>)</mo>
</mrow>
<mo>)</mo>
</mrow>
</math>
= (${quaternion.w.toFixed(1)}, ${(quaternion.x).toFixed(1)}, ${(quaternion.y).toFixed(1)}, ${(quaternion.z).toFixed(1)})`;
eulerEl.innerHTML = `<b>Углы Эйлера:</b> крен ${(drone.rotation.x * 180 / Math.PI).toFixed(0)}°,
тангаж ${(drone.rotation.y * 180 / Math.PI).toFixed(0)}°, рыскание ${(drone.rotation.z * 180 / Math.PI).toFixed(0)}°`;
}
function updateCamera() {
const RANGE = 8;
const VERT_SHIFT = 2;
const HOR_SHIFT = -2;
const width = renderer.domElement.clientWidth;
const height = renderer.domElement.clientHeight;
const ratio = width / height;
if (ratio > 1) {
camera.left = -RANGE * ratio;
camera.right = RANGE * ratio;
camera.top = RANGE + VERT_SHIFT;
camera.bottom = -RANGE + VERT_SHIFT;
} else {
camera.left = -RANGE + HOR_SHIFT;
camera.right = RANGE + HOR_SHIFT;
camera.top = RANGE / ratio + VERT_SHIFT;
camera.bottom = -RANGE / ratio + VERT_SHIFT;
}
camera.updateProjectionMatrix();
renderer.setSize(width, height);
}
function update() {
// requestAnimationFrame(update);
updateCamera();
updateScene();
controls.update();
renderer.render(scene, camera);
}
update();
window.addEventListener('resize', update);
angleInput.addEventListener('input', update);
angleInput.addEventListener('change', update);
diagramEl.addEventListener('mousemove', update);
diagramEl.addEventListener('touchmove', update);
diagramEl.addEventListener('scroll', update);
diagramEl.addEventListener('wheel', update);

View File

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

175
docs/build.md Normal file
View File

@@ -0,0 +1,175 @@
# Building and running
To build the firmware or the simulator, you need to clone the repository using git:
```bash
git clone https://github.com/okalachev/flix.git
cd flix
```
## Simulation
### Ubuntu
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 and flight
#### 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. 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 and stop the simulation.
4. Copy the calibration results to the source code (`gazebo/joystick.h`).
5. Run the simulation again.
6. Use the USB remote control to fly the drone!
## Firmware
### Arduino IDE (Windows, Linux, macOS)
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).
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.
### Command line (Windows, Linux, macOS)
1. [Install Arduino CLI](https://arduino.github.io/arduino-cli/installation/).
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. Compile the firmware using `make`. Arduino dependencies will be installed automatically:
```bash
make
```
You can flash the firmware to the board using command:
```bash
make upload
```
You can also compile the firmware, upload it and start serial port monitoring using command:
```bash
make upload monitor
```
See other available Make commands in the [Makefile](../Makefile).
### Setup and flight
Before flight you need to calibrate the accelerometer:
1. Open Serial Monitor in Arduino IDE (use use `make monitor` command in the command line).
2. Type `ca` command there.
3. Copy calibration results to the source code (`flix/imu.ino`).
#### 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.
3. Connect your smartphone to the appeared `flix` Wi-Fi network.
4. Open QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
5. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
6. Use the virtual joystick to fly the drone!
#### Control with remote control
Before flight using remote control, you need to calibrate it:
1. Open Serial Monitor in Arduino IDE (use use `make monitor` command in the command line).
2. Type `cr` command there.
3. Copy calibration results to the source code (`flix/rc.ino`).
Then you can use your remote control to fly the drone!
> [!NOTE]
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.
### Firmware code structure
See [firmware overview](firmware.md) for more details.

View File

@@ -1,56 +1,37 @@
# Firmware overview
The firmware is a regular Arduino sketch, and it follows the classic Arduino one-threaded design. The initialization code is in the `setup()` function, and the main loop is in the `loop()` function. The sketch includes several files, each responsible for a specific subsystem.
## Dataflow
<img src="img/dataflow.svg" width=600 alt="Firmware dataflow diagram">
<img src="img/dataflow.svg" width=800 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. All the dataflow is happening through global variables (for simplicity):
* `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`, ... *(float[])* pilot's control inputs, range [-1, 1].
* `motors` *(float[])* motor outputs, normalized to [0, 1] range; reverse rotation is possible.
## Source files
Firmware source files are located in `flix` directory. The core files are:
Firmware source files are located in `flix` directory. The key files are:
* [`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) — main entry point, Arduino sketch. Includes global variables definition and the main loop.
* [`imu.ino`](../flix/imu.ino) — reading data from the IMU sensor (gyroscope and accelerometer), IMU calibration.
* [`rc.ino`](../flix/rc.ino) — reading data from the RC receiver, RC calibration.
* [`estimate.ino`](../flix/estimate.ino) — attitude estimation, complementary filter.
* [`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.
* [`estimate.ino`](../flix/estimate.ino) — drone's attitude estimation, complementary filter.
* [`control.ino`](../flix/control.ino) — drone's attitude and rates control, three-dimensional two-level cascade PID controller.
* [`motors.ino`](../flix/motors.ino) — PWM motor outputs control.
Utility files:
Utility files include:
* [`vector.h`](../flix/vector.h), [`quaternion.h`](../flix/quaternion.h) — vector and quaternion libraries.
* [`pid.h`](../flix/pid.h) — generic PID controller.
* [`lpf.h`](../flix/lpf.h) — generic low-pass filter.
### Control subsystem
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.
* `ratesTarget` *(Vector)* — target angular rates, *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].
* `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`.
<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.
* [`vector.h`](../flix/vector.h), [`quaternion.h`](../flix/quaternion.h) — project's vector and quaternion libraries implementation.
* [`pid.h`](../flix/pid.h) — generic PID controller implementation.
* [`lpf.h`](../flix/lpf.h) — generic low-pass filter implementation.
## Building
See build instructions in [usage.md](usage.md).
See build instructions in [build.md](build.md).

View File

@@ -1,22 +0,0 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 340.21 211.28">
<defs>
<style>
.a {
fill: #d5d5d5;
}
.b {
fill: #fff;
}
.c {
fill: #636363;
}
</style>
</defs>
<path class="a" d="M340,159.31c-4.74-86-35.9-128.7-35.9-128.7C288.3,9.53,269.17,2.91,251.87.39s-22.31,7.87-22.31,7.87C201.7,4,170.11,4.19,170.11,4.19S138.51,4,110.65,8.26c0,0-5-10.38-22.3-7.87S51.91,9.53,36.14,30.61c0,0-31.16,42.67-35.9,128.7-2.82,51.08,19.68,55.36,38.43,50.4a60.08,60.08,0,0,0,30.55-19.66c7.51-9,19.64-25.32,34-28,17.28-3.26,33.14-4.77,45.09-4.78l21.82,0,21.81,0c12,0,27.82,1.52,45.09,4.78,14.34,2.71,26.47,19,34,28a60.06,60.06,0,0,0,30.56,19.66C320.29,214.67,342.79,210.39,340,159.31Z"/>
<circle class="b" cx="88.54" cy="85.75" r="45.22"/>
<circle class="b" cx="251.67" cy="85.75" r="45.22"/>
<circle class="c" cx="251.67" cy="85.75" r="13.8"/>
<circle class="c" cx="103.8" cy="112.12" r="13.8"/>
</svg>

Before

Width:  |  Height:  |  Size: 971 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 157 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 79 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 115 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 169 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 147 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 99 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 152 KiB

View File

@@ -1,94 +0,0 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 533 646.91">
<defs>
<style>
.a {
font-size: 50px;
font-family: Tahoma;
}
.b {
opacity: 0.8;
}
.c, .e, .g, .i {
fill: none;
}
.c {
stroke: #0076ba;
}
.c, .e, .g {
stroke-linejoin: bevel;
stroke-width: 13px;
}
.d {
fill: #0076ba;
}
.e {
stroke: #d80100;
}
.f {
fill: #d80100;
}
.g {
stroke: #57ed00;
}
.h {
fill: #57ed00;
}
.i {
stroke: #000;
stroke-miterlimit: 10;
stroke-width: 10px;
}
</style>
</defs>
<g>
<text class="a" transform="translate(58.62 636.12)">x</text>
<text class="a" transform="translate(505.06 562.18)">y</text>
<text class="a" transform="translate(370.06 43.18)">z</text>
<g class="b">
<g>
<line class="c" x1="347" y1="420.2" x2="347" y2="61.78"/>
<polygon class="d" points="370.34 68.61 347 28.2 323.66 68.61 370.34 68.61"/>
</g>
</g>
<g class="b">
<g>
<line class="e" x1="347" y1="420.2" x2="29.31" y2="597.81"/>
<polygon class="f" points="23.89 574.11 0 614.2 46.66 614.84 23.89 574.11"/>
</g>
</g>
<g class="b">
<g>
<line class="g" x1="347" y1="420.2" x2="503.22" y2="501.67"/>
<polygon class="h" points="486.38 519.2 533 517.2 507.96 477.82 486.38 519.2"/>
</g>
</g>
<g class="b">
<g>
<path class="i" d="M103.19,617.68a52.66,52.66,0,1,0-55.51-89.19"/>
<polygon points="41.63 516.97 34.76 541.97 59.85 535.42 41.63 516.97"/>
</g>
</g>
<g class="b">
<g>
<path class="i" d="M295.58,87.51a52.66,52.66,0,1,0,103.78,16.31"/>
<polygon points="412.03 106.78 397.6 85.24 386.16 108.51 412.03 106.78"/>
</g>
</g>
<g class="b">
<g>
<path class="i" d="M505,452.58a52.66,52.66,0,1,0-76,72.53"/>
<polygon points="418.96 533.38 444.84 535 433.31 511.78 418.96 533.38"/>
</g>
</g>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 2.1 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 26 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 33 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 28 KiB

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 140 KiB

View File

@@ -1,123 +0,0 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 464.2 249.05">
<defs>
<style>
.a {
fill: #d5d5d5;
}
.b {
fill: #fff;
}
.c {
fill: #636363;
}
.d {
opacity: 0.7;
}
.e {
fill: none;
stroke: #0076ba;
stroke-linecap: round;
stroke-miterlimit: 10;
stroke-width: 13px;
}
.f {
fill: #0076ba;
}
.g {
font-size: 30px;
font-family: Tahoma;
}
.h {
letter-spacing: 0em;
}
.i {
letter-spacing: -0.01em;
}
.j {
letter-spacing: -0.06em;
}
.k {
letter-spacing: 0em;
}
.l {
letter-spacing: -0.02em;
}
.m {
letter-spacing: 0em;
}
.n {
opacity: 0.6;
}
</style>
</defs>
<path class="a" d="M408.84,197.08c-4.74-86-35.9-128.7-35.9-128.7C357.17,47.3,338,40.68,320.73,38.17S298.43,46,298.43,46C270.57,41.81,239,42,239,42s-31.59-.15-59.45,4.07c0,0-5-10.38-22.31-7.86S120.78,47.3,105,68.38c0,0-31.16,42.68-35.9,128.7-2.82,51.08,19.68,55.36,38.42,50.4a60.06,60.06,0,0,0,30.56-19.66c7.51-9,19.64-25.32,34-28,17.27-3.26,33.14-4.77,45.09-4.78L239,195l21.82,0c11.95,0,27.81,1.52,45.09,4.78,14.34,2.71,26.47,19,34,28a60.08,60.08,0,0,0,30.55,19.66C389.16,252.44,411.66,248.16,408.84,197.08Z"/>
<circle class="b" cx="157.41" cy="123.52" r="45.22"/>
<circle class="b" cx="320.54" cy="123.52" r="45.22"/>
<circle class="c" cx="320.54" cy="123.52" r="13.8"/>
<circle class="c" cx="157.41" cy="149.89" r="13.8"/>
<g class="d">
<g>
<line class="e" x1="157.41" y1="149.89" x2="157.41" y2="49.87"/>
<polygon class="f" points="180.74 56.7 157.41 16.29 134.07 56.7 180.74 56.7"/>
</g>
</g>
<text class="g" transform="translate(38.38 25.91)">Th<tspan class="h" x="34.25" y="0">r</tspan><tspan x="44.91" y="0">o</tspan><tspan class="i" x="61.2" y="0">t</tspan><tspan x="71" y="0">tle</tspan></text>
<g class="d">
<g>
<line class="e" x1="157.41" y1="149.89" x2="82.41" y2="149.89"/>
<polygon class="f" points="89.24 126.56 48.82 149.89 89.24 173.23 89.24 126.56"/>
</g>
</g>
<text class="g" transform="translate(0.18 176.36)"><tspan class="j">Y</tspan><tspan class="h" x="15.37" y="0">a</tspan><tspan x="30.97" y="0">w</tspan></text>
<g class="d">
<g>
<line class="e" x1="320.54" y1="123.52" x2="320.54" y2="50.32"/>
<polygon class="f" points="343.88 57.15 320.54 16.74 297.2 57.15 343.88 57.15"/>
</g>
</g>
<text class="g" transform="translate(336.56 26.36)">P<tspan class="k" x="16.54" y="0">i</tspan><tspan x="23.45" y="0">tch</tspan></text>
<g class="d">
<g>
<line class="e" x1="320.54" y1="123.52" x2="395.54" y2="123.52"/>
<polygon class="f" points="388.71 146.86 429.12 123.52 388.71 100.19 388.71 146.86"/>
</g>
</g>
<text class="g" transform="translate(416.03 160.01)"><tspan class="l">R</tspan><tspan x="18.08" y="0">o</tspan><tspan class="m" x="34.37" y="0">l</tspan><tspan x="41.31" y="0">l</tspan></text>
<g class="d">
<g>
<line class="e" x1="157.41" y1="149.89" x2="213.73" y2="149.89"/>
<polygon class="f" points="206.9 173.23 247.32 149.89 206.9 126.56 206.9 173.23"/>
</g>
</g>
<g class="d">
<g>
<line class="e" x1="320.54" y1="124.52" x2="320.54" y2="197.73"/>
<polygon class="f" points="297.2 190.9 320.54 231.31 343.88 190.9 297.2 190.9"/>
</g>
</g>
<g class="n">
<g>
<line class="e" x1="318.03" y1="123.52" x2="262.32" y2="123.52"/>
<polygon class="f" points="269.14 100.19 228.73 123.52 269.14 146.86 269.14 100.19"/>
</g>
</g>
<g class="d">
<g>
<line class="e" x1="157.41" y1="151.66" x2="157.41" y2="197.73"/>
<polygon class="f" points="134.07 190.9 157.41 231.31 180.74 190.9 134.07 190.9"/>
</g>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 3.9 KiB

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 101 KiB

After

Width:  |  Height:  |  Size: 22 KiB

View File

@@ -1,22 +0,0 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 340.21 211.28">
<defs>
<style>
.a {
fill: #d5d5d5;
}
.b {
fill: #fff;
}
.c {
fill: #636363;
}
</style>
</defs>
<path class="a" d="M340,159.31c-4.74-86-35.9-128.7-35.9-128.7C288.3,9.53,269.17,2.91,251.87.39s-22.31,7.87-22.31,7.87C201.7,4,170.11,4.19,170.11,4.19S138.51,4,110.65,8.26c0,0-5-10.38-22.3-7.87S51.91,9.53,36.14,30.61c0,0-31.16,42.67-35.9,128.7-2.82,51.08,19.68,55.36,38.43,50.4a60.08,60.08,0,0,0,30.55-19.66c7.51-9,19.64-25.32,34-28,17.28-3.26,33.14-4.77,45.09-4.78l21.82,0,21.81,0c12,0,27.82,1.52,45.09,4.78,14.34,2.71,26.47,19,34,28a60.06,60.06,0,0,0,30.56,19.66C320.29,214.67,342.79,210.39,340,159.31Z"/>
<circle class="b" cx="88.54" cy="85.75" r="45.22"/>
<circle class="b" cx="251.67" cy="85.75" r="45.22"/>
<circle class="c" cx="251.67" cy="85.75" r="13.8"/>
<circle class="c" cx="73.28" cy="112.12" r="13.8"/>
</svg>

Before

Width:  |  Height:  |  Size: 971 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 123 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 17 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 30 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 115 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 114 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 105 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 36 KiB

View File

@@ -1,119 +0,0 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 544.13 637.15">
<defs>
<style>
.a {
fill: #dbe1e2;
}
.b {
fill: #c2c1c0;
}
.c {
fill: #c6c6c5;
}
.d {
fill: #ec7d23;
}
.e {
font-size: 50px;
font-family: Tahoma;
}
.e, .n {
fill: #010101;
}
.f {
opacity: 0.8;
}
.g, .i, .k, .m {
fill: none;
stroke-width: 10px;
}
.g {
stroke: #0577ba;
}
.g, .i, .k {
stroke-linejoin: bevel;
}
.h {
fill: #0577ba;
}
.i {
stroke: #76c043;
}
.j {
fill: #76c043;
}
.k {
stroke: #d71f26;
}
.l {
fill: #d71f26;
}
.m {
stroke: #010101;
stroke-miterlimit: 10;
}
</style>
</defs>
<g>
<g>
<rect class="a" x="51.25" y="538.09" width="111.96" height="44.06"/>
<polygon class="b" points="204.47 515.98 163.21 582.15 163.21 538.09 204.47 471.91 204.47 515.98"/>
<polygon class="c" points="163.21 538.19 51.25 538.19 92.46 471.91 204.42 471.91 163.21 538.19"/>
<ellipse class="d" cx="101.09" cy="480" rx="7.45" ry="3.7" transform="translate(-117.09 40.67) rotate(-14.52)"/>
</g>
<text class="e" transform="translate(166.62 107.43)">Z</text>
<g class="f">
<g>
<line class="g" x1="127.84" y1="505.05" x2="127.84" y2="70.04"/>
<polygon class="h" points="145.79 75.3 127.84 44.21 109.89 75.3 145.79 75.3"/>
</g>
</g>
<g class="f">
<g>
<line class="i" x1="127.84" y1="505.05" x2="315.74" y2="203.61"/>
<polygon class="j" points="328.2 217.57 329.41 181.69 297.73 198.57 328.2 217.57"/>
</g>
</g>
<text class="e" transform="translate(338.14 279.7)">Y</text>
<g class="f">
<g>
<line class="k" x1="127.94" y1="504.62" x2="467.04" y2="504.62"/>
<polygon class="l" points="461.79 522.58 492.87 504.62 461.79 486.67 461.79 522.58"/>
</g>
</g>
<text class="e" transform="translate(438.99 582.15)">X</text>
<g class="f">
<g>
<path class="m" d="M80,98.74a52.66,52.66,0,1,0,98.43,36.72"/>
<polygon class="n" points="190.29 140.9 180.45 116.91 164.59 137.41 190.29 140.9"/>
</g>
</g>
<g class="f">
<g>
<path class="m" d="M474,467.75a52.66,52.66,0,1,0-59.23,86.77"/>
<polygon class="n" points="406.68 564.7 432.32 560.9 416.21 540.59 406.68 564.7"/>
</g>
</g>
<g class="f">
<g>
<path class="m" d="M222.38,257.69a52.66,52.66,0,1,1,93.83,47.25"/>
<polygon class="n" points="308.22 293.44 303.95 319.01 328.23 309.93 308.22 293.44"/>
</g>
</g>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 2.8 KiB

View File

@@ -1,67 +0,0 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 533 646.68">
<defs>
<style>
.a {
font-size: 50px;
font-family: Tahoma;
}
.b {
opacity: 0.8;
}
.c, .e, .g {
fill: none;
stroke-linejoin: bevel;
stroke-width: 13px;
}
.c {
stroke: #0076ba;
}
.d {
fill: #0076ba;
}
.e {
stroke: #57ed00;
}
.f {
fill: #57ed00;
}
.g {
stroke: #d80100;
}
.h {
fill: #d80100;
}
</style>
</defs>
<g>
<text class="a" transform="translate(500.62 556.12)">x</text>
<text class="a" transform="translate(370.06 43.18)">z</text>
<g class="b">
<g>
<line class="c" x1="347" y1="420.2" x2="347" y2="61.78"/>
<polygon class="d" points="370.34 68.61 347 28.2 323.66 68.61 370.34 68.61"/>
</g>
</g>
<g class="b">
<g>
<line class="e" x1="347" y1="420.2" x2="29.31" y2="597.81"/>
<polygon class="f" points="23.89 574.11 0 614.2 46.66 614.84 23.89 574.11"/>
</g>
</g>
<g class="b">
<g>
<line class="g" x1="347" y1="420.2" x2="503.22" y2="501.67"/>
<polygon class="h" points="486.38 519.2 533 517.2 507.96 477.82 486.38 519.2"/>
</g>
</g>
<text class="a" transform="translate(58.06 635.89)">y</text>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 1.4 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 26 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 12 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 24 KiB

View File

@@ -1,67 +0,0 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 533 646.91">
<defs>
<style>
.a {
opacity: 0.8;
}
.b, .d, .f {
fill: none;
stroke-linejoin: bevel;
stroke-width: 13px;
}
.b {
stroke: #57ed00;
}
.c {
fill: #57ed00;
}
.d {
stroke: #d80100;
}
.e {
fill: #d80100;
}
.f {
stroke: #0076ba;
}
.g {
fill: #0076ba;
}
.h {
font-size: 50px;
font-family: Tahoma;
}
</style>
</defs>
<g>
<g class="a">
<g>
<line class="b" x1="347" y1="420.2" x2="503.22" y2="501.67"/>
<polygon class="c" points="486.38 519.2 533 517.2 507.96 477.82 486.38 519.2"/>
</g>
</g>
<g class="a">
<g>
<line class="d" x1="347" y1="420.2" x2="29.31" y2="597.81"/>
<polygon class="e" points="23.89 574.11 0 614.2 46.66 614.84 23.89 574.11"/>
</g>
</g>
<g class="a">
<g>
<line class="f" x1="347" y1="420.2" x2="347" y2="61.78"/>
<polygon class="g" points="370.34 68.61 347 28.2 323.66 68.61 370.34 68.61"/>
</g>
</g>
<text class="h" transform="translate(58.62 636.12)">x</text>
<text class="h" transform="translate(505.06 562.18)">y</text>
<text class="h" transform="translate(370.06 43.18)">z</text>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 1.4 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 326 KiB

View File

Before

Width:  |  Height:  |  Size: 36 KiB

After

Width:  |  Height:  |  Size: 36 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 68 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 40 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 45 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 51 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 52 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 44 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 54 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 78 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 76 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 29 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 40 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 40 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 49 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 35 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 36 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 43 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 24 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 45 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 54 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 30 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 43 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 70 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 18 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 33 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 40 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 83 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 58 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 74 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 56 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 57 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 49 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 78 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 20 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 148 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 73 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 58 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 66 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 9.8 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 87 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 50 KiB

Some files were not shown because too many files have changed in this diff Show More