136 Commits
v1.0 ... v1.1

Author SHA1 Message Date
Oleg Kalachev
3fdebf39d8 Fix mavlink disconnection in pauses in cli commands
Implement pause function that proceeds processing mavlink.
Use temporal workaround for simulation, as micros function gives the same result on the same simulation step.
2025-02-28 19:25:41 +03:00
Oleg Kalachev
5bf2e06c5a Use natural order of ino files includes in simulation
In Arduino, ino files are included in alphabetical order.
Cleanup unused function declarations in simulation, add missing.
Rename flu to frd function to match the code style.
2025-02-28 19:06:58 +03:00
Oleg Kalachev
4e3e8c70b0 Update main book illustration 2025-02-28 03:17:09 +03:00
Oleg Kalachev
bda44fca02 Remove dt multiplier from acc correction and increase acc weight
More classical complementary filter implementation
Increase effective accelerometer weight for faster convergence
2025-02-28 00:51:16 +03:00
Oleg Kalachev
e66f6563a5 Add custom Wi-Fi control description by @pavelkabakov #11
Co-authored-by: Pavel Kabakov <110939392+pavelkabakov@users.noreply.github.com>
2025-02-26 01:08:36 +03:00
Oleg Kalachev
95084c167c Add user project by jeka_chex 2025-02-26 00:55:14 +03:00
Oleg Kalachev
931b2066bb Minor book fix 2025-02-26 00:20:50 +03:00
Oleg Kalachev
a2cf318189 Check target system id in mavlink messages
Skip messages addressed to other systems
2025-02-26 00:08:23 +03:00
Oleg Kalachev
83a8dcd63e Cleanup mavlink subsystem code 2025-02-24 13:06:38 +03:00
Oleg Kalachev
c62e536b50 Put last control time in RC control mavlink message instead of send time 2025-02-22 20:07:26 +03:00
Oleg Kalachev
287a4b5a71 Fix accel calibration via mavlink console
Add 5 s timeout as waiting for enter is not implemented for mavlink console yet
2025-02-18 13:01:44 +03:00
Oleg Kalachev
d60628e14d Support MAVLink console
Implement receiving and sending SERIAL_CONTROL message
Use global defined print function instead of Serial.printf
2025-02-18 10:33:01 +03:00
Oleg Kalachev
bfef7bd26a Remove non-nessesary printArray function 2025-02-18 10:26:59 +03:00
Oleg Kalachev
e3c6a0d4df Make some clarifications regarding imu check in troubleshooting 2025-02-18 10:18:27 +03:00
Oleg Kalachev
9566a4a503 Add parameters access method to build article 2025-02-18 10:14:39 +03:00
Oleg Kalachev
e54e0e8c48 Make all the basic functionality work without the imu 2025-02-17 19:44:18 +03:00
Oleg Kalachev
149c62568f Refactor CLI submodule
Move command parsing to doCommand
Parse command with splitString instead of stringToken
Trim commands
Move cliTestMotor to the bottom
Rename parseInput to handleInput, which is more clear
Move motor test function to motors.ino
2025-02-17 15:51:58 +03:00
Oleg Kalachev
641e711e67 Minor fix in joystick support for simulation
Don't use channels variable as it breaks code isolation
2025-02-15 03:29:09 +03:00
Oleg Kalachev
f2171f2db4 Minor clarification in RC receiver connection table 2025-02-12 11:10:04 +03:00
Oleg Kalachev
6ed6ef3e8c Assume armed is true if armed channel is not defined 2025-02-12 10:15:42 +03:00
Oleg Kalachev
083db659c6 Improve RC reading in calibration process 2025-02-12 10:15:13 +03:00
Oleg Kalachev
ce1223e82d Allow CI simulator build under macOS if manually triggered 2025-02-12 06:24:51 +03:00
Peter A. Ukhov
437ce81a68 Add video for flix2 by Peter Ukhov (#10)
Co-authored-by: Oleg Kalachev <okalachev@gmail.com>
2025-02-12 05:01:56 +03:00
Oleg Kalachev
42f318c6df Another update of hall of fame page 2025-02-11 14:02:15 +03:00
Oleg Kalachev
1450c793b7 Update hall of fame page 2025-02-11 12:11:22 +03:00
Oleg Kalachev
3ed4143ba0 Simplify WIFI_ENABLED macro test 2025-02-08 02:41:09 +03:00
Oleg Kalachev
33adf33f0e Add proper command to install arduino-cli on Linux in instructions 2025-02-01 22:56:09 +03:00
Oleg Kalachev
373c0f117a Update user builds page 2025-01-31 11:15:57 +03:00
Oleg Kalachev
0cb2eb5fac Update upload-artifact action to fix build 2025-01-31 03:32:09 +03:00
Oleg Kalachev
70f63bfbe9 Add hall of fame page 2025-01-31 03:19:49 +03:00
Oleg Kalachev
15fbe34d19 Add failsafe to prevent arming without prior zero throttle 2025-01-24 16:23:59 +03:00
Zatupitel
7d2d54a94d Fix working on ESP32-S3 (#8)
Disable brown-out detector in a more correct way: clear only enable bit instead of clearing the whole register.

---------

Co-authored-by: Oleg Kalachev <okalachev@gmail.com>
2025-01-24 14:35:44 +03:00
Oleg Kalachev
60fbe1c450 Fix firmware build with Wi-Fi disabled 2025-01-24 13:50:07 +03:00
Oleg Kalachev
40043768fe Add test on building the firmware without Wi-Fi to Actions 2025-01-24 13:40:27 +03:00
Oleg Kalachev
dcfe39f8c9 Move SBUS RC declaration to the top 2025-01-24 12:10:48 +03:00
Oleg Kalachev
b2100d10da Add motors voltage notice in troubleshooting article 2025-01-23 15:03:19 +03:00
Oleg Kalachev
fd6bc42e9e Fix critical typo in RC loss fail-safe 2025-01-23 00:34:59 +03:00
Oleg Kalachev
c01bac0d0a Update Flix image for frame version 1.1 2025-01-22 22:11:59 +03:00
Oleg Kalachev
f65c668ca1 Add brief assembly guide article 2025-01-22 01:44:31 +03:00
Oleg Kalachev
64cf5929e2 Add new frame models
Version 1.1
2025-01-22 01:42:42 +03:00
Oleg Kalachev
a9e5b2d5ca Add board pin names for motors to readme 2025-01-21 23:42:28 +03:00
Oleg Kalachev
6028b8a617 Catch port bind error in simulation 2025-01-17 17:38:47 +03:00
Oleg Kalachev
b19270f14e Minor cleanups and fixes 2025-01-17 12:30:12 +03:00
Oleg Kalachev
740121a88e Check if requested parameters indexes are correct
In case if gcs gets crazy and requests incorrect parameter index
2025-01-14 21:14:04 +03:00
Oleg Kalachev
b915e47f33 Add instructions on using USB remote control via QGroundControl app 2025-01-14 15:07:02 +03:00
Oleg Kalachev
7effd92043 Make MAVLink control scale a parameter 2025-01-14 14:51:34 +03:00
Oleg Kalachev
26bb4d2b3f Add link to working iOS QGroundControl build 2025-01-13 04:23:19 +03:00
Oleg Kalachev
70f5186c1b Use double for storing time instead of float
Float precision may be not enough after some time of operating
2025-01-12 19:58:36 +03:00
Oleg Kalachev
d4e04c46cd Add time command to cli 2025-01-12 19:50:00 +03:00
Oleg Kalachev
48d21a911f Add missing const qualifiers 2025-01-12 19:46:50 +03:00
Oleg Kalachev
f456e10177 Increase motors PWM frequency to 1000
To match the main loop frequency
2025-01-12 15:35:05 +03:00
Oleg Kalachev
ac54c954aa Cleanup 2025-01-11 04:31:53 +03:00
Oleg Kalachev
9e4a2c5ffc Move controlsTime variable to rc.ino 2025-01-11 00:28:31 +03:00
Oleg Kalachev
7bf5ee330b Add link to contributed circuit diagram to readme 2025-01-10 10:52:31 +03:00
Oleg Kalachev
b9e30be98c Better support for ESCs, add PWM_STOP parameter 2025-01-10 10:49:40 +03:00
Oleg Kalachev
821e6b105e Make channels definition to rc.ino
It's also planned to parametrize them later
2025-01-10 09:37:48 +03:00
Oleg Kalachev
568f9dd5b1 Minor code improvements 2025-01-10 08:59:09 +03:00
Oleg Kalachev
698cc3d9b8 Global variables cleanups
Remove unused PID objects for cli
Move loopRate to time.ino
2025-01-10 07:10:30 +03:00
Oleg Kalachev
85172cdcc8 Make util module header instead of .ino-file 2025-01-10 06:51:14 +03:00
Oleg Kalachev
08b14d1d76 Minor cleanup 2025-01-10 06:04:32 +03:00
Oleg Kalachev
95824e3b75 Make max tilt and max angle rates MAVLink parameters
Also decrease default max yaw rate to 300 degrees
2025-01-10 06:00:06 +03:00
Oleg Kalachev
0a45614751 Move motorsActive function to motors.ino 2025-01-09 11:30:04 +03:00
Oleg Kalachev
c8109af04f Make ONE_G definition const and move to utils.ino 2025-01-09 11:24:40 +03:00
Oleg Kalachev
404ceed851 Make motor indexes definition const int and move them to motors.ino
Remove motor indexes definitions from flix.ino
Add motors.ino to simulation code and implement required mocks
2025-01-09 11:14:18 +03:00
Oleg Kalachev
72033cdd75 Increase motors PWM resolution to 12 bits 2025-01-09 11:02:38 +03:00
Oleg Kalachev
3088ade743 Fix getDutyCycle return type to make it possible to increase resolution 2025-01-09 11:02:21 +03:00
Oleg Kalachev
c2a9d36d4e Add small delay before gyro calibration 2025-01-09 10:06:15 +03:00
Oleg Kalachev
ca409396c7 Add missing const qualifiers to some quaternion methods 2025-01-09 10:02:53 +03:00
Oleg Kalachev
ca032abc03 Implement rotate method for quaternions as replace for multiplication
Vector rotating method is renamed from `rotate` to `rotateVector` to avoid inconsistent object and argument order in different `rotate` methods
2025-01-09 09:56:49 +03:00
Oleg Kalachev
5d10446aaf Bring back possibility to use ESCs for motors 2025-01-09 07:43:49 +03:00
Oleg Kalachev
87cf44371b Some fixes and updates to readme and other articles 2025-01-09 03:46:54 +03:00
Oleg Kalachev
5ee407af8d Update ESP32-core to 3.1.0 2025-01-06 21:01:39 +03:00
Oleg Kalachev
59cb55cf94 Use ubuntu-20.04 runner to build simulator in CI
The latest Ubuntu Gazebo 11 officially supports is Ubuntu 20.04
2025-01-06 00:56:25 +03:00
Oleg Kalachev
5db1258f78 Add battery connector cable to components list 2025-01-06 00:21:59 +03:00
Oleg Kalachev
732de2a5d6 Remove redundant inline specifiers
In-class defined methods are specified as inline by default
2025-01-04 04:09:51 +03:00
Oleg Kalachev
e10475a5e0 Some minor cleanups and fixes 2024-12-28 23:57:44 +03:00
Oleg Kalachev
7ae5457bb4 Improve logging code
Make it easer to add and remove log entries
2024-12-28 22:10:43 +03:00
Oleg Kalachev
299c8a6a02 Various minor fixes 2024-12-27 21:52:21 +03:00
Oleg Kalachev
43be27c43d Fix joystick work in simulation
Logic was broken as joystickGet never got called
2024-12-27 15:34:33 +03:00
Oleg Kalachev
2440c65c46 Remove unused include 2024-12-26 16:07:01 +03:00
Oleg Kalachev
8d7a4595f5 Rename flushParameters to more clear syncParameters 2024-12-26 01:14:26 +03:00
Oleg Kalachev
acc0274175 Minor fix 2024-12-25 02:21:17 +03:00
Oleg Kalachev
edd249566e Increase motors output frequency 2024-12-25 02:13:57 +03:00
Oleg Kalachev
ca355e0162 Simplify motors duty cycle computation 2024-12-25 02:13:33 +03:00
Oleg Kalachev
2efae82177 Minor fixes 2024-12-25 01:41:45 +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
111 changed files with 13749 additions and 463 deletions

View File

@@ -5,6 +5,7 @@ on:
branches: [ '*' ]
pull_request:
branches: [ master ]
workflow_dispatch:
jobs:
build_linux:
@@ -15,6 +16,8 @@ jobs:
run: curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=/usr/local/bin sh
- name: Build firmware
run: make
- name: Build firmware without Wi-Fi
run: sed -i 's/^#define WIFI_ENABLED 1$/#define WIFI_ENABLED 0/' flix/flix.ino && make
- name: Check c_cpp_properties.json
run: tools/check_c_cpp_properties.py
@@ -43,7 +46,7 @@ jobs:
run: python3 tools/check_c_cpp_properties.py
build_simulator:
runs-on: ubuntu-latest
runs-on: ubuntu-20.04
steps:
- name: Install Arduino CLI
uses: arduino/setup-arduino-cli@v1.1.1
@@ -54,7 +57,7 @@ jobs:
run: sudo apt-get install libsdl2-dev
- name: Build simulator
run: make build_simulator
- uses: actions/upload-artifact@v3
- uses: actions/upload-artifact@v4
with:
name: gazebo-plugin-binary
path: gazebo/build/*.so
@@ -62,6 +65,7 @@ jobs:
build_simulator_macos:
runs-on: macos-latest
if: github.event_name == 'workflow_dispatch'
steps:
- name: Install Arduino CLI
run: brew install arduino-cli

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

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
}

View File

@@ -5,18 +5,18 @@
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/libraries/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/**",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/dio_qspi/include",
"~/.arduino15/packages/esp32/hardware/esp32/3.1.0/cores/esp32",
"~/.arduino15/packages/esp32/hardware/esp32/3.1.0/libraries/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.1.0/variants/d1_mini32",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.3-083aad99-v2/esp32/**",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.3-083aad99-v2/esp32/dio_qspi/include",
"~/Arduino/libraries/**",
"/usr/include/**"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32/Arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32/pins_arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.1.0/cores/esp32/Arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.1.0/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",
@@ -28,10 +28,10 @@
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/util.ino",
"${workspaceFolder}/flix/wifi.ino"
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
],
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2302/bin/xtensa-esp32-elf-g++",
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2405/bin/xtensa-esp32-elf-g++",
"cStandard": "c11",
"cppStandard": "c++17",
"defines": [
@@ -52,18 +52,18 @@
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/libraries/**",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/include/**",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/dio_qspi/include",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.1.0/cores/esp32",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.1.0/libraries/**",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.1.0/variants/d1_mini32",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.3-083aad99-v2/esp32/include/**",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.3-083aad99-v2/esp32/dio_qspi/include",
"~/Documents/Arduino/libraries/**",
"/opt/homebrew/include/**"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32/Arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32/pins_arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.1.0/cores/esp32/Arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.1.0/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/flix.ino",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
@@ -75,10 +75,10 @@
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/util.ino",
"${workspaceFolder}/flix/wifi.ino"
"${workspaceFolder}/flix/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
],
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2302/bin/xtensa-esp32-elf-g++",
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2405/bin/xtensa-esp32-elf-g++",
"cStandard": "c11",
"cppStandard": "c++17",
"defines": [
@@ -100,17 +100,17 @@
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/libraries/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/**",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/dio_qspi/include",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.1.0/cores/esp32",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.1.0/libraries/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.1.0/variants/d1_mini32",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.3-083aad99-v2/esp32/**",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.3-083aad99-v2/esp32/dio_qspi/include",
"~/Documents/Arduino/libraries/**"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32/Arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32/pins_arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.1.0/cores/esp32/Arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.1.0/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",
@@ -122,10 +122,10 @@
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/util.ino",
"${workspaceFolder}/flix/wifi.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",
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2405/bin/xtensa-esp32-elf-g++.exe",
"cStandard": "c11",
"cppStandard": "c++17",
"defines": [

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@3.0.3 --config-file arduino-cli.yaml
arduino-cli core install esp32:esp32@3.1.0 --config-file arduino-cli.yaml
arduino-cli lib update-index
arduino-cli lib install "FlixPeriph"
arduino-cli lib install "MAVLink"@2.0.10
arduino-cli lib install "MAVLink"@2.0.12
touch .dependencies
gazebo/build cmake: gazebo/CMakeLists.txt

View File

@@ -4,11 +4,11 @@
<table>
<tr>
<td align=center><strong>Version 1</strong> (3D-printed frame)</td>
<td align=center><strong>Version 1.1</strong> (3D-printed frame)</td>
<td align=center><strong>Version 0</strong></td>
</tr>
<tr>
<td><img src="docs/img/flix1.jpg" width=500 alt="Flix quadcopter"></td>
<td><img src="docs/img/flix1.1.jpg" width=500 alt="Flix quadcopter"></td>
<td><img src="docs/img/flix.jpg" width=500 alt="Flix quadcopter"></td>
</tr>
</table>
@@ -24,7 +24,7 @@
* MAVLink support.
* Control using mobile phone (with QGroundControl app).
* Completely 3D-printed frame.
* *Textbook and videos for students on writing a flight controller¹.*
* 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).
@@ -40,6 +40,10 @@ 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>
See the [user builds gallery](docs/user.md).
<img src="docs/img/user/user.jpg" width=400>
## Simulation
The simulator is implemented using Gazebo and runs the original Arduino code:
@@ -53,25 +57,28 @@ See [instructions on running the simulation](docs/build.md).
|Type|Part|Image|Quantity|
|-|-|:-:|:-:|
|Microcontroller board|ESP32 Mini|<img src="docs/img/esp32.jpg" width=100>|1|
|IMU and barometer² board|GY-91 (or other MPU-9250 board)|<img src="docs/img/gy-91.jpg" width=100>|1|
|Motor|8520 3.7V brushed motor (**shaft 0.8mm!**)|<img src="docs/img/motor.jpeg" width=100>|4|
|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).<br>Motor with exact 3.7V voltage is needed, not ranged working voltage (3.7V — 6V).|<img src="docs/img/motor.jpeg" width=100>|4|
|Propeller|Hubsan 55 mm|<img src="docs/img/prop.jpg" width=100>|4|
|MOSFET (transistor)|100N03A or [compatible](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4|
|MOSFET (transistor)|100N03A or [analog](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4|
|Pull-down resistor|10 kΩ|<img src="docs/img/resistor10k.jpg" width=100>|4|
|3.7V Li-Po battery|LW 952540 (or any compatible by the size)|<img src="docs/img/battery.jpg" width=100>|1|
|Battery connector cable|MX2.0 2P female|<img src="docs/img/mx.png" width=100>|1|
|Li-Po Battery charger|Any|<img src="docs/img/charger.jpg" width=100>|1|
|Screws for IMU board mounting|M3x5|<img src="docs/img/screw-m3.jpg" width=100>|2|
|Screws for frame assembly|M1.4x5|<img src="docs/img/screw-m1.4.jpg" height=30 align=center>|4|
|Frame bottom part|3D printed: [`flix-frame.stl`](docs/assets/flix-frame.stl)|<img src="docs/img/frame1.jpg" width=100>|1|
|Frame top part|3D printed: [`esp32-holder.stl`](docs/assets/esp32-holder.stl)|<img src="docs/img/esp32-holder.jpg" width=100>|1|
|Washer for IMU board mounting|3D printed: [`washer-m3.stl`](docs/assets/washer-m3.stl)|<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|
|Frame bottom part|3D printed⁴:<br>[`flix-frame-1.1.stl`](docs/assets/flix-frame-1.1.stl) [`flix-frame-1.1.step`](docs/assets/flix-frame-1.1.step)|<img src="docs/img/frame1.jpg" width=100>|1|
|Frame top part|3D printed:<br>[`esp32-holder.stl`](docs/assets/esp32-holder.stl) [`esp32-holder.step`](docs/assets/esp32-holder.step)|<img src="docs/img/esp32-holder.jpg" width=100>|1|
|Washer for IMU board mounting|3D printed:<br>[`washer-m3.stl`](docs/assets/washer-m3.stl) [`washer-m3.step`](docs/assets/washer-m3.step)|<img src="docs/img/washer-m3.jpg" width=100>|2|
|*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||||
*² — barometer is not used for now.*<br>
*³ — you may use any transmitter-receiver pair with SBUS interface.*
*³ — 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.*
Tools required for assembly:
@@ -93,20 +100,22 @@ Motor connection scheme:
<img src="docs/img/mosfet-connection.png" height=400 alt="MOSFET connection scheme">
Complete diagram is Work-in-Progress.
You can see a user-contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612338222067&cot=14) of the drone.
See [assembly guide](docs/assembly.md) for instructions on assembling the drone.
### Notes
* Power ESP32 Mini with Li-Po battery using VCC (+) and GND (-) pins.
* Connect the GY-91 board to the ESP32 Mini using VSPI, power it using 3.3V and GND pins:
* Connect the IMU board to the ESP32 Mini using VSPI, power it using 3.3V and GND pins:
|GY-91 pin|ESP32 pin|
|IMU pin|ESP32 pin|
|-|-|
|GND|GND|
|3.3V|3.3V|
|SCK|SVP (GPIO18)|
|MOSI|GPIO23|
|MISO|GPIO19|
|SCL *(SCK)*|SVP (GPIO18)|
|SDA *(MOSI)*|GPIO23|
|SAO *(MISO)*|GPIO19|
|NCS|GPIO5|
* Solder pull-down resistors to the MOSFETs.
@@ -114,10 +123,10 @@ Complete diagram is Work-in-Progress.
|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|
|Motor 0|Rear left|Counter-clockwise|Black & White|GPIO12 (*TDI*)|
|Motor 1|Rear right|Clockwise|Blue & Red|GPIO13 (*TCK*)|
|Motor 2|Front right|Counter-clockwise|Black & White|GPIO14 (*TMS*)|
|Motor 3|Front left|Clockwise|Blue & Red|GPIO15 (*TD0*)|
Counter-clockwise motors have black and white wires and clockwise motors have blue and red wires.
@@ -126,10 +135,20 @@ Complete diagram is Work-in-Progress.
|Receiver pin|ESP32 pin|
|-|-|
|GND|GND|
|VIN|VC (or 3.3V depending on the receiver)|
|Signal|GPIO4|
|VIN|VCC (or 3.3V depending on the receiver)|
|Signal (TX)|GPIO4|
* — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.*
* — 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

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

29
docs/assembly.md Normal file
View File

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

File diff suppressed because it is too large Load Diff

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

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;

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.1.jpg" class="border" width=500 alt="Flix quadcopter">
<p class="github">GitHub:&nbsp;<a href="https://github.com/okalachev/flix">github.com/okalachev/flix</a>.</p>
<p class="telegram">Telegram-канал:&nbsp;<a href="https://t.me/opensourcequadcopter">@opensourcequadcopter</a>.</p>

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)
* [Акселерометр]()
* [Оценка состояния]()
* [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 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер.
Частота сэмплов устанавливается методом `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,7 +9,9 @@ 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:
@@ -82,7 +84,7 @@ cd flix
#### 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.
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone. For **iOS**, use [QGroundControl build from TAJISOFT](https://apps.apple.com/ru/app/qgc-from-tajisoft/id1618653051).
2. Connect your smartphone to the same Wi-Fi network as the machine running the simulator.
3. If you're using a virtual machine, make sure that its network is set to the **bridged** mode with Wi-Fi adapter selected.
4. Run the simulation.
@@ -94,27 +96,35 @@ cd flix
1. Connect your USB remote control to the machine running the simulator.
2. Run the simulation.
3. Calibrate the RC using `cr` command in the command line interface and stop the simulation.
4. Copy the calibration results to the source code (`gazebo/joystick.h`).
5. Run the simulation again.
6. Use the USB remote control to fly the drone!
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, version 3.0.3 (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.10.
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.
2. Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).
3. Install ESP32 core, version 3.1.0 (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.
4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
* `FlixPeriph`, the latest version.
* `MAVLink`, version 2.0.12.
5. Clone the project using git or [download the source code as a ZIP archive](https://codeload.github.com/okalachev/flix/zip/refs/heads/master).
6. Open the downloaded Arduino sketch `flix/flix.ino` in Arduino IDE.
7. Connect your ESP32 board to the computer and choose correct board type in Arduino IDE (*WEMOS D1 MINI ESP32* for ESP32 Mini) and the port.
8. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
### Command line (Windows, Linux, macOS)
1. [Install Arduino CLI](https://arduino.github.io/arduino-cli/installation/).
On Linux, use:
```bash
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
```
2. Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).
3. Compile the firmware using `make`. Arduino dependencies will be installed automatically:
@@ -136,13 +146,15 @@ cd flix
See other available Make commands in the [Makefile](../Makefile).
> [!TIP]
> You can test the firmware on a bare ESP32 board without connecting IMU and other peripherals. The Wi-Fi network `flix` should appear and all the basic functionality including CLI and QGroundControl connection should work.
### Setup and flight
Before flight you need to calibrate the accelerometer:
1. Open Serial Monitor in Arduino IDE (use use `make monitor` command in the command line).
2. Type `ca` command there.
3. Copy calibration results to the source code (`flix/imu.ino`).
1. Open Serial Monitor in Arduino IDE (or use `make monitor` command in the command line).
2. Type `ca` command there and follow the instructions.
#### Control with smartphone
@@ -157,11 +169,36 @@ Before flight you need to calibrate the accelerometer:
Before flight using remote control, you need to calibrate it:
1. Open Serial Monitor in Arduino IDE (use use `make monitor` command in the command line).
2. Type `cr` command there.
3. Copy calibration results to the source code (`flix/rc.ino`).
1. Open Serial Monitor in Arduino IDE (or use `make monitor` command in the command line).
2. Type `cr` command there and follow the instructions.
3. Use the remote control to fly the drone!
Then you can use your remote control to fly the drone!
#### Control with USB remote control
If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it.
1. Install [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html) app on your computer.
2. Connect your USB remote control to the computer.
3. Power up the drone.
4. Connect your computer to the appeared `flix` Wi-Fi network.
5. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
6. Go the the QGroundControl menu ⇒ *Vehicle Setup**Joystick*. Calibrate you USB remote control there.
7. Use the USB remote control to fly the drone!
#### Adjusting parameters
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl app. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup**Parameters*.
<img src="img/parameters.png" width="400">
#### CLI access
In addition to accessing the drone's command line interface (CLI) using the serial port, you can also access it with QGroundControl using Wi-Fi connection. To do that, go to the QGroundControl menu ⇒ *Vehicle Setup**Analyze Tools**MAVLink Console*.
<img src="img/cli.png" width="400">
> [!NOTE]
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.
### Firmware code structure

View File

@@ -6,7 +6,7 @@
The main loop is running at 1000 Hz. All the dataflow is happening through global variables (for simplicity):
* `t` *(float)* current step time, *s*.
* `t` *(double)* current step time, *s*.
* `dt` *(float)* — time delta between the current and previous steps, *s*.
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*.

BIN
docs/img/assembly/1.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 157 KiB

BIN
docs/img/assembly/2.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 79 KiB

BIN
docs/img/assembly/3.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 115 KiB

BIN
docs/img/assembly/4.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 169 KiB

BIN
docs/img/assembly/5.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 147 KiB

BIN
docs/img/assembly/6.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 99 KiB

BIN
docs/img/assembly/7.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 152 KiB

BIN
docs/img/cli.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

BIN
docs/img/flix1.1.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 123 KiB

BIN
docs/img/flixperiph.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 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

BIN
docs/img/mpu9250.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

BIN
docs/img/mx.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 16 KiB

BIN
docs/img/parameters.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 68 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 40 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 45 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 51 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 52 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 44 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 24 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 45 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 54 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 30 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 43 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 70 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 18 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 33 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 40 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 83 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 58 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 74 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 56 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 57 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 49 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 78 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 20 KiB

BIN
docs/img/user/rudpa/1.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 73 KiB

BIN
docs/img/user/rudpa/2.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 58 KiB

BIN
docs/img/user/rudpa/3.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 66 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 9.8 KiB

BIN
docs/img/user/user.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 54 KiB

BIN
docs/img/user/yi_lun/1.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

BIN
docs/img/user/yi_lun/2.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 58 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 5.9 KiB

After

Width:  |  Height:  |  Size: 6.7 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');
}
});

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>

36
docs/troubleshooting.md Normal file
View File

@@ -0,0 +1,36 @@
# 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. You can also access the CLI using QGroundControl (*Vehicle Setup* ⇒ *Analyze Tools**MAVLink Console*).
* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
* **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 is working**. Perform `imu` command and check its output:
* The `status` field should be `OK`.
* The `rate` field should be about 1000 (Hz).
* The `accel` and `gyro` fields should change as you move the drone.
* **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 type**. Motors with exact 3.7V voltage are needed, not ranged working voltage (3.7V — 6V).
* **Check the motors**. Perform the following commands using Serial Monitor:
* `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.

135
docs/user.md Normal file
View File

@@ -0,0 +1,135 @@
# Hall of fame
This page contains user-built drones based on the Flix project. Publish your projects into the official Telegram-chat: [@opensourcequadcopterchat](https://t.me/opensourcequadcopterchat) or send materials as a pull request.
---
Author: [@jeka_chex](https://t.me/jeka_chex).<br>
Features: custom frame, FPV camera, 3-blade 31 mm propellers.<br>
Motor drivers: AON7410 MOSFET + capacitors.<br>
Custom frame files: https://drive.google.com/drive/folders/1QCIc-_YYFxJN4cMhVLjL5SflqegvCowm?usp=share_link.<br>
**Flight video:**
<a href="https://drive.google.com/file/d/1VnWI5YVPojfqsfpyLX4v2V9zHi9adwcd/view?usp=sharing"><img height=300 src="img/user/jeka_chex/video.jpg"></a>
**FPV flight video:**
<a href="https://drive.google.com/file/d/1RSU6VWs9omsge4hGloH5NQqnxvLyhMKB/view?usp=sharing"><img height=300 src="img/user/jeka_chex/video-fpv.jpg"></a>
<table>
<tr>
<td><img src="img/user/jeka_chex/1.jpg" height=150></td>
<td><img src="img/user/jeka_chex/2.jpg" height=150></td>
<td><img src="img/user/jeka_chex/3.jpg" height=150></td>
<td><img src="img/user/jeka_chex/4.jpg" height=150></td>
<td><img src="img/user/jeka_chex/5.jpg" height=150></td>
</tr>
</table>
---
Author: [@fisheyeu](https://t.me/fisheyeu).<br>
[Video](https://drive.google.com/file/d/1IT4eMmWPZpmaZR_qsIRmNJ52hYkFB_0q/view?usp=share_link).
<table>
<tr>
<td><img src="img/user/fisheyeu/1.jpg" height=300></td>
<td><img src="img/user/fisheyeu/2.jpg" height=300></td>
</tr>
</table>
---
Author: [@p_kabakov](https://t.me/p_kabakov).<br>
Custom propellers guard 3D-model: https://drive.google.com/file/d/1TKnzwvrZYzYuRTLLERNmnKH71H9n4Xj_/view?usp=share_link.<br>
Features: ESP32-C3 microcontroller is used.<br>
[Video](https://drive.google.com/file/d/1B0NMcsk0fgwUgNr9XuLOdR2yYCuaj008/view?usp=share_link).
<table>
<tr>
<td><img src="img/user/p_kabakov/1.jpg" width=150></td>
<td><img src="img/user/p_kabakov/2.jpg" width=150></td>
<td><img src="img/user/p_kabakov/3.jpg" width=150></td>
</tr>
</table>
**Custom Wi-Fi RC control:**
<a href="https://github.com/pavelkabakov/flix/blob/master/rc_control_v1/IMG_20250221_195756.jpg"><img height=300 src="img/user/p_kabakov/wifirc.jpg"></a>
See source and description (in Russian): https://github.com/pavelkabakov/flix/tree/master/rc_control_v1.
---
Author: [@yi_lun](https://t.me/yi_lun).<br>
[Video](https://drive.google.com/file/d/1TkSuvHQ_0qQPFUpY5XjJzmhnpX_07cTg/view?usp=share_link).
<table>
<tr>
<td><img src="img/user/yi_lun/1.jpg" width=300></td>
<td><img src="img/user/yi_lun/2.jpg" width=300></td>
</tr>
</table>
---
Author: [@peter_ukhov](https://t.me/peter_ukhov).<br>
Features: customized ESP32 holder, GY-ICM20948V2 IMU board, boost-converter for powering the ESP32.<br>
Files for 3D-printing: https://drive.google.com/file/d/1Sma-FEzFBj2HA5ixJtUyH0uWixvr6vdK/view?usp=share_link.<br>
Schematics: https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612179508274&cot=14.<br>
<a href="https://www.youtube.com/watch?v=wi4w_hOmKcQ"><img width=500 src="img/user/peter_ukhov-2/video.jpg"></a>
<table>
<tr>
<td><img src="img/user/peter_ukhov-2/1.jpg" width=300></td>
<td><img src="img/user/peter_ukhov-2/2.jpg" width=300></td>
</tr>
</table>
---
Author: [@Alexey_Karakash](https://t.me/Alexey_Karakash).<br>
Files for 3D printing of the custom frame: https://drive.google.com/file/d/1tkNmujrHrKpTMVtsRH3mor2zdAM0JHum/view?usp=share_link.<br>
<a href="https://t.me/opensourcequadcopter/61"><img width=500 src="img/user/alexey_karakash/video.jpg"></a>
<table>
<tr>
<td><img src="img/user/alexey_karakash/1.jpg" height=150></td>
<td><img src="img/user/alexey_karakash/2.jpg" height=150></td>
<td><img src="img/user/alexey_karakash/3.jpg" height=150></td>
<td><img src="img/user/alexey_karakash/4.jpg" height=150></td>
<td><img src="img/user/alexey_karakash/5.jpg" height=150></td>
</tr>
</table>
---
Author: [@rudpa](https://t.me/rudpa).<br>
<a href="https://t.me/opensourcequadcopter/46"><img width=500 src="img/user/rudpa/video.jpg"></a>
<table>
<tr>
<td><img src="img/user/rudpa/1.jpg" height=150></td>
<td><img src="img/user/rudpa/2.jpg" height=150></td>
<td><img src="img/user/rudpa/3.jpg" height=150></td>
</tr>
</table>
---
Author: [@peter_ukhov](https://t.me/peter_ukhov).<br>
Schematics: https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612338222067&cot=14.<br>
<a href="https://t.me/opensourcequadcopter/24"><img width=500 src="img/user/peter_ukhov/video.jpg"></a>
<table>
<tr>
<td><img src="img/user/peter_ukhov/1.jpg" height=150></td>
<td><img src="img/user/peter_ukhov/2.jpg" height=150></td>
<td><img src="img/user/peter_ukhov/3.jpg" height=150></td>
</tr>
</table>

View File

@@ -19,7 +19,7 @@ Flix version 0 (obsolete):
|~~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, ...|||
|Wires, connectors, tape, ...||||
*\* — not needed as ESP32 supports [software pin inversion](https://github.com/bolderflight/sbus#inverted-serial).*
@@ -27,4 +27,4 @@ Flix version 0 (obsolete):
<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.
You can also check a user contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764574482511443&cot=14) 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

@@ -5,9 +5,12 @@
#include "pid.h"
#include "vector.h"
#include "util.h"
extern PID rollRatePID, pitchRatePID, yawRatePID, rollPID, pitchPID;
extern LowPassFilter<Vector> ratesFilter;
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern float loopRate, dt;
extern double t;
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
const char* motd =
"\nWelcome to\n"
@@ -19,71 +22,103 @@ 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"
"time - show time info\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},
void print(const char* format, ...) {
char buf[1000];
va_list args;
va_start(args, format);
vsnprintf(buf, sizeof(buf), format, args);
va_end(args);
Serial.print(buf);
#if WIFI_ENABLED
mavlinkPrint(buf);
#endif
}
{"ap", &rollPID.p, &pitchPID.p},
{"ai", &rollPID.i, &pitchPID.i},
{"ad", &rollPID.d, &pitchPID.d},
void pause(float duration) {
#if ARDUINO
double start = t;
while (t - start < duration) {
step();
handleInput();
#if WIFI_ENABLED
processMavlink();
#endif
}
#else
// Code above won't work in the simulation
delay(duration * 1000);
#endif
}
{"yp", &yawRatePID.p, nullptr},
{"yi", &yawRatePID.i, nullptr},
{"yd", &yawRatePID.d, nullptr},
void doCommand(String str, bool echo = false) {
// parse command
String command, arg0, arg1;
splitString(str, command, arg0, arg1);
{"lpr", &ratesFilter.alpha, nullptr},
{"lpd", &rollRatePID.lpf.alpha, &pitchRatePID.lpf.alpha},
// echo command
if (echo && !command.isEmpty()) {
print("> %s\n", str.c_str());
}
{"ss", &loopFreq, nullptr},
{"dt", &dt, nullptr},
{"t", &t, nullptr},
};
void doCommand(String& command, String& value) {
// execute command
if (command == "help" || command == "motd") {
Serial.println(motd);
} else if (command == "show") {
showTable();
print("%s\n", motd);
} else if (command == "p" && arg0 == "") {
printParameters();
} else if (command == "p" && arg0 != "" && arg1 == "") {
print("%s = %g\n", arg0.c_str(), getParameter(arg0.c_str()));
} else if (command == "p") {
bool success = setParameter(arg0.c_str(), arg1.toFloat());
if (success) {
print("%s = %g\n", arg0.c_str(), arg1.toFloat());
} else {
print("Parameter not found: %s\n", arg0.c_str());
}
} else if (command == "preset") {
resetParameters();
} else if (command == "time") {
print("Time: %f\n", t);
print("Loop rate: %f\n", loopRate);
print("dt: %f\n", dt);
} 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);
print("roll: %f pitch: %f yaw: %f\n", degrees(a.x), degrees(a.y), degrees(a.z));
} else if (command == "psq") {
Serial.printf("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
print("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
} else if (command == "imu") {
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);
printIMUInfo();
print("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
print("acc: %f %f %f\n", acc.x, acc.y, acc.z);
printIMUCal();
Serial.printf("frequency: %f\n", loopFreq);
print("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],
channels[RC_CHANNEL_ROLL], channels[RC_CHANNEL_ARMED], channels[RC_CHANNEL_MODE]);
Serial.printf("Control: throttle %f yaw %f pitch %f roll %f armed %f mode %f\n",
controls[RC_CHANNEL_THROTTLE], controls[RC_CHANNEL_YAW], controls[RC_CHANNEL_PITCH],
controls[RC_CHANNEL_ROLL], controls[RC_CHANNEL_ARMED], controls[RC_CHANNEL_MODE]);
Serial.printf("Mode: %s\n", getModeName());
print("Raw: throttle %d yaw %d pitch %d roll %d armed %d mode %d\n",
channels[throttleChannel], channels[yawChannel], channels[pitchChannel],
channels[rollChannel], channels[armedChannel], channels[modeChannel]);
print("Control: throttle %g yaw %g pitch %g roll %g armed %g mode %g\n",
controls[throttleChannel], controls[yawChannel], controls[pitchChannel],
controls[rollChannel], controls[armedChannel], controls[modeChannel]);
print("Mode: %s\n", getModeName());
} else if (command == "mot") {
Serial.printf("MOTOR front-right %f front-left %f rear-right %f rear-left %f\n",
print("Motors: front-right %g front-left %g rear-right %g rear-left %g\n",
motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]);
} else if (command == "log") {
dumpLog();
@@ -94,77 +129,40 @@ void doCommand(String& command, String& value) {
} else if (command == "ca") {
calibrateAccel();
} else if (command == "mfr") {
cliTestMotor(MOTOR_FRONT_RIGHT);
testMotor(MOTOR_FRONT_RIGHT);
} else if (command == "mfl") {
cliTestMotor(MOTOR_FRONT_LEFT);
testMotor(MOTOR_FRONT_LEFT);
} else if (command == "mrr") {
cliTestMotor(MOTOR_REAR_RIGHT);
testMotor(MOTOR_REAR_RIGHT);
} else if (command == "mrl") {
cliTestMotor(MOTOR_REAR_LEFT);
} else if (command == "fullmot") {
fullMotorTest(value.toInt());
testMotor(MOTOR_REAR_LEFT);
} 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);
print("Invalid command: %s\n", command.c_str());
}
}
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;
sendMotors();
delay(5000);
motors[n] = 0;
sendMotors();
Serial.println("Done");
}
void parseInput() {
void handleInput() {
static bool showMotd = true;
static String command;
static String value;
static bool parsingCommand = true;
static String input;
if (showMotd) {
Serial.println(motd);
print("%s\n", motd);
showMotd = false;
}
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;
doCommand(input);
input.clear();
} else {
(parsingCommand ? command : value) += c;
input += c;
}
}
}

View File

@@ -7,6 +7,7 @@
#include "quaternion.h"
#include "pid.h"
#include "lpf.h"
#include "util.h"
#define PITCHRATE_P 0.05
#define PITCHRATE_I 0.2
@@ -29,8 +30,8 @@
#define YAW_P 3
#define PITCHRATE_MAX radians(360)
#define ROLLRATE_MAX radians(360)
#define YAWRATE_MAX radians(360)
#define MAX_TILT radians(30)
#define YAWRATE_MAX radians(300)
#define TILT_MAX radians(30)
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
@@ -44,14 +45,20 @@ PID yawRatePID(YAWRATE_P, YAWRATE_I, YAWRATE_D);
PID rollPID(ROLL_P, ROLL_I, ROLL_D);
PID pitchPID(PITCH_P, PITCH_I, PITCH_D);
PID yawPID(YAW_P, 0, 0);
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
float tiltMax = TILT_MAX;
Quaternion attitudeTarget;
Vector ratesTarget;
Vector torqueTarget;
float thrustTarget;
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
void control() {
interpretRC();
failsafe();
if (mode == STAB) {
controlAttitude();
controlRate();
@@ -65,38 +72,39 @@ void control() {
}
void interpretRC() {
armed = controls[RC_CHANNEL_THROTTLE] >= 0.05 && controls[RC_CHANNEL_ARMED] >= 0.5;
armed = controls[throttleChannel] >= 0.05 &&
(controls[armedChannel] >= 0.5 || isnan(controls[armedChannel])); // assume armed if armed channel is not defined
// NOTE: put ACRO or MANUAL modes there if you want to use them
if (controls[RC_CHANNEL_MODE] < 0.25) {
if (controls[modeChannel] < 0.25) {
mode = STAB;
} else if (controls[RC_CHANNEL_MODE] < 0.75) {
} else if (controls[modeChannel] < 0.75) {
mode = STAB;
} else {
mode = STAB;
}
thrustTarget = controls[RC_CHANNEL_THROTTLE];
thrustTarget = controls[throttleChannel];
if (mode == ACRO) {
yawMode = YAW_RATE;
ratesTarget.x = controls[RC_CHANNEL_ROLL] * ROLLRATE_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
ratesTarget.x = controls[rollChannel] * maxRate.x;
ratesTarget.y = controls[pitchChannel] * maxRate.y;
ratesTarget.z = -controls[yawChannel] * maxRate.z; // positive yaw stick means clockwise rotation in FLU
} else if (mode == STAB) {
yawMode = controls[RC_CHANNEL_YAW] == 0 ? YAW : YAW_RATE;
yawMode = controls[yawChannel] == 0 ? YAW : YAW_RATE;
attitudeTarget = Quaternion::fromEulerZYX(Vector(
controls[RC_CHANNEL_ROLL] * MAX_TILT,
controls[RC_CHANNEL_PITCH] * MAX_TILT,
controls[rollChannel] * tiltMax,
controls[pitchChannel] * tiltMax,
attitudeTarget.getYaw()));
ratesTarget.z = -controls[RC_CHANNEL_YAW] * YAWRATE_MAX; // positive yaw stick means clockwise rotation in FLU
ratesTarget.z = -controls[yawChannel] * maxRate.z; // 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[rollChannel], controls[pitchChannel], -controls[yawChannel]) * 0.01;
}
if (yawMode == YAW_RATE || !motorsActive()) {
@@ -114,8 +122,8 @@ void controlAttitude() {
}
const Vector up(0, 0, 1);
Vector upActual = attitude.rotate(up);
Vector upTarget = attitudeTarget.rotate(up);
Vector upActual = attitude.rotateVector(up);
Vector upTarget = attitudeTarget.rotateVector(up);
Vector error = Vector::angularRatesBetweenVectors(upTarget, upActual);
@@ -161,10 +169,6 @@ void controlTorque() {
motors[3] = constrain(motors[3], 0, 1);
}
bool motorsActive() {
return motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0;
}
const char* getModeName() {
switch (mode) {
case MANUAL: return "MANUAL";

View File

@@ -6,9 +6,9 @@
#include "quaternion.h"
#include "vector.h"
#include "lpf.h"
#include "util.h"
#define ONE_G 9.807f
#define WEIGHT_ACC 0.5f
#define WEIGHT_ACC 0.003
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
@@ -16,7 +16,6 @@ LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
void estimate() {
applyGyro();
applyAcc();
signalizeHorizontality();
}
void applyGyro() {
@@ -24,8 +23,7 @@ void applyGyro() {
rates = ratesFilter.update(gyro);
// apply rates to attitude
attitude *= Quaternion::fromAngularRates(rates * dt);
attitude.normalize();
attitude = attitude.rotate(Quaternion::fromAngularRates(rates * dt));
}
void applyAcc() {
@@ -36,15 +34,9 @@ void applyAcc() {
if (!landed) return;
// calculate accelerometer correction
Vector up = attitude.rotate(Vector(0, 0, 1));
Vector correction = Vector::angularRatesBetweenVectors(acc, up) * dt * WEIGHT_ACC;
Vector up = attitude.rotateVector(Vector(0, 0, 1));
Vector correction = Vector::angularRatesBetweenVectors(acc, up) * 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));
attitude = attitude.rotate(Quaternion::fromAngularRates(correction));
}

41
flix/failsafe.ino Normal file
View File

@@ -0,0 +1,41 @@
// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Fail-safe functions
#define RC_LOSS_TIMEOUT 0.2
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
extern double controlsTime;
extern int rollChannel, pitchChannel, throttleChannel, yawChannel;
void failsafe() {
armingFailsafe();
rcLossFailsafe();
}
// Prevent arming without zero throttle input
void armingFailsafe() {
static double zeroThrottleTime;
static double armingTime;
if (!armed) armingTime = t; // stores the last time when the drone was disarmed, therefore contains arming time
if (controlsTime > 0 && controls[throttleChannel] < 0.05) zeroThrottleTime = controlsTime;
if (armingTime - zeroThrottleTime > 0.1) armed = false; // prevent arming if there was no zero throttle for 0.1 sec
}
// RC loss failsafe
void rcLossFailsafe() {
if (t - controlsTime > RC_LOSS_TIMEOUT) {
descend();
}
}
// Smooth descend on RC lost
void descend() {
mode = STAB;
controls[rollChannel] = 0;
controls[pitchChannel] = 0;
controls[yawChannel] = 0;
controls[throttleChannel] -= dt / DESCEND_TIME;
if (controls[throttleChannel] < 0) controls[throttleChannel] = 0;
}

View File

@@ -5,29 +5,15 @@
#include "vector.h"
#include "quaternion.h"
#include "util.h"
#define SERIAL_BAUDRATE 115200
#define WIFI_ENABLED 1
#define RC_CHANNELS 16
#define RC_CHANNEL_ROLL 0
#define RC_CHANNEL_PITCH 1
#define RC_CHANNEL_THROTTLE 2
#define RC_CHANNEL_YAW 3
#define RC_CHANNEL_ARMED 4
#define RC_CHANNEL_MODE 5
#define MOTOR_REAR_LEFT 0
#define MOTOR_REAR_RIGHT 1
#define MOTOR_FRONT_RIGHT 2
#define MOTOR_FRONT_LEFT 3
float t = NAN; // current step time, s
double t = NAN; // current step time, s
float dt; // time delta from previous step, s
float loopFreq; // loop frequency, Hz
int16_t channels[RC_CHANNELS]; // raw rc channels
float controls[RC_CHANNELS]; // normalized controls in range [-1..1] ([0..1] for throttle)
int16_t channels[16]; // raw rc channels
float controls[16]; // normalized controls in range [-1..1] ([0..1] for throttle)
Vector gyro; // gyroscope data
Vector acc; // accelerometer data, m/s/s
Vector rates; // filtered angular rates, rad/s
@@ -36,19 +22,19 @@ float motors[4]; // normalized motors thrust in range [-1..1]
void setup() {
Serial.begin(SERIAL_BAUDRATE);
Serial.println("Initializing flix");
print("Initializing flix");
disableBrownOut();
setupParameters();
setupLED();
setupMotors();
setLED(true);
#if WIFI_ENABLED == 1
#if WIFI_ENABLED
setupWiFi();
#endif
setupIMU();
setupRC();
setLED(false);
Serial.println("Initializing complete");
print("Initializing complete");
}
void loop() {
@@ -58,9 +44,10 @@ void loop() {
estimate();
control();
sendMotors();
parseInput();
#if WIFI_ENABLED == 1
handleInput();
#if WIFI_ENABLED
processMavlink();
#endif
logData();
syncParameters();
}

View File

@@ -2,39 +2,30 @@
// Repository: https://github.com/okalachev/flix
// Work with the IMU sensor
// IMU is oriented FLU (front-left-up) style.
// In case of FRD (front-right-down) orientation of the IMU, use this code:
// https://gist.github.com/okalachev/713db47e31bce643dbbc9539d166ce98.
#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);
#include "util.h"
MPU9250 IMU(SPI);
Vector accBias;
Vector gyroBias;
Vector accScale(1, 1, 1);
void setupIMU() {
Serial.println("Setup IMU");
bool status = IMU.begin();
if (!status) {
while (true) {
Serial.println("IMU begin error");
delay(1000);
}
}
print("Setup IMU\n");
IMU.begin();
configureIMU();
delay(500); // wait a bit before calibrating
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() {
@@ -44,11 +35,21 @@ void readIMU() {
// 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 calibrateGyro() {
const int samples = 1000;
Serial.println("Calibrating gyro, stand still");
print("Calibrating gyro, stand still\n");
IMU.setGyroRange(IMU.GYRO_RANGE_250DPS); // the most sensitive mode
gyroBias = Vector(0, 0, 0);
@@ -64,23 +65,26 @@ void calibrateGyro() {
}
void calibrateAccel() {
Serial.println("Calibrating accelerometer");
print("Calibrating accelerometer\n");
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');
print("Place level [8 sec]\n");
pause(8);
calibrateAccelOnce();
Serial.print("Place nose up [enter] "); Serial.readStringUntil('\n');
print("Place nose up [8 sec]\n");
pause(8);
calibrateAccelOnce();
Serial.print("Place nose down [enter] "); Serial.readStringUntil('\n');
print("Place nose down [8 sec]\n");
pause(8);
calibrateAccelOnce();
Serial.print("Place on right side [enter] "); Serial.readStringUntil('\n');
print("Place on right side [8 sec]\n");
pause(8);
calibrateAccelOnce();
Serial.print("Place on left side [enter] "); Serial.readStringUntil('\n');
print("Place on left side [8 sec]\n");
pause(8);
calibrateAccelOnce();
Serial.print("Place upside down [enter] "); Serial.readStringUntil('\n');
print("Place upside down [8 sec]\n");
pause(8);
calibrateAccelOnce();
printIMUCal();
@@ -88,7 +92,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);
@@ -109,16 +113,22 @@ void calibrateAccelOnce() {
if (acc.x < accMin.x) accMin.x = acc.x;
if (acc.y < accMin.y) accMin.y = acc.y;
if (acc.z < accMin.z) accMin.z = acc.z;
Serial.printf("acc %f %f %f\n", acc.x, acc.y, acc.z);
Serial.printf("max %f %f %f\n", accMax.x, accMax.y, accMax.z);
Serial.printf("min %f %f %f\n", accMin.x, accMin.y, accMin.z);
print("acc %f %f %f\n", acc.x, acc.y, acc.z);
print("max %f %f %f\n", accMax.x, accMax.y, accMax.z);
print("min %f %f %f\n", accMin.x, accMin.y, accMin.z);
// Compute scale and bias
accScale = (accMax - accMin) / 2 / ONE_G;
accBias = (accMax + accMin) / 2;
}
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);
print("gyro bias: %f %f %f\n", gyroBias.x, gyroBias.y, gyroBias.z);
print("accel bias: %f %f %f\n", accBias.x, accBias.y, accBias.z);
print("accel scale: %f %f %f\n", accScale.x, accScale.y, accScale.z);
}
void printIMUInfo() {
IMU.status() ? print("status: ERROR %d\n", IMU.status()) : print("status: OK\n");
print("model: %s\n", IMU.getModel());
print("who am I: 0x%02X\n", IMU.whoAmI());
}

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

@@ -3,36 +3,60 @@
// In-RAM logging
#include "vector.h"
#define LOG_RATE 100
#define LOG_DURATION 10
#define LOG_PERIOD 1.0 / LOG_RATE
#define LOG_SIZE LOG_DURATION * LOG_RATE
#define LOG_COLUMNS 14
float logBuffer[LOG_SIZE][LOG_COLUMNS]; // * 4 (float)
int logPointer = 0;
float tFloat;
Vector attitudeEuler;
Vector attitudeTargetEuler;
struct LogEntry {
const char *name;
float *value;
};
LogEntry logEntries[] = {
{"t", &tFloat},
{"rates.x", &rates.x},
{"rates.y", &rates.y},
{"rates.z", &rates.z},
{"ratesTarget.x", &ratesTarget.x},
{"ratesTarget.y", &ratesTarget.y},
{"ratesTarget.z", &ratesTarget.z},
{"attitude.x", &attitudeEuler.x},
{"attitude.y", &attitudeEuler.y},
{"attitude.z", &attitudeEuler.z},
{"attitudeTarget.x", &attitudeTargetEuler.x},
{"attitudeTarget.y", &attitudeTargetEuler.y},
{"attitudeTarget.z", &attitudeTargetEuler.z},
{"thrustTarget", &thrustTarget}
};
const int logColumns = sizeof(logEntries) / sizeof(logEntries[0]);
float logBuffer[LOG_SIZE][logColumns];
void prepareLogData() {
tFloat = t;
attitudeEuler = attitude.toEulerZYX();
attitudeTargetEuler = attitudeTarget.toEulerZYX();
}
void logData() {
if (!armed) return;
static float logTime = 0;
static int logPointer = 0;
static double logTime = 0;
if (t - logTime < LOG_PERIOD) return;
logTime = t;
logBuffer[logPointer][0] = t;
logBuffer[logPointer][1] = rates.x;
logBuffer[logPointer][2] = rates.y;
logBuffer[logPointer][3] = rates.z;
logBuffer[logPointer][4] = ratesTarget.x;
logBuffer[logPointer][5] = ratesTarget.y;
logBuffer[logPointer][6] = ratesTarget.z;
logBuffer[logPointer][7] = attitude.toEulerZYX().x;
logBuffer[logPointer][8] = attitude.toEulerZYX().y;
logBuffer[logPointer][9] = attitude.toEulerZYX().z;
logBuffer[logPointer][10] = attitudeTarget.toEulerZYX().x;
logBuffer[logPointer][11] = attitudeTarget.toEulerZYX().y;
logBuffer[logPointer][12] = attitudeTarget.toEulerZYX().z;
logBuffer[logPointer][13] = thrustTarget;
prepareLogData();
for (int i = 0; i < logColumns; i++) {
logBuffer[logPointer][i] = *logEntries[i].value;
}
logPointer++;
if (logPointer >= LOG_SIZE) {
@@ -41,13 +65,15 @@ void logData() {
}
void dumpLog() {
Serial.printf("t,rates.x,rates.y,rates.z,ratesTarget.x,ratesTarget.y,ratesTarget.z,"
"attitude.x,attitude.y,attitude.z,attitudeTarget.x,attitudeTarget.y,attitudeTarget.z,thrustTarget\n");
// Print header
for (int i = 0; i < logColumns; i++) {
print("%s%s", logEntries[i].name, i < logColumns - 1 ? "," : "\n");
}
// Print data
for (int i = 0; i < LOG_SIZE; i++) {
if (logBuffer[i][0] == 0) continue; // skip empty records
for (int j = 0; j < LOG_COLUMNS - 1; j++) {
Serial.printf("%f,", logBuffer[i][j]);
for (int j = 0; j < logColumns; j++) {
print("%g%s", logBuffer[i][j], j < logColumns - 1 ? "," : "\n");
}
Serial.printf("%f\n", logBuffer[i][LOG_COLUMNS - 1]);
}
}

View File

@@ -3,7 +3,7 @@
// MAVLink communication
#if WIFI_ENABLED == 1
#if WIFI_ENABLED
#include <MAVLink.h>
@@ -13,14 +13,19 @@
#define MAVLINK_CONTROL_SCALE 0.7f
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
float mavlinkControlScale = 0.7;
extern double controlsTime;
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
void processMavlink() {
sendMavlink();
receiveMavlink();
}
void sendMavlink() {
static float lastSlow = 0;
static float lastFast = 0;
static double lastSlow = 0;
static double lastFast = 0;
mavlink_message_t msg;
uint32_t time = t * 1000;
@@ -38,12 +43,12 @@ void sendMavlink() {
lastFast = t;
const float zeroQuat[] = {0, 0, 0, 0};
Quaternion attitudeFRD = FLU2FRD(attitude); // MAVLink uses FRD coordinate system
Quaternion attitudeFRD = fluToFrd(attitude); // MAVLink uses FRD coordinate system
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
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,
mavlink_msg_rc_channels_scaled_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, controlsTime * 1000, 0,
controls[0] * 10000, controls[1] * 10000, controls[2] * 10000,
controls[3] * 10000, controls[4] * 10000, controls[5] * 10000,
INT16_MAX, INT16_MAX, UINT8_MAX);
@@ -83,23 +88,125 @@ 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);
controls[RC_CHANNEL_THROTTLE] = manualControl.z / 1000.0f;
controls[RC_CHANNEL_PITCH] = manualControl.x / 1000.0f * MAVLINK_CONTROL_SCALE;
controls[RC_CHANNEL_ROLL] = manualControl.y / 1000.0f * MAVLINK_CONTROL_SCALE;
controls[RC_CHANNEL_YAW] = manualControl.r / 1000.0f * MAVLINK_CONTROL_SCALE;
controls[RC_CHANNEL_MODE] = 1; // STAB mode
controls[RC_CHANNEL_ARMED] = 1; // armed
const mavlink_message_t &msg = *(mavlink_message_t *)_msg;
if (abs(controls[RC_CHANNEL_YAW]) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controls[RC_CHANNEL_YAW] = 0;
if (msg.msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
mavlink_manual_control_t m;
mavlink_msg_manual_control_decode(&msg, &m);
if (m.target && m.target != SYSTEM_ID) return; // 0 is broadcast
controls[throttleChannel] = m.z / 1000.0f;
controls[pitchChannel] = m.x / 1000.0f * mavlinkControlScale;
controls[rollChannel] = m.y / 1000.0f * mavlinkControlScale;
controls[yawChannel] = m.r / 1000.0f * mavlinkControlScale;
controls[modeChannel] = 1; // STAB mode
controls[armedChannel] = 1; // armed
controlsTime = t;
if (abs(controls[yawChannel]) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controls[yawChannel] = 0;
}
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
mavlink_param_request_list_t m;
mavlink_msg_param_request_list_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
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 m;
mavlink_msg_param_request_read_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
char name[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
float value = strlen(name) == 0 ? getParameter(m.param_index) : getParameter(name);
if (m.param_index != -1) {
memcpy(name, getParameterName(m.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(), m.param_index);
sendMessage(&msg);
}
if (msg.msgid == MAVLINK_MSG_ID_PARAM_SET) {
mavlink_param_set_t m;
mavlink_msg_param_set_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
char name[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN + 1];
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
setParameter(name, m.param_value);
// send ack
mavlink_message_t msg;
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
m.param_id, m.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_mission_request_list_t m;
mavlink_msg_mission_request_list_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
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);
}
if (msg.msgid == MAVLINK_MSG_ID_SERIAL_CONTROL) {
mavlink_serial_control_t m;
mavlink_msg_serial_control_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
strlcpy(data, (const char *)m.data, m.count); // data might be not null-terminated
doCommand(data, true);
}
// Handle commands
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
mavlink_command_long_t m;
mavlink_msg_command_long_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
mavlink_message_t ack;
mavlink_message_t response;
if (m.command == MAV_CMD_REQUEST_MESSAGE && m.param1 == MAVLINK_MSG_ID_AUTOPILOT_VERSION) {
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.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, m.command, MAV_RESULT_UNSUPPORTED, UINT8_MAX, 0, msg.sysid, msg.compid);
sendMessage(&ack);
}
}
}
// Send shell output to GCS
void mavlinkPrint(const char* str) {
// Send data in chunks
for (int i = 0; i < strlen(str); i += MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN) {
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
strlcpy(data, str + i, sizeof(data));
mavlink_message_t msg;
mavlink_msg_serial_control_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
SERIAL_CONTROL_DEV_SHELL, 0, 0, 0, strlen(data), (uint8_t *)data, 0, 0);
sendMessage(&msg);
}
}
// Convert Forward-Left-Up to Forward-Right-Down quaternion
inline Quaternion FLU2FRD(const Quaternion &q) {
inline Quaternion fluToFrd(const Quaternion &q) {
return Quaternion(q.w, q.x, -q.y, -q.z);
}

View File

@@ -2,19 +2,29 @@
// Repository: https://github.com/okalachev/flix
// 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
// In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400)
#include "util.h"
#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_FREQUENCY 1000
#define PWM_RESOLUTION 12
#define PWM_STOP 0
#define PWM_MIN 0
#define PWM_MAX 1000000 / PWM_FREQUENCY
// Motors array indexes:
const int MOTOR_REAR_LEFT = 0;
const int MOTOR_REAR_RIGHT = 1;
const int MOTOR_FRONT_RIGHT = 2;
const int MOTOR_FRONT_LEFT = 3;
void setupMotors() {
Serial.println("Setup Motors");
print("Setup Motors\n");
// configure pins
ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
@@ -23,28 +33,35 @@ void setupMotors() {
ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
sendMotors();
Serial.println("Motors initialized");
print("Motors initialized\n");
}
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));
int getDutyCycle(float value) {
value = constrain(value, 0, 1);
float pwm = mapff(value, 0, 1, PWM_MIN, PWM_MAX);
if (value == 0) pwm = PWM_STOP;
float duty = mapff(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
return round(duty);
}
void sendMotors() {
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]));
ledcWrite(MOTOR_0_PIN, getDutyCycle(motors[0]));
ledcWrite(MOTOR_1_PIN, getDutyCycle(motors[1]));
ledcWrite(MOTOR_2_PIN, getDutyCycle(motors[2]));
ledcWrite(MOTOR_3_PIN, getDutyCycle(motors[3]));
}
void fullMotorTest(int n) {
printf("Full test for motor %d\n", n);
for (float signal = 0; signal <= 1; signal += 0.1) {
printf("Motor %d: %f\n", n, signal);
ledcWrite(n, signalToDutyCycle(signal));
delay(3000);
}
printf("Motor %d: %f\n", n, 0);
ledcWrite(n, signalToDutyCycle(0));
bool motorsActive() {
return motors[0] != 0 || motors[1] != 0 || motors[2] != 0 || motors[3] != 0;
}
void testMotor(uint8_t n) {
print("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();
pause(3);
motors[n] = 0;
sendMotors();
print("Done\n");
}

145
flix/parameters.ino Normal file
View File

@@ -0,0 +1,145 @@
// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Parameters storage in flash memory
#include <Preferences.h>
extern float channelNeutral[16];
extern float channelMax[16];
extern float mavlinkControlScale;
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},
{"PITCHRATE_MAX", &maxRate.y},
{"ROLLRATE_MAX", &maxRate.x},
{"YAWRATE_MAX", &maxRate.z},
{"TILT_MAX", &tiltMax},
// imu
{"ACC_BIAS_X", &accBias.x},
{"ACC_BIAS_Y", &accBias.y},
{"ACC_BIAS_Z", &accBias.z},
{"ACC_SCALE_X", &accScale.x},
{"ACC_SCALE_Y", &accScale.y},
{"ACC_SCALE_Z", &accScale.z},
{"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]},
#if WIFI_ENABLED
// MAVLink
{"MAV_CTRL_SCALE", &mavlinkControlScale},
#endif
};
void setupParameters() {
storage.begin("flix", false);
// Read parameters from storage
for (auto &parameter : parameters) {
if (!storage.isKey(parameter.name)) {
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) {
if (index < 0 || index >= parametersCount()) return "";
return parameters[index].name;
}
float getParameter(int index) {
if (index < 0 || index >= parametersCount()) return NAN;
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 syncParameters() {
static double lastSync = 0;
if (t - lastSync < 1) return; // sync once per second
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
lastSync = t;
for (auto &parameter : parameters) {
if (parameter.value == *parameter.variable) continue;
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) {
print("%s = %g\n", parameter.name, *parameter.variable);
}
}
void resetParameters() {
storage.clear();
ESP.restart();
}

View File

@@ -60,7 +60,7 @@ public:
return ret;
}
void toAxisAngle(float& a, float& b, float& c, float& angle) {
void toAxisAngle(float& a, float& b, float& c, float& angle) const {
angle = acos(w) * 2;
a = x / sin(angle / 2);
b = y / sin(angle / 2);
@@ -126,7 +126,7 @@ public:
return (*this = ret);
}
Quaternion operator * (const Quaternion& q) {
Quaternion operator * (const Quaternion& q) const {
return Quaternion(
w * q.w - x * q.x - y * q.y - z * q.z,
w * q.x + x * q.w + y * q.z - z * q.y,
@@ -155,24 +155,33 @@ public:
z /= n;
}
Vector conjugate(const Vector& v) {
Vector conjugate(const Vector& v) const {
Quaternion qv(0, v.x, v.y, v.z);
Quaternion res = (*this) * qv * inversed();
return Vector(res.x, res.y, res.z);
}
Vector conjugateInversed(const Vector& v) {
Vector conjugateInversed(const Vector& v) const {
Quaternion qv(0, v.x, v.y, v.z);
Quaternion res = inversed() * qv * (*this);
return Vector(res.x, res.y, res.z);
}
// Rotate vector by quaternion
inline Vector rotate(const Vector& v) {
Vector rotateVector(const Vector& v) const {
return conjugateInversed(v);
}
inline bool finite() const {
// Rotate quaternion by quaternion
Quaternion rotate(const Quaternion& q, const bool normalize = true) const {
Quaternion rotated = (*this) * q;
if (normalize) {
rotated.normalize();
}
return rotated;
}
bool finite() const {
return isfinite(w) && isfinite(x) && isfinite(y) && isfinite(z);
}

View File

@@ -4,51 +4,66 @@
// Work with the RC receiver
#include <SBUS.h>
#include "util.h"
// NOTE: use 'cr' command to calibrate the RC and put the values here
int channelNeutral[] = {995, 883, 200, 972, 512, 512, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
int channelMax[] = {1651, 1540, 1713, 1630, 1472, 1472, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
SBUS RC(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
SBUS RC(Serial2, 16, 17); // NOTE: remove pin numbers (16, 17) if you use the new default pins for Serial2 (4, 25)
// RC channels mapping:
int rollChannel = 0;
int pitchChannel = 1;
int throttleChannel = 2;
int yawChannel = 3;
int armedChannel = 4;
int modeChannel = 5;
double controlsTime; // time of the last controls update
float channelNeutral[16] = {NAN}; // first element NAN means not calibrated
float channelMax[16];
void setupRC() {
Serial.println("Setup RC");
print("Setup RC\n");
RC.begin();
}
void readRC() {
bool readRC() {
if (RC.read()) {
SBUSData data = RC.data();
memcpy(channels, data.ch, sizeof(channels)); // copy channels data
normalizeRC();
controlsTime = t;
return true;
}
return false;
}
void normalizeRC() {
for (uint8_t i = 0; i < RC_CHANNELS; i++) {
if (isnan(channelNeutral[0])) return; // skip if not calibrated
for (uint8_t i = 0; i < 16; i++) {
controls[i] = mapf(channels[i], channelNeutral[i], channelMax[i], 0, 1);
}
}
void calibrateRC() {
Serial.println("Calibrate RC: move all sticks to maximum positions within 4 seconds");
Serial.println("··o ··o\n··· ···\n··· ···");
delay(4000);
for (int i = 0; i < 30; i++) readRC(); // ensure the values are updated
for (int i = 0; i < RC_CHANNELS; i++) {
print("Calibrate RC: move all sticks to maximum positions [4 sec]\n");
print("··o ··o\n··· ···\n··· ···\n");
pause(4);
while (!readRC());
for (int i = 0; i < 16; i++) {
channelMax[i] = channels[i];
}
Serial.println("Calibrate RC: move all sticks to neutral positions within 4 seconds");
Serial.println("··· ···\n··· ·o·\n·o· ···");
delay(4000);
for (int i = 0; i < 30; i++) readRC(); // ensure the values are updated
for (int i = 0; i < RC_CHANNELS; i++) {
print("Calibrate RC: move all sticks to neutral positions [4 sec]\n");
print("··· ···\n··· ·o·\n·o· ···\n");
pause(4);
while (!readRC());
for (int i = 0; i < 16; i++) {
channelNeutral[i] = channels[i];
}
printRCCal();
}
void printRCCal() {
printArray(channelNeutral, RC_CHANNELS);
printArray(channelMax, RC_CHANNELS);
for (int i = 0; i < sizeof(channelNeutral) / sizeof(channelNeutral[0]); i++) print("%g ", channelNeutral[i]);
print("\n");
for (int i = 0; i < sizeof(channelMax) / sizeof(channelMax[0]); i++) print("%g ", channelMax[i]);
print("\n");
}

View File

@@ -3,8 +3,10 @@
// Time related functions
float loopRate; // Hz
void step() {
float now = micros() / 1000000.0;
double now = micros() / 1000000.0;
dt = now - t;
t = now;
@@ -12,16 +14,16 @@ void step() {
dt = 0; // assume dt to be zero on first step and on reset
}
computeLoopFreq();
computeLoopRate();
}
void computeLoopFreq() {
static float windowStart = 0;
static uint32_t freq = 0;
freq++;
void computeLoopRate() {
static double windowStart = 0;
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

@@ -3,10 +3,14 @@
// Utility functions
#pragma once
#include <math.h>
#include <soc/soc.h>
#include <soc/rtc_cntl_reg.h>
const float ONE_G = 9.80665;
float mapf(long x, long in_min, long in_max, float out_min, float out_max) {
return (float)(x - in_min) * (out_max - out_min) / (float)(in_max - in_min) + out_min;
}
@@ -15,14 +19,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);
@@ -34,17 +30,17 @@ float wrapAngle(float angle) {
return angle;
}
template <typename T>
void printArray(T arr[], int size) {
Serial.print("{");
for (uint8_t i = 0; i < size; i++) {
Serial.print(arr[i]);
if (i < size - 1) Serial.print(", ");
}
Serial.println("}");
}
// Disable reset on low voltage
void disableBrownOut() {
WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA);
}
// Trim and split string by spaces
void splitString(String& str, String& token0, String& token1, String& token2) {
str.trim();
char chars[str.length() + 1];
str.toCharArray(chars, str.length() + 1);
token0 = strtok(chars, " ");
token1 = strtok(NULL, " "); // String(NULL) creates empty string
token2 = strtok(NULL, "");
}

View File

@@ -54,15 +54,15 @@ public:
return Vector(x / b.x, y / b.y, z / b.z);
}
inline bool operator == (const Vector& b) const {
bool operator == (const Vector& b) const {
return x == b.x && y == b.y && z == b.z;
}
inline bool operator != (const Vector& b) const {
bool operator != (const Vector& b) const {
return !(*this == b);
}
inline bool finite() const {
bool finite() const {
return isfinite(x) && isfinite(y) && isfinite(z);
}

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