82 Commits

Author SHA1 Message Date
Oleg Kalachev
073c860b90 Calibrate gyro continuously when landed and stationary 2024-12-24 22:19:54 +03:00
Oleg Kalachev
fd30027ea4 Support AUTOPILOT_VERSION message request to make qgc connection faster
Don't have to wait until the request is timed out.
2024-12-23 17:59:35 +03:00
Oleg Kalachev
6f190295cf Fix building article regarding new parameters subsystem 2024-12-23 13:59:44 +03:00
Oleg Kalachev
ae349fb73c Implement parameters subsystem
* Unified parameters storage.
* Store parameters in flash on the hardware.
* Store parameters in text file in simulation.
* Work with parameters in command line.
* Support parameters in MAVLink for working with parameters in QGC.
2024-12-23 13:00:02 +03:00
Oleg Kalachev
28f6cfff60 Fix SBUS simulation logic
Don't consider zero values from not connected joystick
2024-12-23 04:04:00 +03:00
Oleg Kalachev
7533a9cbfa Move ONE_G definition to flix.ino 2024-12-23 02:37:03 +03:00
Oleg Kalachev
3cc3014ca0 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-23 02:04:22 +03:00
Oleg Kalachev
b6286a50b2 Minor change 2024-12-23 02:01:55 +03:00
Oleg Kalachev
4f2cf0c0b1 Don't let throttle be less than 0 in failsafe 2024-12-23 01:32:25 +03:00
Oleg Kalachev
f06a9301df Add notice on removing props in motor test commands in help 2024-12-23 01:14:05 +03:00
Oleg Kalachev
41cde3261a Minor troubleshooting article fix 2024-12-21 13:53:04 +03:00
Oleg Kalachev
f54da5bf42 Add CLI command for rebooting the drone 2024-12-20 20:59:59 +03:00
Oleg Kalachev
d01d5b7ecb Improve Markdown linting
* Move .markdownlint to the root so it applies to the main readme.
* Improve .markdownlint, enable proper names checks.
* Use markdownlint-cli2 instead of markdownlint-cli as it's more compatible with VSCode extension.
2024-12-17 17:16:19 +03:00
Oleg Kalachev
0608765347 Add link to textbook website to readme 2024-12-17 11:27:14 +03:00
Oleg Kalachev
b70d16c1f7 Update deploy-pages version to fix website deploy 2024-12-16 12:13:36 +03:00
Oleg Kalachev
f7253bed70 Temporarily disable macOS simulation build 2024-12-16 11:59:49 +03:00
Oleg Kalachev
9957205d8f Fix website deploy 2024-12-16 11:58:35 +03:00
Oleg Kalachev
8440ddd3ee Create book and deploy it to the website (#6)
* Create book structure.
* Add workflow for linting the markdown using markdownlint.
* Add workflow for building the book with mdBook and deploying to the website.
* Restyle mdBook and support GitHub-style alerts.
* Add images zooming.
* Add index, firmware structure and gyroscope articles.
2024-12-16 11:53:43 +03:00
Oleg Kalachev
66ba9518ae Minor readme fix 2024-12-16 11:30:53 +03:00
Oleg Kalachev
d273b77ce2 Bring back macOS simulation build in Actions 2024-12-12 09:07:09 +03:00
Oleg Kalachev
77effa5577 Rotate IMU data to support standard axes orientation in new FlixPeriph 2024-12-11 06:17:37 +03:00
Oleg Kalachev
fcb426a16f Update MAVLink-Arduino to 2.0.11 2024-12-09 08:04:36 +03:00
Oleg Kalachev
eea1a6a83c Minor fix in troubleshooting article 2024-12-08 07:40:24 +03:00
Oleg Kalachev
9d470cbdfa Add info on required version of Ubuntu for the simulation 2024-12-05 09:28:44 +03:00
Oleg Kalachev
6e140d673c Cleanup unused utility functions 2024-12-05 08:29:21 +03:00
Oleg Kalachev
c75760e9e6 Some readme change regarding using different IMU board 2024-12-04 23:00:26 +03:00
Oleg Kalachev
172b6becc6 Use new FlixPeriph library with ICM-20948 support 2024-12-04 14:41:23 +03:00
Oleg Kalachev
475e9a87ba Configure IMU before calibrating the gyro which improves calibration 2024-12-04 12:25:07 +03:00
Oleg Kalachev
ea141f851f Use 'loop rate' term instead of misleading 'loop frequency' 2024-12-04 07:00:00 +03:00
Oleg Kalachev
7fa3baa76a Add some minor clarification under the IMU orientation picture 2024-11-30 04:59:04 +03:00
Oleg Kalachev
2c5eac92ea Add diagram for IMU orientation 2024-11-29 10:14:11 +03:00
Oleg Kalachev
048a3c6375 Use the new UART2 pins for RC by default
To make it consistent with the documentation
2024-11-27 23:02:20 +03:00
Oleg Kalachev
a65ec946c0 Update ESP32 core to 3.0.7 2024-11-24 01:45:41 +03:00
Oleg Kalachev
429aecbbad Temporarily disable macOS simulation build in CI 2024-11-24 01:08:03 +03:00
Oleg Kalachev
a7b69f99d0 Fix non-working motor control commands 2024-11-24 00:17:47 +03:00
Oleg Kalachev
b015c15a7e Remove non-working fullmot command 2024-11-24 00:10:37 +03:00
Oleg Kalachev
7a2f2d955b Minor fix to the troubleshooting 2024-11-23 18:18:19 +03:00
Oleg Kalachev
c611549f67 Update link to the troubleshooting article 2024-11-23 18:16:46 +03:00
Oleg Kalachev
be3c5bf312 Add troubleshooting article 2024-11-23 18:13:41 +03:00
Oleg Kalachev
f6ddeb4689 Clarify GY-91 pin names 2024-11-12 21:02:47 +03:00
Oleg Kalachev
f6006d3305 Fix c_cpp_properties.json to match updated ESP32 core version 2024-11-04 16:35:22 +03:00
Oleg Kalachev
eca48c6546 Minor fix 2024-11-04 16:28:54 +03:00
Oleg Kalachev
cd5f6721dc Updates to LED control code
Don't call digitaWrite on each setLED call
2024-11-04 16:28:43 +03:00
Oleg Kalachev
e7445599cc Update core and libraries to the most recent versions 2024-11-04 16:28:13 +03:00
Oleg Kalachev
6327585754 Print accel calibration parameters in more convenient way 2024-11-04 14:37:05 +03:00
Oleg Kalachev
ec832d4e37 Implement RC fail-safe 2024-11-04 11:51:17 +03:00
Oleg Kalachev
2fdad7bdb6 Remove LED horizontality signalization
It's better to control the attitude estimation using QGC
2024-11-03 17:41:13 +03:00
Oleg Kalachev
c5c889679b Fix simulation build 2024-10-31 19:27:27 +03:00
Oleg Kalachev
ad2c64625c Print the IMU information in imu command 2024-10-31 10:24:00 +03:00
Oleg Kalachev
39d4f39932 Some updates in docs 2024-10-30 09:45:27 +03:00
Oleg Kalachev
57fe3fef2a Upload STEP files for models 2024-10-29 14:18:03 +03:00
Oleg Kalachev
4ba9accf4b Fix image for washer-m3 model 2024-10-29 14:04:42 +03:00
Oleg Kalachev
99c891e1cd Add explanation on installing the right ESP32 core in build insutrctions 2024-10-27 11:07:53 +03:00
Oleg Kalachev
378db51de9 Get rid of simulator build warnings 2024-10-24 03:50:03 +03:00
Oleg Kalachev
8a83d70bb6 Update MAVLink-Arduino to 2.0.10 2024-10-24 03:49:28 +03:00
Oleg Kalachev
ba5ac30136 Adjust the default camera position in the simulator 2024-10-24 03:48:31 +03:00
Oleg Kalachev
baf724ed6e Minor README fixes 2024-10-23 14:45:57 +03:00
Oleg Kalachev
af58d56138 README fixes 2024-10-23 14:35:28 +03:00
Oleg Kalachev
13341602f0 Fix Gazebo stl model orientation 2024-10-23 14:30:25 +03:00
Oleg Kalachev
84368738b4 Major documentation update, the new drone version files released 2024-10-23 10:17:47 +03:00
Oleg Kalachev
0397b3a736 Move the visual part of the gazebo model to the bottom of the file 2024-10-23 09:42:17 +03:00
Oleg Kalachev
c41c96a96d Update visual of the Gazebo model to the new version
Use STL instead of DAE, make props separated visuals
2024-10-23 09:41:16 +03:00
Oleg Kalachev
a94687bd56 Keep the t variable monotonic in the simulation
Otherwise it causes stopping sending MAVLink and other bugs
2024-10-23 09:36:54 +03:00
Oleg Kalachev
abcc9b96de Use FLU as the main coordinate system instead of FRD
Corresponding to the IMU orientation in the new version
2024-10-23 09:30:49 +03:00
Oleg Kalachev
f46460e53d Make RC_CHANNELS=16 corresponding the number of SBUS channels 2024-10-23 09:28:09 +03:00
Oleg Kalachev
23f3295439 Remove ESC support and add MOSFET support in motors code
The new version uses MOSFETs
2024-10-23 09:27:54 +03:00
Oleg Kalachev
b0b6eb9a97 Minor code cleanups and clarifications 2024-10-23 09:25:39 +03:00
Oleg Kalachev
84a329cca7 More clean yaw error calculation 2024-10-23 09:25:07 +03:00
Oleg Kalachev
5613028678 Enable Wi-Fi by default 2024-10-23 09:24:58 +03:00
Oleg Kalachev
a0cca80980 Some fixes to VSCode config 2024-07-30 09:28:20 +03:00
Oleg Kalachev
bed5d79db8 Add comments to motor pins 2024-07-30 07:49:21 +03:00
Oleg Kalachev
da51ebab38 Add some C++ code style settings to VSCode settings 2024-07-30 07:46:40 +03:00
Oleg Kalachev
0b977aee28 Add json rules to .editorconfig 2024-07-30 07:46:15 +03:00
Oleg Kalachev
6ef8820770 Add VSCode configuration 2024-07-25 06:51:47 +03:00
Oleg Kalachev
e993dde355 Update ESP32 Arduino Core to v3.0.3 2024-07-25 02:45:59 +03:00
Oleg Kalachev
627233f862 Minor updates 2024-07-25 02:44:47 +03:00
Oleg Kalachev
ce87234a51 Add link to Android QGroundControl download to building instructions 2024-06-18 14:43:40 +03:00
Oleg Kalachev
e40fbd0ce2 Install arduino-cli without sudo in instructions 2024-06-18 13:51:07 +03:00
Oleg Kalachev
0938609dc7 Update checkout action to v4
v3 is deprecated
2024-06-12 03:26:17 +03:00
Oleg Kalachev
1a22350775 Add article on analyzing the logs 2024-06-02 11:46:32 +03:00
Oleg Kalachev
72b2cf49d5 Add tools for conversion svg logs to mcap 2024-06-02 01:45:49 +03:00
Oleg Kalachev
63d602dd7a Add C++ tool for conversion csv logs to ulog 2024-06-02 01:45:05 +03:00
95 changed files with 9553 additions and 307 deletions

View File

@@ -4,7 +4,7 @@ root = true
end_of_line = lf
insert_final_newline = true
[*.{ino,cpp,c,h,hpp,sdf,world}]
[*.{ino,cpp,c,h,hpp,sdf,world,json}]
charset = utf-8
indent_style = tab
tab_width = 4

View File

@@ -7,41 +7,47 @@ on:
branches: [ master ]
jobs:
build:
build_linux:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v3
- uses: actions/checkout@v4
- 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
run: make
- name: Check c_cpp_properties.json
run: tools/check_c_cpp_properties.py
build_macos:
runs-on: macos-latest
steps:
- uses: actions/checkout@v3
- uses: actions/checkout@v4
- name: Install Arduino CLI
run: brew install arduino-cli
- name: Build firmware
run: make
- name: Check c_cpp_properties.json
run: tools/check_c_cpp_properties.py
build_windows:
runs-on: windows-latest
steps:
- uses: actions/checkout@v3
- uses: actions/checkout@v4
- name: Install Arduino CLI
run: choco install arduino-cli
- name: Install Make
run: choco install make
- name: Build firmware
run: make
- name: Check c_cpp_properties.json
run: python3 tools/check_c_cpp_properties.py
build_simulator:
runs-on: ubuntu-latest
steps:
- name: Install Arduino CLI
uses: arduino/setup-arduino-cli@v1.1.1
- uses: actions/checkout@v3
- uses: actions/checkout@v4
- name: Install Gazebo
run: curl -sSL http://get.gazebosim.org | sh
- name: Install SDL2
@@ -54,22 +60,22 @@ jobs:
path: gazebo/build/*.so
retention-days: 1
build_simulator_macos:
runs-on: macos-latest
steps:
- name: Install Arduino CLI
run: brew install arduino-cli
- uses: actions/checkout@v3
- 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

51
.github/workflows/docs.yml vendored Normal file
View File

@@ -0,0 +1,51 @@
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

33
.github/workflows/tools.yml vendored Normal file
View File

@@ -0,0 +1,33 @@
name: Build tools
on:
push:
branches: [ '*' ]
pull_request:
branches: [ master ]
jobs:
csv_to_ulog:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- name: Build csv_to_ulog
run: cd tools/csv_to_ulog && mkdir build && cd build && cmake .. && make
- name: Test csv_to_ulog
run: |
cd tools/csv_to_ulog/build
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
python_tools:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- name: Install Python dependencies
run: pip install -r tools/requirements.txt
- name: Test csv_to_mcap tool
run: |
cd tools
echo -e "t,x,y,z\n0,1,2,3\n1,4,5,6" > log.csv
./csv_to_mcap.py log.csv
test $(stat -c %s log.mcap) -eq 883

7
.gitignore vendored
View File

@@ -3,3 +3,10 @@
build/
tools/log/
.dependencies
.vscode/*
!.vscode/settings.json
!.vscode/c_cpp_properties.json
!.vscode/tasks.json
!.vscode/launch.json
!.vscode/extensions.json
!.vscode/intellisense.h

67
.markdownlint.json Normal file
View File

@@ -0,0 +1,67 @@
{
"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",
"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
}

150
.vscode/c_cpp_properties.json vendored Normal file
View File

@@ -0,0 +1,150 @@
{
"configurations": [
{
"name": "Linux",
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/**",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include",
"~/Arduino/libraries/**",
"/usr/include/**"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32/Arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",
"${workspaceFolder}/flix/flix.ino",
"${workspaceFolder}/flix/imu.ino",
"${workspaceFolder}/flix/led.ino",
"${workspaceFolder}/flix/log.ino",
"${workspaceFolder}/flix/mavlink.ino",
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/util.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
],
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2302/bin/xtensa-esp32-elf-g++",
"cStandard": "c11",
"cppStandard": "c++17",
"defines": [
"F_CPU=240000000L",
"ARDUINO=10607",
"ARDUINO_D1_MINI32",
"ARDUINO_ARCH_ESP32",
"ARDUINO_BOARD=D1_MINI32",
"ARDUINO_VARIANT=d1_mini32",
"ARDUINO_PARTITION_default",
"ESP32",
"CORE_DEBUG_LEVEL=0",
"ARDUINO_USB_CDC_ON_BOOT="
]
},
{
"name": "Mac",
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/include/**",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include",
"~/Documents/Arduino/libraries/**",
"/opt/homebrew/include/**"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32/Arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/flix.ino",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",
"${workspaceFolder}/flix/imu.ino",
"${workspaceFolder}/flix/led.ino",
"${workspaceFolder}/flix/log.ino",
"${workspaceFolder}/flix/mavlink.ino",
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/util.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
],
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2302/bin/xtensa-esp32-elf-g++",
"cStandard": "c11",
"cppStandard": "c++17",
"defines": [
"F_CPU=240000000L",
"ARDUINO=10607",
"ARDUINO_D1_MINI32",
"ARDUINO_ARCH_ESP32",
"ARDUINO_BOARD=D1_MINI32",
"ARDUINO_VARIANT=d1_mini32",
"ARDUINO_PARTITION_default",
"ARDUINO_FQBN=esp32:esp32:d1_mini32",
"ESP32",
"CORE_DEBUG_LEVEL=0",
"ARDUINO_USB_CDC_ON_BOOT="
]
},
{
"name": "Win32",
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/**",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include",
"~/Documents/Arduino/libraries/**"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32/Arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",
"${workspaceFolder}/flix/flix.ino",
"${workspaceFolder}/flix/imu.ino",
"${workspaceFolder}/flix/led.ino",
"${workspaceFolder}/flix/log.ino",
"${workspaceFolder}/flix/mavlink.ino",
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/util.ino",
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
],
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2302/bin/xtensa-esp32-elf-g++.exe",
"cStandard": "c11",
"cppStandard": "c++17",
"defines": [
"F_CPU=240000000L",
"ARDUINO=10607",
"ARDUINO_D1_MINI32",
"ARDUINO_ARCH_ESP32",
"ARDUINO_BOARD=D1_MINI32",
"ARDUINO_VARIANT=d1_mini32",
"ARDUINO_PARTITION_default",
"ARDUINO_FQBN=esp32:esp32:d1_mini32",
"ESP32",
"CORE_DEBUG_LEVEL=0",
"ARDUINO_USB_CDC_ON_BOOT="
]
}
],
"version": 4
}

10
.vscode/extensions.json vendored Normal file
View File

@@ -0,0 +1,10 @@
{
// See https://go.microsoft.com/fwlink/?LinkId=827846 to learn about workspace recommendations.
"recommendations": [
"ms-vscode.cpptools",
"twxs.cmake",
"ms-vscode.cmake-tools",
"ms-python.python"
],
"unwantedRecommendations": []
}

5
.vscode/intellisense.h vendored Normal file
View File

@@ -0,0 +1,5 @@
#ifdef __INTELLISENSE__
#pragma diag_suppress 144, 513
// diag 144: a value of type "enum <unnamed>" cannot be used to initialize an entity of type "enum <unnamed>"C/C++
// diag 513: a value of type "enum <unnamed>" cannot be assigned to an entity of type "enum <unnamed>"C/C++
#endif

25
.vscode/launch.json vendored Normal file
View File

@@ -0,0 +1,25 @@
{
"version": "0.2.0",
"configurations": [
{
"name": "Debug simulation",
"type": "cppdbg",
"request": "launch",
"program": "/usr/bin/gzserver",
"osx": {
"program": "/opt/homebrew/bin/gzserver",
"MIMode": "lldb",
},
"args": ["--verbose", "${workspaceFolder}/gazebo/flix.world"],
"stopAtEntry": false,
"cwd": "${fileDirname}",
"environment": [
{"name": "GAZEBO_MODEL_PATH", "value": "${workspaceFolder}/gazebo/models"},
{"name": "GAZEBO_PLUGIN_PATH", "value": "${workspaceFolder}/gazebo/build"}
],
"MIMode": "gdb",
"preLaunchTask": "Build simulator",
"externalConsole": true,
},
]
}

13
.vscode/settings.json vendored Normal file
View File

@@ -0,0 +1,13 @@
{
"C_Cpp.intelliSenseEngineFallback": "enabled",
"files.associations": {
"*.sdf": "xml",
"*.ino": "cpp",
"*.h": "cpp"
},
"C_Cpp.vcFormat.newLine.beforeOpenBrace.function": "newLine",
"C_Cpp.vcFormat.newLine.beforeOpenBrace.block": "sameLine",
"C_Cpp.vcFormat.newLine.beforeOpenBrace.lambda": "sameLine",
"C_Cpp.vcFormat.newLine.beforeOpenBrace.namespace": "sameLine",
"C_Cpp.vcFormat.newLine.beforeOpenBrace.type": "sameLine"
}

31
.vscode/tasks.json vendored Normal file
View File

@@ -0,0 +1,31 @@
{
"tasks": [
{
"label": "Build firmware",
"type": "shell",
"command": "make",
"problemMatcher": [ "$gcc" ],
"presentation": { "clear": true, "showReuseMessage": false },
},
{
"label": "Upload firmware",
"type": "shell",
"command": "make upload",
"problemMatcher": [ "$gcc" ],
"presentation": { "clear": true, "showReuseMessage": false }
},
{
"label": "Build simulator",
"type": "shell",
"command": "make build_simulator",
"problemMatcher": [ "$gcc" ],
"presentation": { "clear": true, "showReuseMessage": false }
},
{
"label": "Clean",
"type": "shell",
"command": "make clean",
}
],
"version": "2.0.0"
}

View File

@@ -13,10 +13,10 @@ monitor:
dependencies .dependencies:
arduino-cli core update-index --config-file arduino-cli.yaml
arduino-cli core install esp32:esp32@2.0.11 --config-file arduino-cli.yaml
arduino-cli core install esp32:esp32@3.0.7 --config-file arduino-cli.yaml
arduino-cli lib update-index
arduino-cli lib install "FlixPeriph"
arduino-cli lib install "MAVLink"@2.0.1
arduino-cli lib install "MAVLink"@2.0.12
touch .dependencies
gazebo/build cmake: gazebo/CMakeLists.txt

153
README.md
View File

@@ -1,69 +1,156 @@
# flix
# Flix
**flix** (*flight + X*) — making an open source ESP32-based quadcopter from scratch.
**Flix** (*flight + X*) — making an open source ESP32-based quadcopter from scratch.
<img src="docs/img/flix.jpg" width=500 alt="Flix quadcopter">
<table>
<tr>
<td align=center><strong>Version 1</strong> (3D-printed frame)</td>
<td align=center><strong>Version 0</strong></td>
</tr>
<tr>
<td><img src="docs/img/flix1.jpg" width=500 alt="Flix quadcopter"></td>
<td><img src="docs/img/flix.jpg" width=500 alt="Flix quadcopter"></td>
</tr>
</table>
## Features
* Simple and clean Arduino based source code.
* Acro and Stabilized flight using remote control.
* Precise simulation using Gazebo.
* In-RAM logging.
* [In-RAM logging](docs/log.md).
* Command line interface through USB port.
* Wi-Fi support.
* MAVLink support.
* Control using mobile phone (with QGroundControl app).
* ESCs with reverse mode support.
* *Textbook and videos for students on writing a flight controller\*.*
* *Completely 3D-printed frame*.*
* *Position control and autonomous flights using external camera\**.
* Completely 3D-printed frame.
* Textbook for students on writing a flight controller ([in development](https://quadcopter.dev)).
* *Position control and autonomous flights using external camera¹*.
* [Building and running instructions](docs/build.md).
*\* — planned.*
*¹ — planned.*
## It actually flies
See detailed demo video (for version 0): https://youtu.be/8GzzIQ3C6DQ.
<a href="https://youtu.be/8GzzIQ3C6DQ"><img width=500 src="https://i3.ytimg.com/vi/8GzzIQ3C6DQ/maxresdefault.jpg"></a>
See YouTube demo video: https://youtu.be/8GzzIQ3C6DQ.
Version 1 test flight: https://t.me/opensourcequadcopter/42.
<a href="https://t.me/opensourcequadcopter/42"><img width=500 src="docs/img/flight-video.jpg"></a>
## Simulation
Simulation in Gazebo using a plugin that runs original Arduino code is implemented:
The simulator is implemented using Gazebo and runs the original Arduino code:
<img src="docs/img/simulator.png" width=500 alt="Flix simulator">
## Schematics
See [instructions on running the simulation](docs/build.md).
<img src="docs/img/schematics.svg" width=800 alt="Flix schematics">
## Components (version 1)
You can also check a user contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/) of the drone.
|Type|Part|Image|Quantity|
|-|-|:-:|:-:|
|Microcontroller board|ESP32 Mini|<img src="docs/img/esp32.jpg" width=100>|1|
|IMU (and barometer²) board|GY91 (or other MPU9250/MPU6500 board), ICM20948³|<img src="docs/img/gy-91.jpg" width=90 align=center><img src="docs/img/icm-20948.jpg" width=100>|1|
|Motor|8520 3.7V brushed motor (**shaft 0.8mm!**)|<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|
|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 bottom part|3D printed⁴:<br>[`flix-frame.stl`](docs/assets/flix-frame.stl) [`flix-frame.step`](docs/assets/flix-frame.step)|<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>|1|
|*RC transmitter (optional)*|*KINGKONG TINY X8 or other⁵*|<img src="docs/img/tx.jpg" width=100>|1|
|*RC receiver (optional)*|*DF500 or other⁵*|<img src="docs/img/rx.jpg" width=100>|1|
|Wires|28 AWG recommended|<img src="docs/img/wire-28awg.jpg" width=100>||
|Tape, double-sided tape||||
*\* — SBUS inverter is not needed as ESP32 supports [software pin inversion](https://github.com/bolderflight/sbus#inverted-serial).*
*² — barometer is not used for now.*<br>
*³ — change `MPU9250` to `ICM20948` in `imu.ino` file if using ICM-20948 board.*<br>
*⁴ — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*<br>
*⁵ — you may use any transmitter-receiver pair with SBUS interface.*
## Components (version 0)
Tools required for assembly:
|Component|Type|Image|Quantity|
|-|-|-|-|
|ESP32 Mini|Microcontroller board|<img src="docs/img/esp32.jpg" width=100>|1|
|GY-91|IMU+LDO+barometer board|<img src="docs/img/gy-91.jpg" width=100>|1|
|K100|Quadcopter frame|<img src="docs/img/frame.jpg" width=100>|1|
|8520 3.7V brushed motor (**shaft 0.8mm!**)|Motor|<img src="docs/img/motor.jpeg" width=100>|4|
|Hubsan 55 mm| Propeller|<img src="docs/img/prop.jpg" width=100>|4|
|2.7A 1S Dual Way Micro Brush ESC|Motor ESC|<img src="docs/img/esc.jpg" width=100>|4|
|KINGKONG TINY X8|RC transmitter|<img src="docs/img/tx.jpg" width=100>|1|
|DF500 (SBUS)|RC receiver|<img src="docs/img/rx.jpg" width=100>|1|
||~~SBUS inverter~~*|<img src="docs/img/inv.jpg" width=100>|~~1~~|
|3.7 Li-Po 850 MaH 60C|Battery|||
||Battery charger|<img src="docs/img/charger.jpg" width=100>|1|
||Wires, connectors, tape, ...|||
||3D-printed frame parts|||
* 3D printer.
* Soldering iron.
* Solder wire (with flux).
* Screwdrivers.
* Multimeter.
*\* — not needed as ESP32 supports [software pin inversion](https://github.com/bolderflight/sbus#inverted-serial).*
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 (version 1)
### 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">
Complete diagram is Work-in-Progress.
### 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|
|Motor 1|Rear right|Clockwise|Blue & Red|GPIO13|
|Motor 2|Front right|Counter-clockwise|Black & White|GPIO14|
|Motor 3|Front left|Clockwise|Blue & Red|GPIO15|
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|VC (or 3.3V depending on the receiver)|
|Signal|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.
## Version 0
See the information on the obsolete version 0 in the [corresponding article](docs/version0.md).
## Materials
Subscribe to Telegram-channel on developing the drone and the flight controller (in Russian): https://t.me/opensourcequadcopter.
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/.

10
docs/Makefile Normal file
View File

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

31
docs/alerts.py Normal file
View File

@@ -0,0 +1,31 @@
# 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))

File diff suppressed because it is too large Load Diff

Binary file not shown.

5113
docs/assets/flix-frame.step Normal file

File diff suppressed because it is too large Load Diff

BIN
docs/assets/flix-frame.stl Normal file

Binary file not shown.

200
docs/assets/washer-m3.step Normal file
View File

@@ -0,0 +1,200 @@
ISO-10303-21;
HEADER;
FILE_DESCRIPTION(
/* description */ (''),
/* implementation_level */ '2;1');
FILE_NAME(
/* name */ 'washer-m3.step',
/* time_stamp */ '2024-10-29T13:59:42+03:00',
/* author */ (''),
/* organization */ (''),
/* preprocessor_version */ '',
/* originating_system */ '',
/* authorisation */ '');
FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }'));
ENDSEC;
DATA;
#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#125);
#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#132,#12);
#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#124);
#13=STYLED_ITEM('',(#141),#14);
#14=MANIFOLD_SOLID_BREP('Body1',#65);
#15=FACE_BOUND('',#26,.T.);
#16=FACE_BOUND('',#28,.T.);
#17=PLANE('',#85);
#18=PLANE('',#86);
#19=FACE_OUTER_BOUND('',#23,.T.);
#20=FACE_OUTER_BOUND('',#24,.T.);
#21=FACE_OUTER_BOUND('',#25,.T.);
#22=FACE_OUTER_BOUND('',#27,.T.);
#23=EDGE_LOOP('',(#47,#48,#49,#50));
#24=EDGE_LOOP('',(#51,#52,#53,#54));
#25=EDGE_LOOP('',(#55));
#26=EDGE_LOOP('',(#56));
#27=EDGE_LOOP('',(#57));
#28=EDGE_LOOP('',(#58));
#29=LINE('',#112,#31);
#30=LINE('',#118,#32);
#31=VECTOR('',#93,1.7);
#32=VECTOR('',#100,2.7);
#33=CIRCLE('',#80,1.7);
#34=CIRCLE('',#81,1.7);
#35=CIRCLE('',#83,2.7);
#36=CIRCLE('',#84,2.7);
#37=VERTEX_POINT('',#109);
#38=VERTEX_POINT('',#111);
#39=VERTEX_POINT('',#115);
#40=VERTEX_POINT('',#117);
#41=EDGE_CURVE('',#37,#37,#33,.T.);
#42=EDGE_CURVE('',#37,#38,#29,.T.);
#43=EDGE_CURVE('',#38,#38,#34,.T.);
#44=EDGE_CURVE('',#39,#39,#35,.T.);
#45=EDGE_CURVE('',#39,#40,#30,.T.);
#46=EDGE_CURVE('',#40,#40,#36,.T.);
#47=ORIENTED_EDGE('',*,*,#41,.F.);
#48=ORIENTED_EDGE('',*,*,#42,.T.);
#49=ORIENTED_EDGE('',*,*,#43,.T.);
#50=ORIENTED_EDGE('',*,*,#42,.F.);
#51=ORIENTED_EDGE('',*,*,#44,.F.);
#52=ORIENTED_EDGE('',*,*,#45,.T.);
#53=ORIENTED_EDGE('',*,*,#46,.T.);
#54=ORIENTED_EDGE('',*,*,#45,.F.);
#55=ORIENTED_EDGE('',*,*,#44,.T.);
#56=ORIENTED_EDGE('',*,*,#41,.T.);
#57=ORIENTED_EDGE('',*,*,#46,.F.);
#58=ORIENTED_EDGE('',*,*,#43,.F.);
#59=CYLINDRICAL_SURFACE('',#79,1.7);
#60=CYLINDRICAL_SURFACE('',#82,2.7);
#61=ADVANCED_FACE('',(#19),#59,.F.);
#62=ADVANCED_FACE('',(#20),#60,.T.);
#63=ADVANCED_FACE('',(#21,#15),#17,.T.);
#64=ADVANCED_FACE('',(#22,#16),#18,.F.);
#65=CLOSED_SHELL('',(#61,#62,#63,#64));
#66=DERIVED_UNIT_ELEMENT(#68,1.);
#67=DERIVED_UNIT_ELEMENT(#127,-3.);
#68=(
MASS_UNIT()
NAMED_UNIT(*)
SI_UNIT(.KILO.,.GRAM.)
);
#69=DERIVED_UNIT((#66,#67));
#70=MEASURE_REPRESENTATION_ITEM('density measure',
POSITIVE_RATIO_MEASURE(7850.),#69);
#71=PROPERTY_DEFINITION_REPRESENTATION(#76,#73);
#72=PROPERTY_DEFINITION_REPRESENTATION(#77,#74);
#73=REPRESENTATION('material name',(#75),#124);
#74=REPRESENTATION('density',(#70),#124);
#75=DESCRIPTIVE_REPRESENTATION_ITEM('Steel','Steel');
#76=PROPERTY_DEFINITION('material property','material name',#134);
#77=PROPERTY_DEFINITION('material property','density of part',#134);
#78=AXIS2_PLACEMENT_3D('',#107,#87,#88);
#79=AXIS2_PLACEMENT_3D('',#108,#89,#90);
#80=AXIS2_PLACEMENT_3D('',#110,#91,#92);
#81=AXIS2_PLACEMENT_3D('',#113,#94,#95);
#82=AXIS2_PLACEMENT_3D('',#114,#96,#97);
#83=AXIS2_PLACEMENT_3D('',#116,#98,#99);
#84=AXIS2_PLACEMENT_3D('',#119,#101,#102);
#85=AXIS2_PLACEMENT_3D('',#120,#103,#104);
#86=AXIS2_PLACEMENT_3D('',#121,#105,#106);
#87=DIRECTION('axis',(0.,0.,1.));
#88=DIRECTION('refdir',(1.,0.,0.));
#89=DIRECTION('center_axis',(0.,0.,1.));
#90=DIRECTION('ref_axis',(1.,0.,0.));
#91=DIRECTION('center_axis',(0.,0.,-1.));
#92=DIRECTION('ref_axis',(1.,0.,0.));
#93=DIRECTION('',(0.,0.,-1.));
#94=DIRECTION('center_axis',(0.,0.,-1.));
#95=DIRECTION('ref_axis',(1.,0.,0.));
#96=DIRECTION('center_axis',(0.,0.,1.));
#97=DIRECTION('ref_axis',(1.,0.,0.));
#98=DIRECTION('center_axis',(0.,0.,1.));
#99=DIRECTION('ref_axis',(1.,0.,0.));
#100=DIRECTION('',(0.,0.,-1.));
#101=DIRECTION('center_axis',(0.,0.,1.));
#102=DIRECTION('ref_axis',(1.,0.,0.));
#103=DIRECTION('center_axis',(0.,0.,1.));
#104=DIRECTION('ref_axis',(1.,0.,0.));
#105=DIRECTION('center_axis',(0.,0.,1.));
#106=DIRECTION('ref_axis',(1.,0.,0.));
#107=CARTESIAN_POINT('',(0.,0.,0.));
#108=CARTESIAN_POINT('Origin',(0.,0.,0.));
#109=CARTESIAN_POINT('',(-1.7,-2.0818995585505E-16,2.));
#110=CARTESIAN_POINT('Origin',(0.,0.,2.));
#111=CARTESIAN_POINT('',(-1.7,-2.0818995585505E-16,0.));
#112=CARTESIAN_POINT('',(-1.7,-2.0818995585505E-16,0.));
#113=CARTESIAN_POINT('Origin',(0.,0.,0.));
#114=CARTESIAN_POINT('Origin',(0.,0.,0.));
#115=CARTESIAN_POINT('',(-2.7,-3.30654635769785E-16,2.));
#116=CARTESIAN_POINT('Origin',(0.,0.,2.));
#117=CARTESIAN_POINT('',(-2.7,-3.30654635769785E-16,0.));
#118=CARTESIAN_POINT('',(-2.7,-3.30654635769785E-16,0.));
#119=CARTESIAN_POINT('Origin',(0.,0.,0.));
#120=CARTESIAN_POINT('Origin',(0.,0.,2.));
#121=CARTESIAN_POINT('Origin',(0.,0.,0.));
#122=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#126,
'DISTANCE_ACCURACY_VALUE',
'Maximum model space distance between geometric entities at asserted c
onnectivities');
#123=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#126,
'DISTANCE_ACCURACY_VALUE',
'Maximum model space distance between geometric entities at asserted c
onnectivities');
#124=(
GEOMETRIC_REPRESENTATION_CONTEXT(3)
GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#122))
GLOBAL_UNIT_ASSIGNED_CONTEXT((#126,#128,#129))
REPRESENTATION_CONTEXT('','3D')
);
#125=(
GEOMETRIC_REPRESENTATION_CONTEXT(3)
GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#123))
GLOBAL_UNIT_ASSIGNED_CONTEXT((#126,#128,#129))
REPRESENTATION_CONTEXT('','3D')
);
#126=(
LENGTH_UNIT()
NAMED_UNIT(*)
SI_UNIT(.MILLI.,.METRE.)
);
#127=(
LENGTH_UNIT()
NAMED_UNIT(*)
SI_UNIT($,.METRE.)
);
#128=(
NAMED_UNIT(*)
PLANE_ANGLE_UNIT()
SI_UNIT($,.RADIAN.)
);
#129=(
NAMED_UNIT(*)
SI_UNIT($,.STERADIAN.)
SOLID_ANGLE_UNIT()
);
#130=SHAPE_DEFINITION_REPRESENTATION(#131,#132);
#131=PRODUCT_DEFINITION_SHAPE('',$,#134);
#132=SHAPE_REPRESENTATION('',(#78),#124);
#133=PRODUCT_DEFINITION_CONTEXT('part definition',#138,'design');
#134=PRODUCT_DEFINITION('washer-m3','washer-m3',#135,#133);
#135=PRODUCT_DEFINITION_FORMATION('',$,#140);
#136=PRODUCT_RELATED_PRODUCT_CATEGORY('washer-m3','washer-m3',(#140));
#137=APPLICATION_PROTOCOL_DEFINITION('international standard',
'automotive_design',2009,#138);
#138=APPLICATION_CONTEXT(
'Core Data for Automotive Mechanical Design Process');
#139=PRODUCT_CONTEXT('part definition',#138,'mechanical');
#140=PRODUCT('washer-m3','washer-m3',$,(#139));
#141=PRESENTATION_STYLE_ASSIGNMENT((#142));
#142=SURFACE_STYLE_USAGE(.BOTH.,#143);
#143=SURFACE_SIDE_STYLE('',(#144));
#144=SURFACE_STYLE_FILL_AREA(#145);
#145=FILL_AREA_STYLE('Steel - Satin',(#146));
#146=FILL_AREA_STYLE_COLOUR('Steel - Satin',#147);
#147=COLOUR_RGB('Steel - Satin',0.627450980392157,0.627450980392157,0.627450980392157);
ENDSEC;
END-ISO-10303-21;

BIN
docs/assets/washer-m3.stl Normal file

Binary file not shown.

110
docs/book.css Normal file
View File

@@ -0,0 +1,110 @@
.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;
}
.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'; }

22
docs/book.toml Normal file
View File

@@ -0,0 +1,22 @@
[book]
authors = ["Oleg Kalachev"]
language = "ru"
multilingual = false
src = "book"
title = "Полетный контроллер с нуля"
description = "Учебник по разработке полетного контроллера квадрокоптера"
[build]
build-dir = "build"
[output.html]
additional-css = ["book.css", "zoom.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"

10
docs/book/README.md Normal file
View File

@@ -0,0 +1,10 @@
# Flix
> [!IMPORTANT]
> Flix — это проект по созданию открытого квадрокоптера на базе ESP32 с нуля и учебника по разработке полетных контроллеров.
<img src="img/flix1.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>

22
docs/book/SUMMARY.md Normal file
View File

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

32
docs/book/firmware.md Normal file
View File

@@ -0,0 +1,32 @@
# Архитектура прошивки
<img src="img/dataflow.svg" width=800 alt="Firmware dataflow diagram">
Главный цикл работает на частоте 1000 Гц. Передача данных между подсистемами происходит через глобальные переменные:
* `t` *(float)* — текущее время шага, *с*.
* `dt` *(float)* — дельта времени между текущим и предыдущим шагами, *с*.
* `gyro` *(Vector)* — данные с гироскопа, *рад/с*.
* `acc` *(Vector)* — данные с акселерометра, *м/с<sup>2</sup>*.
* `rates` *(Vector)* — отфильтрованные угловые скорости, *рад/с*.
* `attitude` *(Quaternion)* — оценка ориентации (положения) дрона.
* `controls` *(float[])* — пользовательские управляющие сигналы с пульта, нормализованные в диапазоне [-1, 1].
* `motors` *(float[])* — выходные сигналы на моторы, нормализованные в диапазоне [-1, 1] (возможно вращение в обратную сторону).
## Исходные файлы
Исходные файлы прошивки находятся в директории `flix`. Ключевые файлы:
* [`flix.ino`](https://github.com/okalachev/flix/blob/canonical/flix/flix.ino) — основной входной файл, скетч Arduino. Включает определение глобальных переменных и главный цикл.
* [`imu.ino`](https://github.com/okalachev/flix/blob/canonical/flix/imu.ino) — чтение данных с датчика IMU (гироскоп и акселерометр), калибровка IMU.
* [`rc.ino`](https://github.com/okalachev/flix/blob/canonical/flix/rc.ino) — чтение данных с RC-приемника, калибровка RC.
* [`mavlink.ino`](https://github.com/okalachev/flix/blob/canonical/flix/mavlink.ino) — взаимодействие с QGroundControl через MAVLink.
* [`estimate.ino`](https://github.com/okalachev/flix/blob/canonical/flix/estimate.ino) — оценка ориентации дрона, комплементарный фильтр.
* [`control.ino`](https://github.com/okalachev/flix/blob/canonical/flix/control.ino) — управление ориентацией и угловыми скоростями дрона, трехмерный двухуровневый каскадный PID-регулятор.
* [`motors.ino`](https://github.com/okalachev/flix/blob/canonical/flix/motors.ino) — управление выходными сигналами на моторы через ШИМ.
Вспомогательные файлы включают:
* [`vector.h`](https://github.com/okalachev/flix/blob/canonical/flix/vector.h), [`quaternion.h`](https://github.com/okalachev/flix/blob/canonical/flix/quaternion.h) — реализация библиотек векторов и кватернионов проекта.
* [`pid.h`](https://github.com/okalachev/flix/blob/canonical/flix/pid.h) — реализация общего ПИД-регулятора.
* [`lpf.h`](https://github.com/okalachev/flix/blob/canonical/flix/lpf.h) — реализация общего фильтра нижних частот.

262
docs/book/gyro.md Normal file
View File

@@ -0,0 +1,262 @@
# Гироскоп
<div class="firmware">
<strong>Файл прошивки Flix:</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 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер. В Flix используется частота сэмплов 1 кГц.
Частота сэмплов устанавливается методом `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).

1
docs/book/img Symbolic link
View File

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

View File

@@ -9,12 +9,14 @@ cd flix
## Simulation
### Ubuntu
### Ubuntu 20.04
The latest version of Ubuntu supported by Gazebo 11 simulator is 20.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=/usr/local/bin sh
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
```
2. Install Gazebo 11:
@@ -78,19 +80,35 @@ cd flix
make simulator
```
### Flight
### Setup and flight
Use USB remote control or QGroundControl mobile app (with *Virtual Joystick* setting enabled) to control the drone. *Auto-Center Throttle* setting **should be disabled**.
#### 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.
4. Run the simulation again.
5. 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. Install ESP32 core using [Boards Manager](https://docs.arduino.cc/learn/starting-guide/cores).
2. Install ESP32 core, version 3.0.7 (version 2.x is not supported). See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
3. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
* `FlixPeriph`.
* `MAVLink`, version 2.0.1.
* `FlixPeriph`, the latest version.
* `MAVLink`, version 2.0.12.
4. Clone the project using git or [download the source code as a ZIP archive](https://codeload.github.com/okalachev/flix/zip/refs/heads/master).
5. Open the downloaded Arduino sketch `flix/flix.ino` in Arduino IDE.
6. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
@@ -119,12 +137,34 @@ Use USB remote control or QGroundControl mobile app (with *Virtual Joystick* set
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 and follow the instructions.
#### 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 and follow the instructions.
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.
## Setup
Before flight in simulation and on the real drone, you need to calibrate your remote control. Use drone's command line interface (`make monitor` on the real drone) and type `cr` command. Copy calibration results to the source code (`flix/rc.ino` and/or `gazebo/joystick.h`).
On the real drone, you also need to calibrate the accelerometer and the gyroscope. Use `ca` and `cg` commands for that. Copy calibration results to the source code (`flix/imu.ino`).

BIN
docs/img/100n03a.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 27 KiB

BIN
docs/img/battery.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 32 KiB

BIN
docs/img/esp32-holder.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 9.3 KiB

BIN
docs/img/flight-video.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 79 KiB

BIN
docs/img/flightplot.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 56 KiB

BIN
docs/img/flix1.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 89 KiB

BIN
docs/img/flixperiph.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

BIN
docs/img/foxglove.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 61 KiB

BIN
docs/img/frame1.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

78
docs/img/gy91-lfd.svg Normal file

File diff suppressed because one or more lines are too long

After

Width:  |  Height:  |  Size: 47 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 115 KiB

BIN
docs/img/gyro-plotter.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 114 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 105 KiB

BIN
docs/img/gyroscope.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 36 KiB

BIN
docs/img/icm-20948.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 36 KiB

119
docs/img/imu-axes.svg Normal file
View File

@@ -0,0 +1,119 @@
<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>

After

Width:  |  Height:  |  Size: 2.8 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 38 KiB

BIN
docs/img/mpu9250.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

BIN
docs/img/plotjuggler.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 53 KiB

BIN
docs/img/resistor10k.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

256
docs/img/schematics1.svg Normal file
View File

@@ -0,0 +1,256 @@
<?xml version="1.0" encoding="utf-8"?>
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 1920 1080" style="enable-background:new 0 0 1920 1080;" xml:space="preserve">
<style type="text/css">
.st0{clip-path:url(#SVGID_00000116955662310502408250000008996271717606231736_);fill:#FFFFFF;}
.st1{clip-path:url(#SVGID_00000116955662310502408250000008996271717606231736_);fill:#0076BA;}
.st2{clip-path:url(#SVGID_00000116955662310502408250000008996271717606231736_);fill:none;stroke:#0076BA;stroke-width:6;}
.st3{clip-path:url(#SVGID_00000055674346191406539380000013421132283630177205_);}
.st4{fill:#FFFFFF;}
.st5{font-family:'Tahoma';}
.st6{font-size:60px;}
.st7{clip-path:url(#SVGID_00000057846011469822040540000011754501750068092081_);fill:none;stroke:#0076BA;stroke-width:6;}
.st8{clip-path:url(#SVGID_00000057846011469822040540000011754501750068092081_);fill:none;stroke:#0076BA;stroke-width:6;stroke-dasharray:12,12;}
.st9{clip-path:url(#SVGID_00000031912132892401345140000018376817810309323944_);}
.st10{letter-spacing:-1;}
.st11{clip-path:url(#SVGID_00000096022444481931167570000018189382621257791423_);fill:none;stroke:#D5D5D5;stroke-width:6;}
.st12{clip-path:url(#SVGID_00000096022444481931167570000018189382621257791423_);fill:#D5D5D5;}
.st13{clip-path:url(#SVGID_00000096022444481931167570000018189382621257791423_);}
.st14{font-size:40px;}
.st15{clip-path:url(#SVGID_00000096022444481931167570000018189382621257791423_);fill:none;stroke:#D5D5D5;stroke-width:6;stroke-dasharray:12,12;}
.st16{letter-spacing:-3;}
.st17{clip-path:url(#SVGID_00000096022444481931167570000018189382621257791423_);fill:none;stroke:#0076BA;stroke-width:6;}
.st18{clip-path:url(#SVGID_00000178923025368094801390000008109591059568692644_);}
.st19{clip-path:url(#SVGID_00000170245726615134129150000014803823133490835355_);fill:none;stroke:#D5D5D5;stroke-width:6;}
.st20{clip-path:url(#SVGID_00000170245726615134129150000014803823133490835355_);fill:#D5D5D5;}
.st21{clip-path:url(#SVGID_00000170245726615134129150000014803823133490835355_);}
.st22{clip-path:url(#SVGID_00000170245726615134129150000014803823133490835355_);fill:none;stroke:#FF9300;stroke-width:6;}
.st23{clip-path:url(#SVGID_00000137829079020238483810000004945639728221863820_);}
.st24{clip-path:url(#SVGID_00000127742992435002359440000017943924755103710901_);fill:none;stroke:#0076BA;stroke-width:6;}
.st25{clip-path:url(#SVGID_00000172413095142863711730000006643673940354901182_);}
.st26{fill:#333333;}
.st27{clip-path:url(#SVGID_00000057841300642942441540000015331613196773382808_);fill:none;stroke:#0076BA;stroke-width:3;}
.st28{clip-path:url(#SVGID_00000015346235126698654330000007941041458912523396_);}
.st29{font-size:30px;}
</style>
<g>
<defs>
<rect id="SVGID_1_" width="1920" height="1080"/>
</defs>
<clipPath id="SVGID_00000171677823290121104880000004951624621648774806_">
<use xlink:href="#SVGID_1_" style="overflow:visible;"/>
</clipPath>
<rect style="clip-path:url(#SVGID_00000171677823290121104880000004951624621648774806_);fill:#FFFFFF;" width="1920" height="1080"/>
<path style="clip-path:url(#SVGID_00000171677823290121104880000004951624621648774806_);fill:#0076BA;" d="M781,353.4h358
c8.4,0,13.4,0,16.7,1.4c4.8,1.8,8.6,5.6,10.4,10.4c1.4,3.3,1.4,8.4,1.4,16.7v268.8c0,8.4,0,13.4-1.4,16.7
c-1.8,4.8-5.6,8.6-10.4,10.4c-3.3,1.4-8.4,1.4-16.7,1.4H781c-8.4,0-13.4,0-16.7-1.4c-4.8-1.8-8.6-5.6-10.4-10.4
c-1.4-3.3-1.4-8.4-1.4-16.7V381.9c0-8.4,0-13.4,1.4-16.7c1.8-4.8,5.6-8.6,10.4-10.4C767.6,353.4,772.6,353.4,781,353.4z"/>
<path style="clip-path:url(#SVGID_00000171677823290121104880000004951624621648774806_);fill:none;stroke:#0076BA;stroke-width:6;" d="
M781,353.4h358c8.4,0,13.4,0,16.7,1.4c4.8,1.8,8.6,5.6,10.4,10.4c1.4,3.3,1.4,8.4,1.4,16.7v268.8c0,8.4,0,13.4-1.4,16.7
c-1.8,4.8-5.6,8.6-10.4,10.4c-3.3,1.4-8.4,1.4-16.7,1.4H781c-8.4,0-13.4,0-16.7-1.4c-4.8-1.8-8.6-5.6-10.4-10.4
c-1.4-3.3-1.4-8.4-1.4-16.7V381.9c0-8.4,0-13.4,1.4-16.7c1.8-4.8,5.6-8.6,10.4-10.4C767.6,353.4,772.6,353.4,781,353.4z"/>
</g>
<g>
<defs>
<rect id="SVGID_00000039115730048533150280000004801426134829330596_" x="737.4" y="353.4" width="445.2" height="325.8"/>
</defs>
<clipPath id="SVGID_00000016774010820287457580000002865762276517841055_">
<use xlink:href="#SVGID_00000039115730048533150280000004801426134829330596_" style="overflow:visible;"/>
</clipPath>
<g style="clip-path:url(#SVGID_00000016774010820287457580000002865762276517841055_);">
<text transform="matrix(1 0 0 1 877.1631 540.0012)" class="st4 st5 st6">ESP32</text>
</g>
</g>
<g>
<defs>
<rect id="SVGID_00000075151113810300876960000013536007874996673433_" width="1920" height="1080"/>
</defs>
<clipPath id="SVGID_00000107586269070498659130000000925674275700912771_">
<use xlink:href="#SVGID_00000075151113810300876960000013536007874996673433_" style="overflow:visible;"/>
</clipPath>
<path style="clip-path:url(#SVGID_00000107586269070498659130000000925674275700912771_);fill:none;stroke:#0076BA;stroke-width:6;" d="
M107.1,424.9h369.6c6.7,0,10.7,0,13.4,1.1c3.9,1.4,6.9,4.4,8.3,8.3c1.1,2.7,1.1,6.7,1.1,13.4v153.2c0,6.7,0,10.7-1.1,13.4
c-1.4,3.9-4.4,6.9-8.3,8.3c-2.7,1.1-6.7,1.1-13.4,1.1H107.1c-6.7,0-10.7,0-13.4-1.1c-3.9-1.4-6.9-4.4-8.3-8.3
c-1.1-2.7-1.1-6.7-1.1-13.4V447.6c0-6.7,0-10.7,1.1-13.4c1.4-3.9,4.4-6.9,8.3-8.3C96.4,424.9,100.4,424.9,107.1,424.9z"/>
<path style="clip-path:url(#SVGID_00000107586269070498659130000000925674275700912771_);fill:none;stroke:#0076BA;stroke-width:6;stroke-dasharray:12,12;" d="
M777.9,846.9h364.3c7.5,0,11.9,0,14.9,1.2c4.3,1.6,7.7,5,9.3,9.3c1.2,3,1.2,7.5,1.2,14.9V974c0,7.5,0,11.9-1.2,14.9
c-1.6,4.3-5,7.7-9.3,9.3c-3,1.2-7.5,1.2-14.9,1.2H777.9c-7.5,0-11.9,0-14.9-1.2c-4.3-1.6-7.7-5-9.3-9.3c-1.2-3-1.2-7.5-1.2-14.9
V872.4c0-7.5,0-11.9,1.2-14.9c1.6-4.3,5-7.7,9.3-9.3C765.9,846.9,770.4,846.9,777.9,846.9z"/>
</g>
<g>
<defs>
<rect id="SVGID_00000128454988870213717900000008065144461254055839_" x="737.3" y="846.9" width="445.4" height="152.5"/>
</defs>
<clipPath id="SVGID_00000124119398570885020400000016506660910002275730_">
<use xlink:href="#SVGID_00000128454988870213717900000008065144461254055839_" style="overflow:visible;"/>
</clipPath>
<g style="clip-path:url(#SVGID_00000124119398570885020400000016506660910002275730_);">
<text transform="matrix(1 0 0 1 802.3304 947.0799)"><tspan x="0" y="0" class="st5 st6">RC </tspan><tspan x="92" y="0" class="st5 st6 st10">R</tspan><tspan x="128.2" y="0" class="st5 st6">ecei</tspan><tspan x="232.7" y="0" class="st5 st6">v</tspan><tspan x="262.2" y="0" class="st5 st6">er</tspan></text>
</g>
</g>
<g>
<defs>
<rect id="SVGID_00000130607252134697782620000007941153577788369085_" width="1920" height="1080"/>
</defs>
<clipPath id="SVGID_00000168829390248542060830000011029723519784449157_">
<use xlink:href="#SVGID_00000130607252134697782620000007941153577788369085_" style="overflow:visible;"/>
</clipPath>
<path style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:none;stroke:#D5D5D5;stroke-width:6;" d="
M429.1,526.4c96.1,19.6,194.9,26.9,296.4,22l3-0.2"/>
<polygon style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:#D5D5D5;" points="726.2,560.4
749.5,547.1 724.8,536.5 "/>
<g style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);">
<text transform="matrix(1 0 0 1 571.0244 599.9149)" class="st5 st14">SPI</text>
</g>
<path style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:none;stroke:#D5D5D5;stroke-width:6;stroke-dasharray:12,12;" d="
M991.9,843.9c7.9-38.5,9.3-84.5,4.4-137.8l-0.3-3"/>
<polygon style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:#D5D5D5;" points="1008.2,704.8
993.7,682.3 984.4,707.4 "/>
<g style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);">
<text transform="matrix(1 0 0 1 746.5599 778.8257)"><tspan x="0" y="0" class="st5 st14">SBUS (</tspan><tspan x="122.2" y="0" class="st5 st14">U</tspan><tspan x="148.3" y="0" class="st5 st14">A</tspan><tspan x="172.2" y="0" class="st5 st14 st10">R</tspan><tspan x="196" y="0" class="st5 st14">T</tspan><tspan x="219.8" y="0" class="st5 st14">)</tspan></text>
</g>
<path style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:none;stroke:#D5D5D5;stroke-width:6;" d="
M1170.5,537.8c72.8,3.7,147.2,3.8,223,0.3l3-0.2"/>
<polygon style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:#D5D5D5;" points="1394.1,550
1417.5,536.8 1392.9,526 "/>
<g style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);">
<text transform="matrix(1 0 0 1 1236.025 523.2462)" class="st5 st14">PWM</text>
</g>
<path style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:none;stroke:#D5D5D5;stroke-width:6;" d="
M1612.3,595.6c-10.7,73.2-11.3,149.1-2,227.5l0.4,3"/>
<polygon style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:#D5D5D5;" points="1598.5,824.7
1613.5,846.9 1622.2,821.6 "/>
<g style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);">
<text transform="matrix(1 0 0 1 1450.277 736.9998)"><tspan x="0" y="0" class="st5 st14 st10">V</tspan><tspan x="22.1" y="0" class="st5 st14">o</tspan><tspan x="43.8" y="0" class="st5 st14">l</tspan><tspan x="53" y="0" class="st5 st14">tage</tspan></text>
</g>
<g style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);">
<text transform="matrix(1 0 0 1 212.8847 595.784)"><tspan x="0" y="0" class="st5 st6">G</tspan><tspan x="40" y="0" class="st5 st6 st16">Y</tspan><tspan x="70.8" y="0" class="st5 st6">-91</tspan></text>
</g>
<path style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:none;stroke:#0076BA;stroke-width:6;" d="
M777.9,77.5h364.3c7.5,0,11.9,0,14.9,1.2c4.3,1.6,7.7,5,9.3,9.3c1.2,3,1.2,7.5,1.2,14.9v101.7c0,7.5,0,11.9-1.2,14.9
c-1.6,4.3-5,7.7-9.3,9.3c-3,1.2-7.5,1.2-14.9,1.2H777.9c-7.5,0-11.9,0-14.9-1.2c-4.3-1.6-7.7-5-9.3-9.3c-1.2-3-1.2-7.5-1.2-14.9
V103c0-7.5,0-11.9,1.2-14.9c1.6-4.3,5-7.7,9.3-9.3C765.9,77.5,770.4,77.5,777.9,77.5z"/>
</g>
<g>
<defs>
<rect id="SVGID_00000137820956330754408580000017691839315522467728_" x="737.3" y="77.5" width="445.4" height="152.5"/>
</defs>
<clipPath id="SVGID_00000016789657776342930330000013964875638603798149_">
<use xlink:href="#SVGID_00000137820956330754408580000017691839315522467728_" style="overflow:visible;"/>
</clipPath>
<g style="clip-path:url(#SVGID_00000016789657776342930330000013964875638603798149_);">
<text transform="matrix(1 0 0 1 865.0551 177.6901)"><tspan x="0" y="0" class="st5 st6">B</tspan><tspan x="35.6" y="0" class="st5 st6">a</tspan><tspan x="67.1" y="0" class="st5 st6">t</tspan><tspan x="86.7" y="0" class="st5 st6">tery</tspan></text>
</g>
</g>
<g>
<defs>
<rect id="SVGID_00000016756559387490335270000000552908433054081441_" width="1920" height="1080"/>
</defs>
<clipPath id="SVGID_00000171720285722730791730000010936644841389779363_">
<use xlink:href="#SVGID_00000016756559387490335270000000552908433054081441_" style="overflow:visible;"/>
</clipPath>
<path style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);fill:none;stroke:#D5D5D5;stroke-width:6;" d="
M925.7,233.1c-5.3,27.2-6.8,58.4-4.3,93.4l0.3,3"/>
<polygon style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);fill:#D5D5D5;" points="909.4,327.6
923.5,350.4 933.3,325.4 "/>
<g style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);">
<text transform="matrix(1 0 0 1 937.7745 299.4789)"><tspan x="0" y="0" class="st5 st14">&gt;3</tspan><tspan x="50.9" y="0" class="st5 st14">.</tspan><tspan x="62.1" y="0" class="st5 st14">7V</tspan></text>
</g>
<path style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);fill:none;stroke:#D5D5D5;stroke-width:6;" d="
M1170.6,161.5c228,25.6,371.6,110,430.8,253.1l1.1,2.8"/>
<polygon style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);fill:#D5D5D5;" points="1590.2,418.8
1609.8,437.1 1612.6,410.4 "/>
<g style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);">
<text transform="matrix(1 0 0 1 1396.229 204.8126)"><tspan x="0" y="0" class="st5 st14">&gt;3</tspan><tspan x="50.9" y="0" class="st5 st14">.</tspan><tspan x="62.1" y="0" class="st5 st14">7V</tspan></text>
</g>
<path style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);fill:none;stroke:#FF9300;stroke-width:6;" d="
M1445.9,849.9h364.3c7.5,0,11.9,0,14.9,1.2c4.3,1.6,7.7,5,9.3,9.3c1.2,3,1.2,7.5,1.2,14.9V977c0,7.5,0,11.9-1.2,14.9
c-1.6,4.3-5,7.7-9.3,9.3c-3,1.2-7.5,1.2-14.9,1.2h-364.3c-7.5,0-11.9,0-14.9-1.2c-4.3-1.6-7.7-5-9.3-9.3c-1.2-3-1.2-7.5-1.2-14.9
V875.4c0-7.5,0-11.9,1.2-14.9c1.6-4.3,5-7.7,9.3-9.3C1434,849.9,1438.5,849.9,1445.9,849.9z"/>
</g>
<g>
<defs>
<rect id="SVGID_00000125590519588794066770000004908208256101094292_" x="1405.4" y="849.9" width="445.4" height="152.5"/>
</defs>
<clipPath id="SVGID_00000020367246295901477730000005237269270844408247_">
<use xlink:href="#SVGID_00000125590519588794066770000004908208256101094292_" style="overflow:visible;"/>
</clipPath>
<g style="clip-path:url(#SVGID_00000020367246295901477730000005237269270844408247_);">
<text transform="matrix(1 0 0 1 1507.9561 950.0799)" class="st5 st6">Motors </text>
</g>
<g style="clip-path:url(#SVGID_00000020367246295901477730000005237269270844408247_);">
<text transform="matrix(1 0 0 1 1706.5596 950.0799)" class="st5 st14">x4</text>
</g>
</g>
<g>
<defs>
<rect id="SVGID_00000078757851010072822240000012642622956562684587_" width="1920" height="1080"/>
</defs>
<clipPath id="SVGID_00000132802581807603645050000011682039405646066589_">
<use xlink:href="#SVGID_00000078757851010072822240000012642622956562684587_" style="overflow:visible;"/>
</clipPath>
<path style="clip-path:url(#SVGID_00000132802581807603645050000011682039405646066589_);fill:none;stroke:#0076BA;stroke-width:6;" d="
M1445.9,440.1h364.3c7.5,0,11.9,0,14.9,1.2c4.3,1.6,7.7,5,9.3,9.3c1.2,3,1.2,7.5,1.2,14.9v101.7c0,7.5,0,11.9-1.2,14.9
c-1.6,4.3-5,7.7-9.3,9.3c-3,1.2-7.5,1.2-14.9,1.2h-364.3c-7.5,0-11.9,0-14.9-1.2c-4.3-1.6-7.7-5-9.3-9.3c-1.2-3-1.2-7.5-1.2-14.9
V465.5c0-7.5,0-11.9,1.2-14.9c1.6-4.3,5-7.7,9.3-9.3C1434,440.1,1438.5,440.1,1445.9,440.1z"/>
</g>
<g>
<defs>
<rect id="SVGID_00000121968229548182703620000008187702022402881724_" x="1405.4" y="440.1" width="445.4" height="152.5"/>
</defs>
<clipPath id="SVGID_00000130637550574198708210000000321319364498620830_">
<use xlink:href="#SVGID_00000121968229548182703620000008187702022402881724_" style="overflow:visible;"/>
</clipPath>
<g style="clip-path:url(#SVGID_00000130637550574198708210000000321319364498620830_);">
<text transform="matrix(1 0 0 1 1486.833 540.213)" class="st5 st6">MOSFE</text>
</g>
<g style="clip-path:url(#SVGID_00000130637550574198708210000000321319364498620830_);">
<text transform="matrix(1 0 0 1 1673.8936 540.213)" class="st26 st5 st6">T</text>
</g>
<g style="clip-path:url(#SVGID_00000130637550574198708210000000321319364498620830_);">
<text transform="matrix(1 0 0 1 1708.9326 540.213)" class="st5 st6"> </text>
</g>
<g style="clip-path:url(#SVGID_00000130637550574198708210000000321319364498620830_);">
<text transform="matrix(1 0 0 1 1727.6826 540.213)" class="st5 st14">x4</text>
</g>
</g>
<g>
<defs>
<rect id="SVGID_00000038395453607794357290000016650519059911045024_" width="1920" height="1080"/>
</defs>
<clipPath id="SVGID_00000077303055156502403190000000114138446408493755_">
<use xlink:href="#SVGID_00000038395453607794357290000016650519059911045024_" style="overflow:visible;"/>
</clipPath>
<path style="clip-path:url(#SVGID_00000077303055156502403190000000114138446408493755_);fill:none;stroke:#0076BA;stroke-width:3;" d="
M167.8,451H416c4.5,0,7.1,0,8.9,0.7c2.6,0.9,4.6,3,5.5,5.5c0.7,1.8,0.7,4.5,0.7,8.9v46.6c0,4.5,0,7.1-0.7,8.9
c-0.9,2.6-3,4.6-5.5,5.5c-1.8,0.7-4.5,0.7-8.9,0.7H167.8c-4.5,0-7.1,0-8.9-0.7c-2.6-0.9-4.6-3-5.5-5.5c-0.7-1.8-0.7-4.5-0.7-8.9
v-46.6c0-4.5,0-7.1,0.7-8.9c0.9-2.6,3-4.6,5.5-5.5C160.7,451,163.4,451,167.8,451z"/>
</g>
<g>
<defs>
<rect id="SVGID_00000077301502947632695740000005629016913768095395_" x="145.2" y="451" width="293.5" height="77"/>
</defs>
<clipPath id="SVGID_00000004518590643829462700000008680026774255780777_">
<use xlink:href="#SVGID_00000077301502947632695740000005629016913768095395_" style="overflow:visible;"/>
</clipPath>
<g style="clip-path:url(#SVGID_00000004518590643829462700000008680026774255780777_);">
<text transform="matrix(1 0 0 1 197.8359 501.2101)" class="st5 st29">MPU9250 IMU</text>
</g>
</g>
</svg>

After

Width:  |  Height:  |  Size: 17 KiB

BIN
docs/img/screw-m1.4.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 30 KiB

BIN
docs/img/screw-m3.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.7 KiB

BIN
docs/img/washer-m3.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 6.7 KiB

BIN
docs/img/wire-28awg.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 37 KiB

7
docs/js.js Normal file
View File

@@ -0,0 +1,7 @@
// Enable zoom on images larger than 300px
document.querySelectorAll('.content img').forEach(function (img) {
var width = img.getAttribute('width');
if (!width || width >= 300) {
img.setAttribute('data-action', 'zoom');
}
});

72
docs/log.md Normal file
View File

@@ -0,0 +1,72 @@
# Log analysis
Flix quadcopter uses RAM to store flight log data. The default log capacity is 10 seconds at 100 Hz. This configuration can be adjusted in the `log.ino` file.
To perform log analysis, you need to download the log right after the flight without powering off the drone. Then you can use several tools to analyze the log data.
## Log download
To download the log, connect the ESP32 using USB right after the flight and run the following command:
```bash
make log
```
Logs are stored in `tools/log/*.csv` files.
## Analysis
### PlotJuggler
The recommended tool for log analysis is PlotJuggler.
<img src="img/plotjuggler.png" width="500">
1. Install PlotJuggler using the [official instructions](https://github.com/facontidavide/PlotJuggler?tab=readme-ov-file#installation).
2. Run PlotJuggler and drag'n'drop the downloaded log file there. Choose `t` column to be used as X axis.
You can open the most recent downloaded file using the command:
```bash
make plot
```
You can perform both log download and run PlotJuggler in one command:
```bash
make log plot
```
### FlightPlot
FlightPlot is a powerful tool for analyzing logs in [ULog format](https://docs.px4.io/main/en/dev_log/ulog_file_format.html). This format is used in PX4 and ArduPilot flight software.
<img src="img/flightplot.png" width="500">
1. [Install FlightPlot](https://github.com/PX4/FlightPlot).
2. Flix repository contains a tool for converting CSV logs to ULog format. Build the tool using [the instructions](../tools/csv_to_ulog/README.md) and convert the log you want to analyze.
3. Run FlightPlot and drag'n'drop the converted ULog-file there.
### Foxglove Studio
Foxglove is a tool for visualizing and analyzing robotics data with very rich functionality. It can import various formats, but mainly focuses on its own format, called [MCAP](https://mcap.dev).
<img src="img/foxglove.png" width="500">
1. Install Foxglove Studio from the [official website](https://foxglove.dev/download).
2. Flix repository contains a tool for converting CSV logs to MCAP format. First, install its dependencies:
```bash
cd tools
pip install -r requirements.txt
```
3. Convert the log you want to analyze:
```bash
csv_to_mcap.py log_file.csv
```
4. Open the log in Foxglove Studio using *Open local file* command.

336
docs/theme/index.hbs vendored Normal file
View File

@@ -0,0 +1,336 @@
<!DOCTYPE HTML>
<html lang="{{ language }}" class="{{ default_theme }} sidebar-visible" dir="{{ text_direction }}">
<head>
<!-- Book generated using mdBook -->
<meta charset="UTF-8">
<title>{{ title }}</title>
{{#if is_print }}
<meta name="robots" content="noindex">
{{/if}}
{{#if base_url}}
<base href="{{ base_url }}">
{{/if}}
<!-- Custom HTML head -->
{{> head}}
<meta name="description" content="{{ description }}">
<meta name="viewport" content="width=device-width, initial-scale=1">
<meta name="theme-color" content="#ffffff">
{{#if favicon_svg}}
<link rel="icon" href="{{ path_to_root }}favicon.svg">
{{/if}}
{{#if favicon_png}}
<link rel="shortcut icon" href="{{ path_to_root }}favicon.png">
{{/if}}
<link rel="stylesheet" href="{{ path_to_root }}css/variables.css">
<link rel="stylesheet" href="{{ path_to_root }}css/general.css">
<link rel="stylesheet" href="{{ path_to_root }}css/chrome.css">
{{#if print_enable}}
<link rel="stylesheet" href="{{ path_to_root }}css/print.css" media="print">
{{/if}}
<!-- Fonts -->
<link rel="stylesheet" href="{{ path_to_root }}FontAwesome/css/font-awesome.css">
{{#if copy_fonts}}
<link rel="stylesheet" href="{{ path_to_root }}fonts/fonts.css">
{{/if}}
<!-- Highlight.js Stylesheets -->
<link rel="stylesheet" href="{{ path_to_root }}highlight.css">
<link rel="stylesheet" href="{{ path_to_root }}tomorrow-night.css">
<link rel="stylesheet" href="{{ path_to_root }}ayu-highlight.css">
<!-- Custom theme stylesheets -->
{{#each additional_css}}
<link rel="stylesheet" href="{{ ../path_to_root }}{{ this }}">
{{/each}}
{{#if mathjax_support}}
<!-- MathJax -->
<script async src="https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.1/MathJax.js?config=TeX-AMS-MML_HTMLorMML"></script>
{{/if}}
<!-- Provide site root to javascript -->
<script>
var path_to_root = "{{ path_to_root }}";
var default_theme = window.matchMedia("(prefers-color-scheme: dark)").matches ? "{{ preferred_dark_theme }}" : "{{ default_theme }}";
</script>
<!-- Start loading toc.js asap -->
<script src="{{ path_to_root }}toc.js"></script>
<!-- Yandex.Metrika counter -->
<script type="text/javascript" > (function(m,e,t,r,i,k,a){m[i]=m[i]||function(){(m[i].a=m[i].a||[]).push(arguments)}; m[i].l=1*new Date(); for (var j = 0; j < document.scripts.length; j++) {if (document.scripts[j].src === r) { return; }} k=e.createElement(t),a=e.getElementsByTagName(t)[0],k.async=1,k.src=r,a.parentNode.insertBefore(k,a)}) (window, document, "script", "https://mc.yandex.ru/metrika/tag.js", "ym"); ym(97589916, "init", { clickmap:true, trackLinks:true, accurateTrackBounce:true }); </script> <noscript><div><img src="https://mc.yandex.ru/watch/97589916" style="position:absolute; left:-9999px;" alt="" /></div></noscript> <!-- /Yandex.Metrika counter -->
</head>
<body>
<div id="body-container">
<!-- Work around some values being stored in localStorage wrapped in quotes -->
<script>
try {
var theme = localStorage.getItem('mdbook-theme');
var sidebar = localStorage.getItem('mdbook-sidebar');
if (theme.startsWith('"') && theme.endsWith('"')) {
localStorage.setItem('mdbook-theme', theme.slice(1, theme.length - 1));
}
if (sidebar.startsWith('"') && sidebar.endsWith('"')) {
localStorage.setItem('mdbook-sidebar', sidebar.slice(1, sidebar.length - 1));
}
} catch (e) { }
</script>
<!-- Set the theme before any content is loaded, prevents flash -->
<script>
var theme;
try { theme = localStorage.getItem('mdbook-theme'); } catch(e) { }
if (theme === null || theme === undefined) { theme = default_theme; }
const html = document.documentElement;
html.classList.remove('{{ default_theme }}')
html.classList.add(theme);
html.classList.add("js");
</script>
<input type="checkbox" id="sidebar-toggle-anchor" class="hidden">
<!-- Hide / unhide sidebar before it is displayed -->
<script>
var sidebar = null;
var sidebar_toggle = document.getElementById("sidebar-toggle-anchor");
if (document.body.clientWidth >= 1080) {
try { sidebar = localStorage.getItem('mdbook-sidebar'); } catch(e) { }
sidebar = sidebar || 'visible';
} else {
sidebar = 'hidden';
}
sidebar_toggle.checked = sidebar === 'visible';
html.classList.remove('sidebar-visible');
html.classList.add("sidebar-" + sidebar);
</script>
<nav id="sidebar" class="sidebar" aria-label="Table of contents">
<!-- populated by js -->
<mdbook-sidebar-scrollbox class="sidebar-scrollbox">
<footer>
<a href="https://github.com/okalachev/flix" class="github">GitHub</a>
<a href="https://t.me/opensourcequadcopter" class="telegram">Telegram-канал</a>
💰 Поддержать проект:
<iframe style="margin-top: 0.4em;" src="https://yoomoney.ru/quickpay/fundraise/button?billNumber=16U9OH2S4IT.241205&" width="330" height="50" frameborder="0" allowtransparency="true" scrolling="no"></iframe>
&copy; 2024 Олег Калачев
</footer>
</mdbook-sidebar-scrollbox>
<noscript>
<iframe class="sidebar-iframe-outer" src="{{ path_to_root }}toc.html"></iframe>
</noscript>
<div id="sidebar-resize-handle" class="sidebar-resize-handle">
<div class="sidebar-resize-indicator"></div>
</div>
</nav>
<div id="page-wrapper" class="page-wrapper">
<div class="page">
{{> header}}
<div id="menu-bar-hover-placeholder"></div>
<div id="menu-bar" class="menu-bar sticky">
<div class="left-buttons">
<label id="sidebar-toggle" class="icon-button" for="sidebar-toggle-anchor" title="Toggle Table of Contents" aria-label="Toggle Table of Contents" aria-controls="sidebar">
<i class="fa fa-bars"></i>
</label>
<button id="theme-toggle" class="icon-button" type="button" title="Change theme" aria-label="Change theme" aria-haspopup="true" aria-expanded="false" aria-controls="theme-list">
<i class="fa fa-paint-brush"></i>
</button>
<ul id="theme-list" class="theme-popup" aria-label="Themes" role="menu">
<li role="none"><button role="menuitem" class="theme" id="light">Light</button></li>
<li role="none"><button role="menuitem" class="theme" id="rust">Rust</button></li>
<li role="none"><button role="menuitem" class="theme" id="coal">Coal</button></li>
<li role="none"><button role="menuitem" class="theme" id="navy">Navy</button></li>
<li role="none"><button role="menuitem" class="theme" id="ayu">Ayu</button></li>
</ul>
{{#if search_enabled}}
<button id="search-toggle" class="icon-button" type="button" title="Search. (Shortkey: s)" aria-label="Toggle Searchbar" aria-expanded="false" aria-keyshortcuts="S" aria-controls="searchbar">
<i class="fa fa-search"></i>
</button>
{{/if}}
</div>
<h1 class="menu-title">{{ book_title }}</h1>
<div class="right-buttons">
{{#if print_enable}}
<a href="{{ path_to_root }}print.html" title="Print this book" aria-label="Print this book">
<i id="print-button" class="fa fa-print"></i>
</a>
{{/if}}
{{#if git_repository_url}}
<a href="{{git_repository_url}}" title="Git repository" aria-label="Git repository">
<i id="git-repository-button" class="fa {{git_repository_icon}}"></i>
</a>
{{/if}}
{{#if git_repository_edit_url}}
<a href="{{git_repository_edit_url}}" title="Suggest an edit" aria-label="Suggest an edit">
<i id="git-edit-button" class="fa fa-edit"></i>
</a>
{{/if}}
</div>
</div>
{{#if search_enabled}}
<div id="search-wrapper" class="hidden">
<form id="searchbar-outer" class="searchbar-outer">
<input type="search" id="searchbar" name="searchbar" placeholder="Search this book ..." aria-controls="searchresults-outer" aria-describedby="searchresults-header">
</form>
<div id="searchresults-outer" class="searchresults-outer hidden">
<div id="searchresults-header" class="searchresults-header"></div>
<ul id="searchresults">
</ul>
</div>
</div>
{{/if}}
<!-- Apply ARIA attributes after the sidebar and the sidebar toggle button are added to the DOM -->
<script>
document.getElementById('sidebar-toggle').setAttribute('aria-expanded', sidebar === 'visible');
document.getElementById('sidebar').setAttribute('aria-hidden', sidebar !== 'visible');
Array.from(document.querySelectorAll('#sidebar a')).forEach(function(link) {
link.setAttribute('tabIndex', sidebar === 'visible' ? 0 : -1);
});
</script>
<div id="content" class="content">
<main>
{{{ content }}}
</main>
<nav class="nav-wrapper" aria-label="Page navigation">
<!-- Mobile navigation buttons -->
{{#previous}}
<a rel="prev" href="{{ path_to_root }}{{link}}" class="mobile-nav-chapters previous" title="Previous chapter" aria-label="Previous chapter" aria-keyshortcuts="Left">
<i class="fa fa-angle-left"></i>
</a>
{{/previous}}
{{#next}}
<a rel="next prefetch" href="{{ path_to_root }}{{link}}" class="mobile-nav-chapters next" title="Next chapter" aria-label="Next chapter" aria-keyshortcuts="Right">
<i class="fa fa-angle-right"></i>
</a>
{{/next}}
<div style="clear: both"></div>
</nav>
</div>
</div>
<nav class="nav-wide-wrapper" aria-label="Page navigation">
{{#previous}}
<a rel="prev" href="{{ path_to_root }}{{link}}" class="nav-chapters previous" title="Previous chapter" aria-label="Previous chapter" aria-keyshortcuts="Left">
<i class="fa fa-angle-left"></i>
</a>
{{/previous}}
{{#next}}
<a rel="next prefetch" href="{{ path_to_root }}{{link}}" class="nav-chapters next" title="Next chapter" aria-label="Next chapter" aria-keyshortcuts="Right">
<i class="fa fa-angle-right"></i>
</a>
{{/next}}
</nav>
</div>
{{#if live_reload_endpoint}}
<!-- Livereload script (if served using the cli tool) -->
<script>
const wsProtocol = location.protocol === 'https:' ? 'wss:' : 'ws:';
const wsAddress = wsProtocol + "//" + location.host + "/" + "{{{live_reload_endpoint}}}";
const socket = new WebSocket(wsAddress);
socket.onmessage = function (event) {
if (event.data === "reload") {
socket.close();
location.reload();
}
};
window.onbeforeunload = function() {
socket.close();
}
</script>
{{/if}}
{{#if google_analytics}}
<!-- Google Analytics Tag -->
<script>
var localAddrs = ["localhost", "127.0.0.1", ""];
// make sure we don't activate google analytics if the developer is
// inspecting the book locally...
if (localAddrs.indexOf(document.location.hostname) === -1) {
(function(i,s,o,g,r,a,m){i['GoogleAnalyticsObject']=r;i[r]=i[r]||function(){
(i[r].q=i[r].q||[]).push(arguments)},i[r].l=1*new Date();a=s.createElement(o),
m=s.getElementsByTagName(o)[0];a.async=1;a.src=g;m.parentNode.insertBefore(a,m)
})(window,document,'script','https://www.google-analytics.com/analytics.js','ga');
ga('create', '{{google_analytics}}', 'auto');
ga('send', 'pageview');
}
</script>
{{/if}}
{{#if playground_line_numbers}}
<script>
window.playground_line_numbers = true;
</script>
{{/if}}
{{#if playground_copyable}}
<script>
window.playground_copyable = true;
</script>
{{/if}}
{{#if playground_js}}
<script src="{{ path_to_root }}ace.js"></script>
<script src="{{ path_to_root }}editor.js"></script>
<script src="{{ path_to_root }}mode-rust.js"></script>
<script src="{{ path_to_root }}theme-dawn.js"></script>
<script src="{{ path_to_root }}theme-tomorrow_night.js"></script>
{{/if}}
{{#if search_js}}
<script src="{{ path_to_root }}elasticlunr.min.js"></script>
<script src="{{ path_to_root }}mark.min.js"></script>
<script src="{{ path_to_root }}searcher.js"></script>
{{/if}}
<script src="{{ path_to_root }}clipboard.min.js"></script>
<script src="{{ path_to_root }}highlight.js"></script>
<script src="{{ path_to_root }}book.js"></script>
<!-- Custom JS scripts -->
{{#each additional_js}}
<script src="{{ ../path_to_root }}{{this}}"></script>
{{/each}}
{{#if is_print}}
{{#if mathjax_support}}
<script>
window.addEventListener('load', function() {
MathJax.Hub.Register.StartupHook('End', function() {
window.setTimeout(window.print, 100);
});
});
</script>
{{else}}
<script>
window.addEventListener('load', function() {
window.setTimeout(window.print, 100);
});
</script>
{{/if}}
{{/if}}
</div>
</body>
</html>

33
docs/troubleshooting.md Normal file
View File

@@ -0,0 +1,33 @@
# Troubleshooting
## The sketch doesn't compile
Do the following:
* **Check ESP32 core is installed**. Check if the version matches the one used in the [tutorial](build.md#firmware).
* **Check libraries**. Install all the required libraries from the tutorial. Make sure there are no MPU9250 or other peripherals libraries that may conflict with the ones used in the tutorial.
## The drone doesn't fly
Do the following:
* **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V.
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button to make sure you see the whole ESP32 output.
* **Make sure correct IMU model is chosen**. If using ICM-20948 board, change `MPU9250` to `ICM20948` everywhere in the `imu.ino` file.
* **Check if the CLI is working**. Perform `help` command in Serial Monitor. You should see the list of available commands.
* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
* **Make sure you're not moving the drone several seconds after the power on**. The drone calibrates its gyroscope on the start so it should stay still for a while.
* **Check the IMU sample rate**. Perform `imu` command. The `rate` field should be about 1000 (Hz).
* **Check the IMU data**. Perform `imu` command, check raw accelerometer and gyro output. The output should change as you move the drone.
* **Calibrate the accelerometer.** if is wasn't done before. Type `ca` command in Serial Monitor and follow the instructions.
* **Check the attitude estimation**. Connect to the drone using QGroundControl. Rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct.
* **Check the IMU orientation is set correctly**. If the attitude estimation is rotated, make sure `rotateIMU` function is defined correctly in `imu.ino` file.
* **Check the motors**. Perform the following commands using Serial Monitor:
* `mfr` — should rotate front right motor (counter-clockwise).
* `mfl` — should rotate front left motor (clockwise).
* `mrl` — should rotate rear left motor (counter-clockwise).
* `mrr` — should rotate rear right motor (clockwise).
* **Calibrate the RC** if you use it. Type `cr` command in Serial Monitor and follow the instructions.
* **Check the RC data** if you use it. Use `rc` command, `Control` should show correct values between -1 and 1, and between 0 and 1 for the throttle.
* **Check the IMU output using QGroundControl**. Connect to the drone using QGroundControl on your computer. Go to the *Analyze* tab, *MAVLINK Inspector*. Plot the data from the `SCALED_IMU` message. The gyroscope and accelerometer data should change according to the drone movement.
* **Check the gyroscope only attitude estimation**. Comment out `applyAcc();` line in `estimate.ino` and check if the attitude estimation in QGroundControl. It should be stable, but only drift very slowly.

30
docs/version0.md Normal file
View File

@@ -0,0 +1,30 @@
# Flix version 0
Flix version 0 (obsolete):
<img src="img/flix.jpg" width=500 alt="Flix quadcopter">
## Components list
|Type|Part|Image|Quantity|
|-|-|-|-|
|Microcontroller board|ESP32 Mini|<img src="img/esp32.jpg" width=100>|1|
|IMU and barometer² board|GY-91 (or other MPU-9250 board)|<img src="img/gy-91.jpg" width=100>|1|
|Quadcopter frame|K100|<img src="img/frame.jpg" width=100>|1|
|Motor|8520 3.7V brushed motor (**shaft 0.8mm!**)|<img src="img/motor.jpeg" width=100>|4|
|Propeller|Hubsan 55 mm|<img src="img/prop.jpg" width=100>|4|
|Motor ESC|2.7A 1S Dual Way Micro Brush ESC|<img src="img/esc.jpg" width=100>|4|
|RC transmitter|KINGKONG TINY X8|<img src="img/tx.jpg" width=100>|1|
|RC receiver|DF500 (SBUS)|<img src="img/rx.jpg" width=100>|1|
|~~SBUS inverter~~*||<img src="img/inv.jpg" width=100>|~~1~~|
|Battery|3.7 Li-Po 850 MaH 60C|||
|Battery charger||<img src="img/charger.jpg" width=100>|1|
|Wires, connectors, tape, ...||||
*\* — not needed as ESP32 supports [software pin inversion](https://github.com/bolderflight/sbus#inverted-serial).*
## Schematics
<img src="img/schematics.svg" width=800 alt="Flix schematics">
You can also check a user contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/) of the drone.

31
docs/zoom.css Normal file
View File

@@ -0,0 +1,31 @@
img[data-action="zoom"] {
cursor: zoom-in;
}
.zoom-img,
.zoom-img-wrap {
position: relative;
z-index: 666;
transition: all 300ms;
}
img.zoom-img {
cursor: zoom-out;
}
.zoom-overlay {
cursor: zoom-out;
z-index: 420;
background: #fff;
position: fixed;
top: 0;
left: 0;
right: 0;
bottom: 0;
filter: "alpha(opacity=0)";
opacity: 0;
transition: opacity 300ms;
}
.zoom-overlay-open .zoom-overlay {
filter: "alpha(opacity=100)";
opacity: 1;
}
/*# sourceMappingURL=data:application/json;base64,eyJ2ZXJzaW9uIjozLCJzb3VyY2VzIjpbIi4uL2Nzcy96b29tLmNzcyJdLCJuYW1lcyI6W10sIm1hcHBpbmdzIjoiQUFBQTtFQUNFLGdCQUFnQjtDQUNqQjtBQUNEOztFQUVFLG1CQUFtQjtFQUNuQixhQUFhO0VBQ2Isc0JBQXNCO0NBQ3ZCO0FBQ0Q7RUFDRSxpQkFBaUI7Q0FDbEI7QUFDRDtFQUNFLGlCQUFpQjtFQUNqQixhQUFhO0VBQ2IsaUJBQWlCO0VBQ2pCLGdCQUFnQjtFQUNoQixPQUFPO0VBQ1AsUUFBUTtFQUNSLFNBQVM7RUFDVCxVQUFVO0VBQ1YsMkJBQTJCO0VBQzNCLFdBQVc7RUFDWCwrQkFBK0I7Q0FDaEM7QUFDRDtFQUNFLDZCQUE2QjtFQUM3QixXQUFXO0NBQ1oiLCJmaWxlIjoiem9vbS5jc3MiLCJzb3VyY2VzQ29udGVudCI6WyJpbWdbZGF0YS1hY3Rpb249XCJ6b29tXCJdIHtcbiAgY3Vyc29yOiB6b29tLWluO1xufVxuLnpvb20taW1nLFxuLnpvb20taW1nLXdyYXAge1xuICBwb3NpdGlvbjogcmVsYXRpdmU7XG4gIHotaW5kZXg6IDY2NjtcbiAgdHJhbnNpdGlvbjogYWxsIDMwMG1zO1xufVxuaW1nLnpvb20taW1nIHtcbiAgY3Vyc29yOiB6b29tLW91dDtcbn1cbi56b29tLW92ZXJsYXkge1xuICBjdXJzb3I6IHpvb20tb3V0O1xuICB6LWluZGV4OiA0MjA7XG4gIGJhY2tncm91bmQ6ICNmZmY7XG4gIHBvc2l0aW9uOiBmaXhlZDtcbiAgdG9wOiAwO1xuICBsZWZ0OiAwO1xuICByaWdodDogMDtcbiAgYm90dG9tOiAwO1xuICBmaWx0ZXI6IFwiYWxwaGEob3BhY2l0eT0wKVwiO1xuICBvcGFjaXR5OiAwO1xuICB0cmFuc2l0aW9uOiAgICAgIG9wYWNpdHkgMzAwbXM7XG59XG4uem9vbS1vdmVybGF5LW9wZW4gLnpvb20tb3ZlcmxheSB7XG4gIGZpbHRlcjogXCJhbHBoYShvcGFjaXR5PTEwMClcIjtcbiAgb3BhY2l0eTogMTtcbn1cbiJdfQ== */

281
docs/zoom.js Normal file
View File

@@ -0,0 +1,281 @@
/* https://github.com/spinningarrow/zoom-vanilla.js
The MIT License
Permission is hereby granted, free of charge, to any person obtaining
a copy of this software and associated documentation files (the
"Software"), to deal in the Software without restriction, including
without limitation the rights to use, copy, modify, merge, publish,
distribute, sublicense, and/or sell copies of the Software, and to
permit persons to whom the Software is furnished to do so, subject to
the following conditions:
The above copyright notice and this permission notice shall be
included in all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE
LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION
OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
+function () { "use strict";
var OFFSET = 80
// From http://youmightnotneedjquery.com/#offset
function offset(element) {
var rect = element.getBoundingClientRect()
var scrollTop = window.pageYOffset ||
document.documentElement.scrollTop ||
document.body.scrollTop ||
0
var scrollLeft = window.pageXOffset ||
document.documentElement.scrollLeft ||
document.body.scrollLeft ||
0
return {
top: rect.top + scrollTop,
left: rect.left + scrollLeft
}
}
function zoomListener() {
var activeZoom = null
var initialScrollPosition = null
var initialTouchPosition = null
function listen() {
document.body.addEventListener('click', function (event) {
if (event.target.getAttribute('data-action') !== 'zoom' ||
event.target.tagName !== 'IMG') return
zoom(event)
})
}
function zoom(event) {
event.stopPropagation()
if (document.body.classList.contains('zoom-overlay-open')) return
if (event.metaKey || event.ctrlKey) return openInNewWindow()
closeActiveZoom({ forceDispose: true })
activeZoom = vanillaZoom(event.target)
activeZoom.zoomImage()
addCloseActiveZoomListeners()
}
function openInNewWindow() {
window.open(event.target.getAttribute('data-original') ||
event.target.currentSrc ||
event.target.src,
'_blank')
}
function closeActiveZoom(options) {
options = options || { forceDispose: false }
if (!activeZoom) return
activeZoom[options.forceDispose ? 'dispose' : 'close']()
removeCloseActiveZoomListeners()
activeZoom = null
}
function addCloseActiveZoomListeners() {
// todo(fat): probably worth throttling this
window.addEventListener('scroll', handleScroll)
document.addEventListener('click', handleClick)
document.addEventListener('keyup', handleEscPressed)
document.addEventListener('touchstart', handleTouchStart)
document.addEventListener('touchend', handleClick)
}
function removeCloseActiveZoomListeners() {
window.removeEventListener('scroll', handleScroll)
document.removeEventListener('keyup', handleEscPressed)
document.removeEventListener('click', handleClick)
document.removeEventListener('touchstart', handleTouchStart)
document.removeEventListener('touchend', handleClick)
}
function handleScroll(event) {
if (initialScrollPosition === null) initialScrollPosition = window.pageYOffset
var deltaY = initialScrollPosition - window.pageYOffset
if (Math.abs(deltaY) >= 40) closeActiveZoom()
}
function handleEscPressed(event) {
if (event.keyCode == 27) closeActiveZoom()
}
function handleClick(event) {
event.stopPropagation()
event.preventDefault()
closeActiveZoom()
}
function handleTouchStart(event) {
initialTouchPosition = event.touches[0].pageY
event.target.addEventListener('touchmove', handleTouchMove)
}
function handleTouchMove(event) {
if (Math.abs(event.touches[0].pageY - initialTouchPosition) <= 10) return
closeActiveZoom()
event.target.removeEventListener('touchmove', handleTouchMove)
}
return { listen: listen }
}
var vanillaZoom = (function () {
var fullHeight = null
var fullWidth = null
var overlay = null
var imgScaleFactor = null
var targetImage = null
var targetImageWrap = null
var targetImageClone = null
function zoomImage() {
var img = document.createElement('img')
img.onload = function () {
fullHeight = Number(img.height)
fullWidth = Number(img.width)
zoomOriginal()
}
img.src = targetImage.currentSrc || targetImage.src
}
function zoomOriginal() {
targetImageWrap = document.createElement('div')
targetImageWrap.className = 'zoom-img-wrap'
targetImageWrap.style.position = 'absolute'
targetImageWrap.style.top = offset(targetImage).top + 'px'
targetImageWrap.style.left = offset(targetImage).left + 'px'
targetImageClone = targetImage.cloneNode()
targetImageClone.style.visibility = 'hidden'
targetImage.style.width = targetImage.offsetWidth + 'px'
targetImage.parentNode.replaceChild(targetImageClone, targetImage)
document.body.appendChild(targetImageWrap)
targetImageWrap.appendChild(targetImage)
targetImage.classList.add('zoom-img')
targetImage.setAttribute('data-action', 'zoom-out')
overlay = document.createElement('div')
overlay.className = 'zoom-overlay'
document.body.appendChild(overlay)
calculateZoom()
triggerAnimation()
}
function calculateZoom() {
targetImage.offsetWidth // repaint before animating
var originalFullImageWidth = fullWidth
var originalFullImageHeight = fullHeight
var maxScaleFactor = originalFullImageWidth / targetImage.width
var viewportHeight = window.innerHeight - OFFSET
var viewportWidth = window.innerWidth - OFFSET
var imageAspectRatio = originalFullImageWidth / originalFullImageHeight
var viewportAspectRatio = viewportWidth / viewportHeight
if (originalFullImageWidth < viewportWidth && originalFullImageHeight < viewportHeight) {
imgScaleFactor = maxScaleFactor
} else if (imageAspectRatio < viewportAspectRatio) {
imgScaleFactor = (viewportHeight / originalFullImageHeight) * maxScaleFactor
} else {
imgScaleFactor = (viewportWidth / originalFullImageWidth) * maxScaleFactor
}
}
function triggerAnimation() {
targetImage.offsetWidth // repaint before animating
var imageOffset = offset(targetImage)
var scrollTop = window.pageYOffset
var viewportY = scrollTop + (window.innerHeight / 2)
var viewportX = (window.innerWidth / 2)
var imageCenterY = imageOffset.top + (targetImage.height / 2)
var imageCenterX = imageOffset.left + (targetImage.width / 2)
var translateY = Math.round(viewportY - imageCenterY)
var translateX = Math.round(viewportX - imageCenterX)
var targetImageTransform = 'scale(' + imgScaleFactor + ')'
var targetImageWrapTransform =
'translate(' + translateX + 'px, ' + translateY + 'px) translateZ(0)'
targetImage.style.webkitTransform = targetImageTransform
targetImage.style.msTransform = targetImageTransform
targetImage.style.transform = targetImageTransform
targetImageWrap.style.webkitTransform = targetImageWrapTransform
targetImageWrap.style.msTransform = targetImageWrapTransform
targetImageWrap.style.transform = targetImageWrapTransform
document.body.classList.add('zoom-overlay-open')
}
function close() {
document.body.classList.remove('zoom-overlay-open')
document.body.classList.add('zoom-overlay-transitioning')
targetImage.style.webkitTransform = ''
targetImage.style.msTransform = ''
targetImage.style.transform = ''
targetImageWrap.style.webkitTransform = ''
targetImageWrap.style.msTransform = ''
targetImageWrap.style.transform = ''
if (!'transition' in document.body.style) return dispose()
targetImageWrap.addEventListener('transitionend', dispose)
targetImageWrap.addEventListener('webkitTransitionEnd', dispose)
}
function dispose() {
targetImage.removeEventListener('transitionend', dispose)
targetImage.removeEventListener('webkitTransitionEnd', dispose)
if (!targetImageWrap || !targetImageWrap.parentNode) return
targetImage.classList.remove('zoom-img')
targetImage.style.width = ''
targetImage.setAttribute('data-action', 'zoom')
targetImageClone.parentNode.replaceChild(targetImage, targetImageClone)
targetImageWrap.parentNode.removeChild(targetImageWrap)
overlay.parentNode.removeChild(overlay)
document.body.classList.remove('zoom-overlay-transitioning')
}
return function (target) {
targetImage = target
return { zoomImage: zoomImage, close: close, dispose: dispose }
}
}())
zoomListener().listen()
}()

View File

@@ -19,61 +19,50 @@ const char* motd =
"|__| |_______||__| /__/ \\__\\\n\n"
"Commands:\n\n"
"help - show help\n"
"show - show all parameters\n"
"<name> <value> - set parameter\n"
"p - show all parameters\n"
"p <name> - show parameter\n"
"p <name> <value> - set parameter\n"
"preset - reset parameters\n"
"ps - show pitch/roll/yaw\n"
"psq - show attitude quaternion\n"
"imu - show IMU data\n"
"rc - show RC data\n"
"mot - show motor data\n"
"mot - show motor output\n"
"log - dump in-RAM log\n"
"cr - calibrate RC\n"
"cg - calibrate gyro\n"
"ca - calibrate accel\n"
"mfr, mfl, mrr, mrl - test appropriate motor\n"
"fullmot <n> - full motor test\n"
"reset - reset drone's state\n";
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
"reset - reset drone's state\n"
"reboot - reboot the drone\n";
const struct Param {
const char* name;
float* value;
float* value2;
} params[] = {
{"rp", &rollRatePID.p, &pitchRatePID.p},
{"ri", &rollRatePID.i, &pitchRatePID.i},
{"rd", &rollRatePID.d, &pitchRatePID.d},
{"ap", &rollPID.p, &pitchPID.p},
{"ai", &rollPID.i, &pitchPID.i},
{"ad", &rollPID.d, &pitchPID.d},
{"yp", &yawRatePID.p, nullptr},
{"yi", &yawRatePID.i, nullptr},
{"yd", &yawRatePID.d, nullptr},
{"lpr", &ratesFilter.alpha, nullptr},
{"lpd", &rollRatePID.lpf.alpha, &pitchRatePID.lpf.alpha},
{"ss", &loopFreq, nullptr},
{"dt", &dt, nullptr},
{"t", &t, nullptr},
};
void doCommand(String& command, String& value) {
void doCommand(String& command, String& arg0, String& arg1) {
if (command == "help" || command == "motd") {
Serial.println(motd);
} else if (command == "show") {
showTable();
} else if (command == "p" && arg0 == "") {
printParameters();
} else if (command == "p" && arg0 != "" && arg1 == "") {
Serial.printf("%s = %g\n", arg0.c_str(), getParameter(arg0.c_str()));
} else if (command == "p") {
bool success = setParameter(arg0.c_str(), arg1.toFloat());
if (success) {
Serial.printf("%s = %g\n", arg0.c_str(), arg1.toFloat());
} else {
Serial.printf("Parameter not found: %s\n", arg0.c_str());
}
} else if (command == "preset") {
resetParameters();
} else if (command == "ps") {
Vector a = attitude.toEulerZYX();
Serial.printf("roll: %f pitch: %f yaw: %f\n", a.x * RAD_TO_DEG, a.y * RAD_TO_DEG, a.z * RAD_TO_DEG);
} else if (command == "psq") {
Serial.printf("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
} else if (command == "imu") {
printIMUInfo();
Serial.printf("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
Serial.printf("acc: %f %f %f\n", acc.x, acc.y, acc.z);
printIMUCal();
Serial.printf("frequency: %f\n", loopFreq);
Serial.printf("rate: %f\n", loopRate);
} else if (command == "rc") {
Serial.printf("Raw: throttle %d yaw %d pitch %d roll %d armed %d mode %d\n",
channels[RC_CHANNEL_THROTTLE], channels[RC_CHANNEL_YAW], channels[RC_CHANNEL_PITCH],
@@ -101,41 +90,23 @@ void doCommand(String& command, String& value) {
cliTestMotor(MOTOR_REAR_RIGHT);
} else if (command == "mrl") {
cliTestMotor(MOTOR_REAR_LEFT);
} else if (command == "fullmot") {
fullMotorTest(value.toInt(), false);
} else if (command == "reset") {
attitude = Quaternion();
} else if (command == "reboot") {
ESP.restart();
} else if (command == "") {
// do nothing
} else {
float val = value.toFloat();
// TODO: on error returns 0, check invalid value
for (uint8_t i = 0; i < sizeof(params) / sizeof(params[0]); i++) {
if (command == params[i].name) {
*params[i].value = val;
if (params[i].value2 != nullptr) *params[i].value2 = val;
Serial.print(command);
Serial.print(" = ");
Serial.println(val, 4);
return;
}
}
Serial.println("Invalid command: " + command);
}
}
void showTable() {
for (uint8_t i = 0; i < sizeof(params) / sizeof(params[0]); i++) {
Serial.print(params[i].name);
Serial.print(" ");
Serial.println(*params[i].value, 5);
}
}
void cliTestMotor(uint8_t n) {
Serial.printf("Testing motor %d\n", n);
motors[n] = 1;
delay(50); // ESP32 may need to wait until the end of the current cycle to change duty https://github.com/espressif/arduino-esp32/issues/5306
sendMotors();
delay(5000);
delay(3000);
motors[n] = 0;
sendMotors();
Serial.println("Done");
@@ -143,9 +114,7 @@ void cliTestMotor(uint8_t n) {
void parseInput() {
static bool showMotd = true;
static String command;
static String value;
static bool parsingCommand = true;
static String input;
if (showMotd) {
Serial.println(motd);
@@ -155,16 +124,21 @@ void parseInput() {
while (Serial.available()) {
char c = Serial.read();
if (c == '\n') {
parsingCommand = true;
if (!command.isEmpty()) {
doCommand(command, value);
}
command.clear();
value.clear();
} else if (c == ' ') {
parsingCommand = false;
char chars[input.length() + 1];
input.toCharArray(chars, input.length() + 1);
String command = stringToken(chars, " ");
String arg0 = stringToken(NULL, " ");
String arg1 = stringToken(NULL, "");
doCommand(command, arg0, arg1);
input.clear();
} else {
(parsingCommand ? command : value) += c;
input += c;
}
}
}
// Helper function for parsing input
String stringToken(char* str, const char* delim) {
char* token = strtok(str, delim);
return token == NULL ? "" : token;
}

View File

@@ -52,6 +52,7 @@ float thrustTarget;
void control() {
interpretRC();
failsafe();
if (mode == STAB) {
controlAttitude();
controlRate();
@@ -81,22 +82,22 @@ void interpretRC() {
if (mode == ACRO) {
yawMode = YAW_RATE;
ratesTarget.x = controls[RC_CHANNEL_ROLL] * ROLLRATE_MAX;
ratesTarget.y = -controls[RC_CHANNEL_PITCH] * PITCHRATE_MAX; // up pitch stick means tilt clockwise in frd
ratesTarget.z = controls[RC_CHANNEL_YAW] * YAWRATE_MAX;
ratesTarget.y = controls[RC_CHANNEL_PITCH] * PITCHRATE_MAX;
ratesTarget.z = -controls[RC_CHANNEL_YAW] * YAWRATE_MAX; // positive yaw stick means clockwise rotation in FLU
} else if (mode == STAB) {
yawMode = controls[RC_CHANNEL_YAW] == 0 ? YAW : YAW_RATE;
attitudeTarget = Quaternion::fromEulerZYX(Vector(
controls[RC_CHANNEL_ROLL] * MAX_TILT,
-controls[RC_CHANNEL_PITCH] * MAX_TILT,
controls[RC_CHANNEL_PITCH] * MAX_TILT,
attitudeTarget.getYaw()));
ratesTarget.z = controls[RC_CHANNEL_YAW] * YAWRATE_MAX;
ratesTarget.z = -controls[RC_CHANNEL_YAW] * YAWRATE_MAX; // positive yaw stick means clockwise rotation in FLU
} else if (mode == MANUAL) {
// passthrough mode
yawMode = YAW_RATE;
torqueTarget = Vector(controls[RC_CHANNEL_ROLL], -controls[RC_CHANNEL_PITCH], controls[RC_CHANNEL_YAW]) * 0.01;
torqueTarget = Vector(controls[RC_CHANNEL_ROLL], controls[RC_CHANNEL_PITCH], -controls[RC_CHANNEL_YAW]) * 0.01;
}
if (yawMode == YAW_RATE || !motorsActive()) {
@@ -113,7 +114,7 @@ void controlAttitude() {
return;
}
const Vector up(0, 0, -1);
const Vector up(0, 0, 1);
Vector upActual = attitude.rotate(up);
Vector upTarget = attitudeTarget.rotate(up);
@@ -123,7 +124,8 @@ void controlAttitude() {
ratesTarget.y = pitchPID.update(error.y, dt);
if (yawMode == YAW) {
ratesTarget.z = yawPID.update(wrapAngle(attitudeTarget.getYaw() - attitude.getYaw()), dt);
float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw());
ratesTarget.z = yawPID.update(yawError, dt);
}
}
@@ -149,10 +151,10 @@ void controlTorque() {
return;
}
motors[MOTOR_FRONT_LEFT] = thrustTarget + torqueTarget.x + torqueTarget.y - torqueTarget.z;
motors[MOTOR_FRONT_RIGHT] = thrustTarget - torqueTarget.x + torqueTarget.y + torqueTarget.z;
motors[MOTOR_REAR_LEFT] = thrustTarget + torqueTarget.x - torqueTarget.y + torqueTarget.z;
motors[MOTOR_REAR_RIGHT] = thrustTarget - torqueTarget.x - torqueTarget.y - torqueTarget.z;
motors[MOTOR_FRONT_LEFT] = thrustTarget + torqueTarget.x - torqueTarget.y + torqueTarget.z;
motors[MOTOR_FRONT_RIGHT] = thrustTarget - torqueTarget.x - torqueTarget.y - torqueTarget.z;
motors[MOTOR_REAR_LEFT] = thrustTarget + torqueTarget.x + torqueTarget.y - torqueTarget.z;
motors[MOTOR_REAR_RIGHT] = thrustTarget - torqueTarget.x + torqueTarget.y + torqueTarget.z;
motors[0] = constrain(motors[0], 0, 1);
motors[1] = constrain(motors[1], 0, 1);

View File

@@ -7,7 +7,6 @@
#include "vector.h"
#include "lpf.h"
#define ONE_G 9.807f
#define WEIGHT_ACC 0.5f
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
@@ -16,7 +15,6 @@ LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
void estimate() {
applyGyro();
applyAcc();
signalizeHorizontality();
}
void applyGyro() {
@@ -33,18 +31,14 @@ void applyAcc() {
float accNorm = acc.norm();
bool landed = !motorsActive() && abs(accNorm - ONE_G) < ONE_G * 0.1f;
setLED(landed);
if (!landed) return;
// calculate accelerometer correction
Vector up = attitude.rotate(Vector(0, 0, -1));
Vector up = attitude.rotate(Vector(0, 0, 1));
Vector correction = Vector::angularRatesBetweenVectors(acc, up) * dt * WEIGHT_ACC;
// apply correction
attitude *= Quaternion::fromAngularRates(correction);
attitude.normalize();
}
void signalizeHorizontality() {
float angle = Vector::angleBetweenVectors(attitude.rotate(Vector(0, 0, -1)), Vector(0, 0, -1));
setLED(angle < radians(15));
}

23
flix/failsafe.ino Normal file
View File

@@ -0,0 +1,23 @@
// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Fail-safe for RC loss
#define RC_LOSS_TIMEOUT 0.2
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
void failsafe() {
if (t - controlsTime > RC_LOSS_TIMEOUT) {
descend();
}
}
void descend() {
// Smooth descend on RC lost
mode = STAB;
controls[RC_CHANNEL_ROLL] = 0;
controls[RC_CHANNEL_PITCH] = 0;
controls[RC_CHANNEL_YAW] = 0;
controls[RC_CHANNEL_THROTTLE] -= dt / DESCEND_TIME;
if (controls[RC_CHANNEL_THROTTLE] < 0) controls[RC_CHANNEL_THROTTLE] = 0;
}

View File

@@ -8,9 +8,9 @@
#define SERIAL_BAUDRATE 115200
#define WIFI_ENABLED 0
#define WIFI_ENABLED 1
#define RC_CHANNELS 6
#define RC_CHANNELS 16
#define RC_CHANNEL_ROLL 0
#define RC_CHANNEL_PITCH 1
#define RC_CHANNEL_THROTTLE 2
@@ -23,21 +23,26 @@
#define MOTOR_FRONT_RIGHT 2
#define MOTOR_FRONT_LEFT 3
#define ONE_G 9.80665
float t = NAN; // current step time, s
float dt; // time delta from previous step, s
float loopFreq; // loop frequency, Hz
int16_t channels[16]; // raw rc channels
float loopRate; // loop rate, Hz
int16_t channels[RC_CHANNELS]; // raw rc channels
float controls[RC_CHANNELS]; // normalized controls in range [-1..1] ([0..1] for throttle)
float controlsTime; // time of the last controls update
Vector gyro; // gyroscope data
Vector acc; // accelerometer data, m/s/s
Vector rates; // filtered angular rates, rad/s
Quaternion attitude; // estimated attitude
bool landed; // are we landed and stationary
float motors[4]; // normalized motors thrust in range [-1..1]
void setup() {
Serial.begin(SERIAL_BAUDRATE);
Serial.println("Initializing flix");
disableBrownOut();
setupParameters();
setupLED();
setupMotors();
setLED(true);
@@ -63,4 +68,5 @@ void loop() {
processMavlink();
#endif
logData();
flushParameters();
}

View File

@@ -6,14 +6,11 @@
#include <SPI.h>
#include <MPU9250.h>
#define ONE_G 9.80665
// NOTE: use 'ca' command to calibrate the accelerometer and put the values here
Vector accBias(0, 0, 0);
Vector accScale(1, 1, 1);
MPU9250 IMU(SPI);
Vector accBias;
Vector gyroBias;
Vector accScale(1, 1, 1);
void setupIMU() {
Serial.println("Setup IMU");
@@ -24,23 +21,42 @@ void setupIMU() {
delay(1000);
}
}
calibrateGyro();
configureIMU();
// calibrateGyro();
}
void configureIMU() {
IMU.setAccelRange(IMU.ACCEL_RANGE_4G);
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
IMU.setDlpfBandwidth(IMU.DLPF_BANDWIDTH_184HZ);
IMU.setSrd(0); // set sample rate to 1000 Hz
IMU.setDLPF(IMU.DLPF_MAX);
IMU.setRate(IMU.RATE_1KHZ_APPROX);
}
void readIMU() {
IMU.waitForData();
IMU.getGyro(gyro.x, gyro.y, gyro.z);
IMU.getAccel(acc.x, acc.y, acc.z);
calibrateGyroOnce();
// apply scale and bias
acc = (acc - accBias) / accScale;
gyro = gyro - gyroBias;
// rotate
rotateIMU(acc);
rotateIMU(gyro);
}
void rotateIMU(Vector& data) {
// Rotate from LFD to FLU
// NOTE: In case of using other IMU orientation, change this line:
data = Vector(data.y, data.x, -data.z);
// Axes orientation for various boards: https://github.com/okalachev/flixperiph#imu-axes-orientation
}
void calibrateGyroOnce() {
if (!landed) return;
static float samples = 0; // overflows after 49 days at 1000 Hz
samples++;
gyroBias = gyroBias + (gyro - gyroBias) / samples; // running average
}
void calibrateGyro() {
@@ -63,8 +79,6 @@ void calibrateGyro() {
void calibrateAccel() {
Serial.println("Calibrating accelerometer");
IMU.setAccelRange(IMU.ACCEL_RANGE_2G); // the most sensitive mode
IMU.setDlpfBandwidth(IMU.DLPF_BANDWIDTH_20HZ);
IMU.setSrd(19);
Serial.setTimeout(60000);
Serial.print("Place level [enter] "); Serial.readStringUntil('\n');
@@ -85,7 +99,7 @@ void calibrateAccel() {
}
void calibrateAccelOnce() {
const int samples = 100;
const int samples = 1000;
static Vector accMax(-INFINITY, -INFINITY, -INFINITY);
static Vector accMin(INFINITY, INFINITY, INFINITY);
@@ -115,7 +129,12 @@ void calibrateAccelOnce() {
}
void printIMUCal() {
Serial.printf("gyro bias: %f %f %f\n", gyroBias.x, gyroBias.y, gyroBias.z);
Serial.printf("accel bias: %f %f %f\n", accBias.x, accBias.y, accBias.z);
Serial.printf("accel scale: %f %f %f\n", accScale.x, accScale.y, accScale.z);
Serial.printf("gyro bias: %f, %f, %f\n", gyroBias.x, gyroBias.y, gyroBias.z);
Serial.printf("accel bias: %f, %f, %f\n", accBias.x, accBias.y, accBias.z);
Serial.printf("accel scale: %f, %f, %f\n", accScale.x, accScale.y, accScale.z);
}
void printIMUInfo() {
Serial.printf("model: %s\n", IMU.getModel());
Serial.printf("who am I: 0x%02X\n", IMU.whoAmI());
}

View File

@@ -1,7 +1,7 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Main LED control
// Board's LED control
#define BLINK_PERIOD 500000
@@ -14,7 +14,12 @@ void setupLED() {
}
void setLED(bool on) {
static bool state = false;
if (on == state) {
return; // don't call digitalWrite if the state is the same
}
digitalWrite(LED_BUILTIN, on ? HIGH : LOW);
state = on;
}
void blinkLED() {

View File

@@ -38,8 +38,9 @@ void sendMavlink() {
lastFast = t;
const float zeroQuat[] = {0, 0, 0, 0};
Quaternion attitudeFRD = FLU2FRD(attitude); // MAVLink uses FRD coordinate system
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
time, attitude.w, attitude.x, attitude.y, attitude.z, rates.x, rates.y, rates.z, zeroQuat);
time, attitudeFRD.w, attitudeFRD.x, attitudeFRD.y, attitudeFRD.z, rates.x, rates.y, rates.z, zeroQuat);
sendMessage(&msg);
mavlink_msg_rc_channels_scaled_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0,
@@ -83,6 +84,7 @@ void receiveMavlink() {
void handleMavlink(const void *_msg) {
mavlink_message_t *msg = (mavlink_message_t *)_msg;
if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
mavlink_manual_control_t manualControl;
mavlink_msg_manual_control_decode(msg, &manualControl);
@@ -92,9 +94,77 @@ void handleMavlink(const void *_msg) {
controls[RC_CHANNEL_YAW] = manualControl.r / 1000.0f * MAVLINK_CONTROL_SCALE;
controls[RC_CHANNEL_MODE] = 1; // STAB mode
controls[RC_CHANNEL_ARMED] = 1; // armed
controlsTime = t;
if (abs(controls[RC_CHANNEL_YAW]) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controls[RC_CHANNEL_YAW] = 0;
}
if (msg->msgid == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
mavlink_message_t msg;
for (int i = 0; i < parametersCount(); i++) {
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
getParameterName(i), getParameter(i), MAV_PARAM_TYPE_REAL32, parametersCount(), i);
sendMessage(&msg);
}
}
if (msg->msgid == MAVLINK_MSG_ID_PARAM_REQUEST_READ) {
mavlink_param_request_read_t paramRequestRead;
mavlink_msg_param_request_read_decode(msg, &paramRequestRead);
char name[16 + 1];
strlcpy(name, paramRequestRead.param_id, sizeof(name)); // param_id might be not null-terminated
float value = strlen(name) == 0 ? getParameter(paramRequestRead.param_index) : getParameter(name);
if (paramRequestRead.param_index != -1) {
memcpy(name, getParameterName(paramRequestRead.param_index), 16);
}
mavlink_message_t msg;
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
name, value, MAV_PARAM_TYPE_REAL32, parametersCount(), paramRequestRead.param_index);
sendMessage(&msg);
}
if (msg->msgid == MAVLINK_MSG_ID_PARAM_SET) {
mavlink_param_set_t paramSet;
mavlink_msg_param_set_decode(msg, &paramSet);
char name[16 + 1];
strlcpy(name, paramSet.param_id, sizeof(name)); // param_id might be not null-terminated
setParameter(name, paramSet.param_value);
// send ack
mavlink_message_t msg;
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
paramSet.param_id, paramSet.param_value, MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
sendMessage(&msg);
}
if (msg->msgid == MAVLINK_MSG_ID_MISSION_REQUEST_LIST) { // handle to make qgc happy
mavlink_message_t msg;
mavlink_msg_mission_count_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, 0, 0, 0, MAV_MISSION_TYPE_MISSION, 0);
sendMessage(&msg);
}
// Handle commands
if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
mavlink_command_long_t commandLong;
mavlink_msg_command_long_decode(msg, &commandLong);
mavlink_message_t ack;
mavlink_message_t response;
if (commandLong.command == MAV_CMD_REQUEST_MESSAGE && commandLong.param1 == MAVLINK_MSG_ID_AUTOPILOT_VERSION) {
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, commandLong.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg->sysid, msg->compid);
sendMessage(&ack);
mavlink_msg_autopilot_version_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &response,
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MAVLINK2, 1, 0, 1, 1, 0, 0, 0, 0, 0, 0, 0);
sendMessage(&response);
} else {
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, commandLong.command, MAV_RESULT_UNSUPPORTED, UINT8_MAX, 0, msg->sysid, msg->compid);
sendMessage(&ack);
}
}
}
// Convert Forward-Left-Up to Forward-Right-Down quaternion
inline Quaternion FLU2FRD(const Quaternion &q) {
return Quaternion(q.w, q.x, -q.y, -q.z);
}
#endif

View File

@@ -1,69 +1,39 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Motors output control
// Motors output control using MOSFETs
// In case of using ESC, use this version of the code: https://gist.github.com/okalachev/8871d3a94b6b6c0a298f41a4edd34c61.
// Motor: 8520 3.7V
// ESC: KINGDUO Micro Mini 4A 1S Brushed Esc 3.6-6V
#define MOTOR_0_PIN 12
#define MOTOR_1_PIN 13
#define MOTOR_2_PIN 14
#define MOTOR_3_PIN 15
#define MOTOR_0_PIN 12 // rear left
#define MOTOR_1_PIN 13 // rear right
#define MOTOR_2_PIN 14 // front right
#define MOTOR_3_PIN 15 // front left
#define PWM_FREQUENCY 200
#define PWM_RESOLUTION 8
#define PWM_NEUTRAL 1500
#define PWM_MIN 1600
#define PWM_MAX 2300
#define PWM_REVERSE_MIN 1400
#define PWM_REVERSE_MAX 700
void setupMotors() {
Serial.println("Setup Motors");
// configure PWM channels
ledcSetup(0, PWM_FREQUENCY, PWM_RESOLUTION);
ledcSetup(1, PWM_FREQUENCY, PWM_RESOLUTION);
ledcSetup(2, PWM_FREQUENCY, PWM_RESOLUTION);
ledcSetup(3, PWM_FREQUENCY, PWM_RESOLUTION);
// attach channels to motor pins
ledcAttachPin(MOTOR_0_PIN, 0);
ledcAttachPin(MOTOR_1_PIN, 1);
ledcAttachPin(MOTOR_2_PIN, 2);
ledcAttachPin(MOTOR_3_PIN, 3);
// configure pins
ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
ledcAttach(MOTOR_1_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
ledcAttach(MOTOR_2_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
sendMotors();
Serial.println("Motors initialized");
}
uint16_t getPWM(float val, int n) {
if (val == 0) {
return PWM_NEUTRAL;
} else if (val > 0) {
return mapff(val, 0, 1, PWM_MIN, PWM_MAX);
} else {
return mapff(val, 0, -1, PWM_REVERSE_MIN, PWM_REVERSE_MAX);
}
}
uint8_t pwmToDutyCycle(uint16_t pwm) {
return map(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
uint8_t signalToDutyCycle(float control) {
float duty = mapff(control, 0, 1, 0, (1 << PWM_RESOLUTION) - 1);
return round(constrain(duty, 0, (1 << PWM_RESOLUTION) - 1));
}
void sendMotors() {
ledcWrite(0, pwmToDutyCycle(getPWM(motors[0], 0)));
ledcWrite(1, pwmToDutyCycle(getPWM(motors[1], 1)));
ledcWrite(2, pwmToDutyCycle(getPWM(motors[2], 2)));
ledcWrite(3, pwmToDutyCycle(getPWM(motors[3], 3)));
}
void fullMotorTest(int n, bool reverse) {
printf("Full test for motor %d\n", n);
for (int pwm = PWM_NEUTRAL; pwm <= 2300 && pwm >= 700; pwm += reverse ? -100 : 100) {
printf("Motor %d: %d\n", n, pwm);
ledcWrite(n, pwmToDutyCycle(pwm));
delay(3000);
}
printf("Motor %d: %d\n", n, PWM_NEUTRAL);
ledcWrite(n, pwmToDutyCycle(PWM_NEUTRAL));
ledcWrite(MOTOR_0_PIN, signalToDutyCycle(motors[0]));
ledcWrite(MOTOR_1_PIN, signalToDutyCycle(motors[1]));
ledcWrite(MOTOR_2_PIN, signalToDutyCycle(motors[2]));
ledcWrite(MOTOR_3_PIN, signalToDutyCycle(motors[3]));
}

133
flix/parameters.ino Normal file
View File

@@ -0,0 +1,133 @@
#pragma once
#include <Preferences.h>
#include <vector>
extern float channelNeutral[RC_CHANNELS];
extern float channelMax[RC_CHANNELS];
Preferences storage;
struct Parameter {
const char *name;
float *variable;
float value; // cache
};
Parameter parameters[] = {
// control
{"ROLLRATE_P", &rollRatePID.p},
{"ROLLRATE_I", &rollRatePID.i},
{"ROLLRATE_D", &rollRatePID.d},
{"ROLLRATE_I_LIM", &rollRatePID.windup},
{"PITCHRATE_P", &pitchRatePID.p},
{"PITCHRATE_I", &pitchRatePID.i},
{"PITCHRATE_D", &pitchRatePID.d},
{"PITCHRATE_I_LIM", &pitchRatePID.windup},
{"YAWRATE_P", &yawRatePID.p},
{"YAWRATE_I", &yawRatePID.i},
{"YAWRATE_D", &yawRatePID.d},
{"ROLL_P", &rollPID.p},
{"ROLL_I", &rollPID.i},
{"ROLL_D", &rollPID.d},
{"PITCH_P", &pitchPID.p},
{"PITCH_I", &pitchPID.i},
{"PITCH_D", &pitchPID.d},
{"YAW_P", &yawPID.p},
// imu
{"ACC_BIAS_X", &accBias.x},
{"ACC_BIAS_Y", &accBias.y},
{"ACC_BIAS_Z", &accBias.z},
{"ACC_SCALE_X", &accScale.x},
{"ACC_SCALE_Y", &accScale.y},
{"ACC_SCALE_Z", &accScale.z},
// {"GYRO_BIAS_X", &gyroBias.x},
// {"GYRO_BIAS_Y", &gyroBias.y},
// {"GYRO_BIAS_Z", &gyroBias.z},
// rc
{"RC_NEUTRAL_0", &channelNeutral[0]},
{"RC_NEUTRAL_1", &channelNeutral[1]},
{"RC_NEUTRAL_2", &channelNeutral[2]},
{"RC_NEUTRAL_3", &channelNeutral[3]},
{"RC_NEUTRAL_4", &channelNeutral[4]},
{"RC_NEUTRAL_5", &channelNeutral[5]},
{"RC_NEUTRAL_6", &channelNeutral[6]},
{"RC_NEUTRAL_7", &channelNeutral[7]},
{"RC_MAX_0", &channelMax[0]},
{"RC_MAX_1", &channelMax[1]},
{"RC_MAX_2", &channelMax[2]},
{"RC_MAX_3", &channelMax[3]},
{"RC_MAX_4", &channelMax[4]},
{"RC_MAX_5", &channelMax[5]},
{"RC_MAX_6", &channelMax[6]},
{"RC_MAX_7", &channelMax[7]}
};
void setupParameters() {
storage.begin("flix", false);
// Read parameters from storage
for (auto &parameter : parameters) {
if (!storage.isKey(parameter.name)) {
Serial.printf("Define new parameter %s = %f\n", parameter.name, *parameter.variable);
storage.putFloat(parameter.name, *parameter.variable);
}
*parameter.variable = storage.getFloat(parameter.name, *parameter.variable);
parameter.value = *parameter.variable;
}
}
int parametersCount() {
return sizeof(parameters) / sizeof(parameters[0]);
}
const char *getParameterName(int index) {
return parameters[index].name;
}
float getParameter(int index) {
return *parameters[index].variable;
}
float getParameter(const char *name) {
for (auto &parameter : parameters) {
if (strcmp(parameter.name, name) == 0) {
return *parameter.variable;
}
}
return NAN;
}
bool setParameter(const char *name, const float value) {
for (auto &parameter : parameters) {
if (strcmp(parameter.name, name) == 0) {
*parameter.variable = value;
return true;
}
}
return false;
}
void flushParameters() {
static float lastFlush = 0;
if (t - lastFlush < 1) return; // flush once per second
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
lastFlush = t;
for (auto &parameter : parameters) {
if (parameter.value == *parameter.variable) continue;
if (isnan(parameter.value) && isnan(*parameter.variable)) continue; // handle NAN != NAN
storage.putFloat(parameter.name, *parameter.variable);
parameter.value = *parameter.variable;
}
}
void printParameters() {
for (auto &parameter : parameters) {
Serial.printf("%s = %g\n", parameter.name, *parameter.variable);
}
}
void resetParameters() {
storage.clear();
ESP.restart();
}

View File

@@ -75,7 +75,7 @@ public:
float sqz = z * z;
float sqw = w * w;
// Cases derived from https://orbitalstation.wordpress.com/tag/quaternion/
float sarg = -2 * (x * z - w * y) / (sqx + sqy + sqz + sqw); /* normalization added from urdfom_headers */
float sarg = -2 * (x * z - w * y) / (sqx + sqy + sqz + sqw);
if (sarg <= -0.99999) {
euler.x = 0;
euler.y = -0.5 * PI;

View File

@@ -5,11 +5,10 @@
#include <SBUS.h>
// NOTE: use 'cr' command to calibrate the RC and put the values here
int channelNeutral[] = {995, 883, 200, 972, 512, 512};
int channelMax[] = {1651, 1540, 1713, 1630, 1472, 1472};
float channelNeutral[RC_CHANNELS] = {NAN}; // first element NAN means not calibrated
float channelMax[RC_CHANNELS];
SBUS RC(Serial2);
SBUS RC(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
void setupRC() {
Serial.println("Setup RC");
@@ -21,10 +20,12 @@ void readRC() {
SBUSData data = RC.data();
memcpy(channels, data.ch, sizeof(channels)); // copy channels data
normalizeRC();
controlsTime = t;
}
}
void normalizeRC() {
if (isnan(channelNeutral[0])) return; // skip if not calibrated
for (uint8_t i = 0; i < RC_CHANNELS; i++) {
controls[i] = mapf(channels[i], channelNeutral[i], channelMax[i], 0, 1);
}

View File

@@ -12,16 +12,16 @@ void step() {
dt = 0; // assume dt to be zero on first step and on reset
}
computeLoopFreq();
computeLoopRate();
}
void computeLoopFreq() {
void computeLoopRate() {
static float windowStart = 0;
static uint32_t freq = 0;
freq++;
static uint32_t rate = 0;
rate++;
if (t - windowStart >= 1) { // 1 second window
loopFreq = freq;
loopRate = rate;
windowStart = t;
freq = 0;
rate = 0;
}
}

View File

@@ -15,14 +15,6 @@ float mapff(float x, float in_min, float in_max, float out_min, float out_max) {
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
int8_t sign(float x) {
return (x > 0) - (x < 0);
}
float randomFloat(float min, float max) {
return min + (max - min) * (float)rand() / RAND_MAX;
}
// Wrap angle to [-PI, PI)
float wrapAngle(float angle) {
angle = fmodf(angle, 2 * PI);

View File

@@ -7,6 +7,7 @@
#include <cmath>
#include <string>
#include <stdint.h>
#include <stdio.h>
#include <unistd.h>
#include <sys/poll.h>
@@ -26,15 +27,27 @@ long map(long x, long in_min, long in_max, long out_min, long out_max) {
return (delta * rise) / run + out_min;
}
size_t strlcpy(char* dst, const char* src, size_t len) {
size_t l = strlen(src);
size_t i = 0;
while (i < len - 1 && *src != '\0') { *dst++ = *src++; i++; }
*dst = '\0';
return l;
}
class __FlashStringHelper;
// Arduino String partial implementation
// https://www.arduino.cc/reference/en/language/variables/data-types/stringobject/
class String: public std::string {
public:
String(const char *str = "") : std::string(str) {}
long toInt() const { return atol(this->c_str()); }
float toFloat() const { return atof(this->c_str()); }
bool isEmpty() const { return this->empty(); }
void toCharArray(char *buf, unsigned int bufsize, unsigned int index = 0) const {
strlcpy(buf, this->c_str() + index, bufsize);
}
};
class Print;
@@ -116,7 +129,7 @@ public:
int read() {
if (available()) {
char c;
::read(STDIN_FILENO, &c, 1); // use raw read to avoid C++ buffering
size_t res = ::read(STDIN_FILENO, &c, 1); // use raw read to avoid C++ buffering
// https://stackoverflow.com/questions/45238997/does-getchar-function-has-its-own-buffer-to-store-remaining-input
return c;
}
@@ -128,12 +141,18 @@ public:
HardwareSerial Serial, Serial2;
class EspClass {
public:
void restart() { Serial.println("Ignore reboot in simulation"); }
} ESP;
void delay(uint32_t ms) {
std::this_thread::sleep_for(std::chrono::milliseconds(ms));
}
unsigned long __micros;
unsigned long __resetTime = 0;
unsigned long micros() {
return __micros;
return __micros + __resetTime; // keep the time monotonic
}

View File

@@ -15,6 +15,7 @@ set(CMAKE_BUILD_TYPE RelWithDebInfo)
add_library(flix SHARED simulator.cpp)
target_link_libraries(flix ${GAZEBO_LIBRARIES} ${SDL2_LIBRARIES})
target_include_directories(flix PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
target_compile_options(flix PRIVATE -Wno-address-of-packed-member) # disable unneeded mavlink warnings
# Include dir for MAVLink-Arduino library
target_include_directories(flix PUBLIC $ENV{HOME}/Arduino/libraries/MAVLink)

63
gazebo/Preferences.h Normal file
View File

@@ -0,0 +1,63 @@
// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Partial implementation of the ESP32 Preferences library for the simulation
#include <map>
#include <fstream>
#include "util.h"
class Preferences {
private:
std::map<std::string, float> storage;
std::string storagePath;
void readFromFile() {
std::ifstream file(storagePath);
std::string key;
float value;
while (file >> key >> value) {
storage[key] = value;
}
}
void writeToFile() {
std::ofstream file(storagePath);
for (auto &pair : storage) {
file << pair.first << " " << pair.second << std::endl;
}
}
public:
bool begin(const char *name, bool readOnly = false, const char *partition_label = NULL) {
storagePath = getPluginPath().parent_path() / (std::string(name) + ".txt");
gzmsg << "Preferences initialized: " << storagePath << std::endl;
readFromFile();
return true;
}
void end();
bool isKey(const char *key) {
return storage.find(key) != storage.end();
}
size_t putFloat(const char *key, float value) {
storage[key] = value;
writeToFile();
return sizeof(value);
}
float getFloat(const char *key, float defaultValue = NAN) {
if (!isKey(key)) {
return defaultValue;
}
return storage[key];
}
bool clear() {
storage.clear();
writeToFile();
return true;
}
};

View File

@@ -12,13 +12,12 @@ struct SBUSData {
class SBUS {
public:
SBUS(HardwareSerial& bus, const bool inv = true) {};
SBUS(HardwareSerial& bus, const int8_t rxpin, const int8_t txpin, const bool inv = true) {};
void begin() {};
bool read() { return joystickGet(); };
bool read() { return joystickInitialized; };
SBUSData data() {
SBUSData data;
for (uint8_t i = 0; i < 16; i++) {
data.ch[i] = channels[i];
}
joystickGet(data.ch);
return data;
};
};

View File

@@ -10,7 +10,7 @@
#include "Arduino.h"
#include "wifi.h"
#define RC_CHANNELS 6
#define RC_CHANNELS 16
#define MOTOR_REAR_LEFT 0
#define MOTOR_FRONT_LEFT 3
@@ -19,22 +19,24 @@
#define WIFI_ENABLED 1
#define ONE_G 9.80665
float t = NAN;
float dt;
float loopFreq;
float loopRate;
float motors[4];
int16_t channels[16]; // raw rc channels
float controls[RC_CHANNELS];
float controlsTime;
Vector acc;
Vector gyro;
Vector rates;
Quaternion attitude;
// declarations
void computeLoopFreq();
void computeLoopRate();
void applyGyro();
void applyAcc();
void signalizeHorizontality();
void control();
void interpretRC();
void controlAttitude();
@@ -43,17 +45,23 @@ void controlTorque();
void showTable();
bool motorsActive();
void cliTestMotor(uint8_t n);
String stringToken(char* str, const char* delim);
void normalizeRC();
void printRCCal();
void processMavlink();
void sendMavlink();
void sendMessage(const void *msg);
void receiveMavlink();
void handleMavlink(const void *_msg);
void failsafe();
void descend();
inline Quaternion FLU2FRD(const Quaternion &q);
// mocks
void setLED(bool on) {};
void calibrateGyro() { printf("Skip gyro calibrating\n"); };
void calibrateAccel() { printf("Skip accel calibrating\n"); };
void fullMotorTest(int n, bool reverse) { printf("Skip full motor test\n"); };
void sendMotors() {};
void printIMUCal() { printf("cal: N/A\n"); };
void printIMUInfo() {};
Vector accBias, gyroBias, accScale(1, 1, 1);

View File

@@ -9,7 +9,7 @@
</scene>
<gui>
<camera name="user_camera">
<pose>-2 -0.3 1.5 0 0.5 0.1</pose>
<pose>-2.3 0 1.1 0 0.3 0</pose>
</camera>
</gui>
<physics type="ode">
@@ -23,7 +23,7 @@
</include>
<include>
<uri>model://flix</uri>
<pose>0 0 0.2 0 0 0</pose>
<pose>0 0 0.3 0 0 0</pose>
</include>
</world>
</sdf>

View File

@@ -7,10 +7,6 @@
#include <gazebo/gazebo.hh>
#include <iostream>
// simulation calibration overrides, NOTE: use `cr` command and replace with the actual values
const int channelNeutralOverride[] = {-258, -258, -27349, 0, -27349, 0};
const int channelMaxOverride[] = {27090, 27090, 27090, 27090, -5676, 1};
#define RC_CHANNEL_ROLL 0
#define RC_CHANNEL_PITCH 1
#define RC_CHANNEL_THROTTLE 2
@@ -21,8 +17,6 @@ const int channelMaxOverride[] = {27090, 27090, 27090, 27090, -5676, 1};
SDL_Joystick *joystick;
bool joystickInitialized = false, warnShown = false;
void normalizeRC();
void joystickInit() {
SDL_Init(SDL_INIT_JOYSTICK);
joystick = SDL_JoystickOpen(0);
@@ -33,15 +27,9 @@ void joystickInit() {
gzwarn << "Joystick not found, begin waiting for joystick..." << std::endl;
warnShown = true;
}
// apply calibration overrides
extern int channelNeutral[RC_CHANNELS];
extern int channelMax[RC_CHANNELS];
memcpy(channelNeutral, channelNeutralOverride, sizeof(channelNeutralOverride));
memcpy(channelMax, channelMaxOverride, sizeof(channelMaxOverride));
}
bool joystickGet() {
bool joystickGet(int16_t ch[16]) {
if (!joystickInitialized) {
joystickInit();
return false;
@@ -49,8 +37,8 @@ bool joystickGet() {
SDL_JoystickUpdate();
for (uint8_t i = 0; i < 8; i++) {
channels[i] = SDL_JoystickGetAxis(joystick, i);
for (uint8_t i = 0; i < sizeof(channels) / sizeof(channels[0]); i++) {
ch[i] = SDL_JoystickGetAxis(joystick, i);
}
return true;
}

View File

@@ -13,15 +13,10 @@
<collision name="collision">
<geometry>
<box>
<size>0.125711 0.125711 0.022</size>
<size>0.095 0.095 0.0276</size>
</box>
</geometry>
</collision>
<visual name="body">
<geometry>
<mesh><uri>model://flix/flix.dae</uri></mesh>
</geometry>
</visual>
<sensor name="imu" type="imu">
<always_on>1</always_on>
<visualize>1</visualize>
@@ -63,6 +58,37 @@
</linear_acceleration>
</imu>
</sensor>
<visual name="body">
<geometry>
<mesh><uri>model://flix/flix.stl</uri></mesh>
</geometry>
<material>
<ambient>0.5 0.5 0.6 1</ambient>
<diffuse>0.5 0.5 0.6 1</diffuse>
<specular>0 0 0 1</specular>
<emissive>0 0 0 1</emissive>
</material>
</visual>
<visual name="prop0"><!-- rear left -->
<geometry><cylinder><radius>0.0275</radius><length>0</length></cylinder></geometry>
<pose>-0.04243 0.04243 0.0142 0 0 0</pose>
<material><ambient>0.8 0.3 0.3 0.5</ambient><diffuse>0.8 0.3 0.3 0.5</diffuse></material>
</visual>
<visual name="prop1"><!-- rear right -->
<geometry><cylinder><radius>0.0275</radius><length>0</length></cylinder></geometry>
<pose>-0.04243 -0.04243 0.0142 0 0 0</pose>
<material><ambient>0.8 0.3 0.3 0.5</ambient><diffuse>0.8 0.3 0.3 0.5</diffuse></material>
</visual>
<visual name="prop2"><!-- front right -->
<geometry><cylinder><radius>0.0275</radius><length>0</length></cylinder></geometry>
<pose>0.04243 -0.04243 0.0142 0 0 0</pose>
<material><ambient>1 1 1 0.5</ambient><diffuse>1 1 1 0.5</diffuse></material>
</visual>
<visual name="prop3"><!-- front left -->
<geometry><cylinder><radius>0.0275</radius><length>0</length></cylinder></geometry>
<pose>0.04243 0.04243 0.0142 0 0 0</pose>
<material><ambient>1 1 1 0.5</ambient><diffuse>1 1 1 0.5</diffuse></material>
</visual>
</link>
<plugin name="flix" filename="libflix.so"/>
</model>

BIN
gazebo/models/flix/flix.stl Normal file

Binary file not shown.

View File

@@ -17,15 +17,16 @@
#include "Arduino.h"
#include "flix.h"
#include "util.h"
#include "util.ino"
#include "rc.ino"
#include "time.ino"
#include "estimate.ino"
#include "control.ino"
#include "log.ino"
#include "parameters.ino"
#include "cli.ino"
#include "mavlink.ino"
#include "failsafe.ino"
#include "lpf.h"
using ignition::math::Vector3d;
@@ -47,15 +48,17 @@ public:
this->model = _parent;
this->body = this->model->GetLink("body");
this->imu = dynamic_pointer_cast<sensors::ImuSensor>(sensors::get_sensor(model->GetScopedName(true) + "::body::imu")); // default::flix::body::imu
this->updateConnection = event::Events::ConnectWorldUpdateBegin(bind(&ModelFlix::OnUpdate, this));
this->resetConnection = event::Events::ConnectWorldReset(bind(&ModelFlix::OnReset, this));
this->updateConnection = event::Events::ConnectWorldUpdateBegin(std::bind(&ModelFlix::OnUpdate, this));
this->resetConnection = event::Events::ConnectWorldReset(std::bind(&ModelFlix::OnReset, this));
initNode();
Serial.begin(0);
setupParameters();
gzmsg << "Flix plugin loaded" << endl;
}
void OnReset() {
attitude = Quaternion(); // reset estimated attitude
__resetTime += __micros;
gzmsg << "Flix plugin reset" << endl;
}
@@ -63,9 +66,9 @@ public:
__micros = model->GetWorld()->SimTime().Double() * 1000000;
step();
// read imu
gyro = flu2frd(imu->AngularVelocity());
acc = this->accFilter.update(flu2frd(imu->LinearAcceleration()));
// read virtual imu
gyro = Vector(imu->AngularVelocity().X(), imu->AngularVelocity().Y(), imu->AngularVelocity().Z());
acc = this->accFilter.update(Vector(imu->LinearAcceleration().X(), imu->LinearAcceleration().Y(), imu->LinearAcceleration().Z()));
// read rc
readRC();
@@ -75,7 +78,7 @@ public:
estimate();
// correct yaw to the actual yaw
attitude.setYaw(-this->model->WorldPose().Yaw());
attitude.setYaw(this->model->WorldPose().Yaw());
control();
parseInput();
@@ -84,6 +87,7 @@ public:
applyMotorForces();
publishTopics();
logData();
flushParameters();
}
void applyMotorForces() {

View File

@@ -1,14 +1,9 @@
#include <ignition/math/Vector3.hh>
#include <ignition/math/Pose3.hh>
#include <filesystem>
using ignition::math::Vector3d;
using ignition::math::Pose3d;
Pose3d flu2frd(const Pose3d& p) {
return ignition::math::Pose3d(p.Pos().X(), -p.Pos().Y(), -p.Pos().Z(),
p.Rot().W(), p.Rot().X(), -p.Rot().Y(), -p.Rot().Z());
}
Vector flu2frd(const Vector3d& v) {
return Vector(v.X(), -v.Y(), -v.Z());
std::filesystem::path getPluginPath() {
Dl_info dl_info;
if (dladdr((void*)&getPluginPath, &dl_info) == 0) {
throw std::runtime_error("Unable to determine plugin path using dladdr.");
}
return std::filesystem::path(dl_info.dli_fname);
}

View File

@@ -18,7 +18,7 @@ int wifiSocket;
void setupWiFi() {
wifiSocket = socket(AF_INET, SOCK_DGRAM, 0);
sockaddr_in addr;
sockaddr_in addr; // local address
addr.sin_family = AF_INET;
addr.sin_addr.s_addr = INADDR_ANY;
addr.sin_port = htons(WIFI_UDP_PORT_LOCAL);
@@ -30,7 +30,7 @@ void setupWiFi() {
void sendWiFi(const uint8_t *buf, int len) {
if (wifiSocket == 0) setupWiFi();
sockaddr_in addr;
sockaddr_in addr; // remote address
addr.sin_family = AF_INET;
addr.sin_addr.s_addr = INADDR_BROADCAST; // send UDP broadcast
addr.sin_port = htons(WIFI_UDP_PORT_REMOTE);

61
tools/check_c_cpp_properties.py Executable file
View File

@@ -0,0 +1,61 @@
#!/usr/bin/env python3
import os
import platform
import json
import re
path = '.vscode/c_cpp_properties.json' if os.path.exists('./.vscode/c_cpp_properties.json') else '../.vscode/c_cpp_properties.json'
txt = open(path).read()
# remove comments
txt = re.sub(r'//.*', '', txt)
props = json.loads(txt)
env = props.get('env', {})
env['workspaceFolder'] = '.'
def check_path(s):
source = s
# replace env
for key, value in env.items():
s = s.replace('${' + key + '}', value)
# remove globs from the end
if s.endswith('**'):
s = s[:-2]
elif s.endswith('*'):
s = s[:-1]
s = os.path.expanduser(s)
if s == '':
s = '.'
print('Check', source, '->', s)
assert os.path.exists(s), 'Path does not exist: ' + s
# linux, macos or windows:
platform = platform.system().lower()
if platform == 'darwin':
platform = 'mac'
elif platform == 'windows':
platform = 'win32'
elif platform == 'linux':
pass
else:
raise Exception('Unknown platform: ' + platform)
for configuration in props['configurations']:
if platform not in configuration['name'].lower():
print('Skip configuration', configuration['name'])
continue
print('Check configuration', configuration['name'])
for include_path in configuration.get('includePath', []):
check_path(include_path)
for forced_include in configuration.get('forcedInclude', []):
check_path(forced_include)
for browse in configuration.get('browse', {}).get('path', []):
check_path(browse)
if 'compilerPath' in configuration:
check_path(configuration['compilerPath'])

46
tools/csv_to_mcap.py Executable file
View File

@@ -0,0 +1,46 @@
#!/usr/bin/env python3
"""Convert CSV log file to MCAP file.
Usage:
csv_to_mcap.py <csv_file> [<mcap_file>]
"""
import csv
import json
import docopt
from mcap.writer import Writer
args = docopt.docopt(__doc__)
input_file = args['<csv_file>']
output_file = args['<mcap_file>'] or input_file.replace('.csv', '.mcap')
if input_file == output_file:
raise ValueError('Input and output files are the same')
csv_file = open(input_file, 'r')
csv_reader = csv.reader(csv_file, delimiter=',')
header = next(csv_reader)
mcap_file = open(output_file, 'wb')
writer = Writer(mcap_file)
writer.start()
properties = {key: {'type': 'number'} for key in header}
schema_id = writer.register_schema(
name="state",
encoding="jsonschema",
data=json.dumps({"type": "object", "properties": properties}).encode(),
)
channel_id = writer.register_channel(
schema_id=schema_id,
topic="state",
message_encoding="json",
)
for row in csv_reader:
data = {key: float(value) for key, value in zip(header, row)}
timestamp = round(float(row[0]) * 1e9)
writer.add_message(channel_id=channel_id, log_time=timestamp, data=json.dumps(data).encode(), publish_time=timestamp,)
writer.finish()

View File

@@ -0,0 +1,23 @@
cmake_minimum_required(VERSION 3.15)
project(csv_to_ulog)
include(FetchContent)
set(CMAKE_CXX_STANDARD 17)
FetchContent_Declare(
ulog_cpp
GIT_REPOSITORY https://github.com/PX4/ulog_cpp.git
GIT_TAG cf24ec6
)
FetchContent_Declare(
rapidcsv
GIT_REPOSITORY https://github.com/d99kris/rapidcsv.git
GIT_TAG v8.82
)
FetchContent_MakeAvailable(ulog_cpp)
FetchContent_MakeAvailable(rapidcsv)
add_executable(csv_to_ulog csv_to_ulog.cpp)
target_link_libraries(csv_to_ulog PUBLIC ulog_cpp::ulog_cpp)
target_include_directories(csv_to_ulog PUBLIC ${rapidcsv_SOURCE_DIR}/src)

View File

@@ -0,0 +1,20 @@
# csv_to_ulog
Tool for converting CSV flight logs to ULog format so they can be analyzed using [FlightPlot](https://github.com/PX4/FlightPlot) software.
To build, go to the `<flix>/tools/csv_to_ulog` directory and run:
```bash
mkdir build
cd build
cmake ..
make
```
Convert a CSV file to ULog:
```bash
./csv_to_ulog log_file.csv
```
ULog file will be saved in the same directory.

View File

@@ -0,0 +1,72 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Tool for conversion CSV log file to ULog format
#include <ulog_cpp/simple_writer.hpp>
#include <rapidcsv.h>
#include <vector>
#include <string>
#include <filesystem>
using std::vector;
using std::string;
struct Data {
uint64_t timestamp;
float values[30];
};
int main(int argc, char** argv)
{
if (argc < 2) {
printf("Usage: %s file.csv [file.ulg]\n", argv[0]);
return -1;
}
// check input file exists
if (!std::filesystem::exists(argv[1])) {
printf("Input file \"%s\" does not exist\n", argv[1]);
return -1;
}
// open csv file
rapidcsv::Document csv(argv[1]);
auto columns = csv.GetColumnNames();
// open ulog file
string ulog_file;
if (argc < 3) {
ulog_file = std::filesystem::path(argv[1]).replace_extension(".ulg").string();
} else {
ulog_file = argv[2];
}
ulog_cpp::SimpleWriter writer(ulog_file.c_str(), 0);
writer.writeInfo("sys_name", "flix");
vector<ulog_cpp::Field> fields;
fields.push_back(ulog_cpp::Field("uint64_t", "timestamp"));
columns.erase(columns.begin()); // remove timestamp column
for (auto& column : columns) {
// Valid field name for ULog: [a-z0-9_]+
std::replace(column.begin(), column.end(), '.', '_'); // replace dots with underscores
std::transform(column.begin(), column.end(), column.begin(), [](unsigned char c) { return std::tolower(c); }); // lowercase column name
fields.push_back(ulog_cpp::Field("float", column));
}
const char* msg_name = "state";
writer.writeMessageFormat(msg_name, fields);
writer.headerComplete();
const uint16_t msg_id = writer.writeAddLoggedMessage(msg_name);
for (size_t i = 0; i < csv.GetRowCount(); i++) {
Data data;
data.timestamp = csv.GetCell<float>(0, i) * 1000000.0;
for (size_t j = 1; j <= columns.size(); j++) {
data.values[j - 1] = csv.GetCell<float>(j, i);
}
writer.writeData(msg_id, data);
}
}

View File

@@ -1,2 +1,3 @@
docopt
matplotlib
mcap