Compare commits
52 Commits
v1.0
...
gyro-calib
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
073c860b90 | ||
|
|
fd30027ea4 | ||
|
|
6f190295cf | ||
|
|
ae349fb73c | ||
|
|
28f6cfff60 | ||
|
|
7533a9cbfa | ||
|
|
3cc3014ca0 | ||
|
|
b6286a50b2 | ||
|
|
4f2cf0c0b1 | ||
|
|
f06a9301df | ||
|
|
41cde3261a | ||
|
|
f54da5bf42 | ||
|
|
d01d5b7ecb | ||
|
|
0608765347 | ||
|
|
b70d16c1f7 | ||
|
|
f7253bed70 | ||
|
|
9957205d8f | ||
|
|
8440ddd3ee | ||
|
|
66ba9518ae | ||
|
|
d273b77ce2 | ||
|
|
77effa5577 | ||
|
|
fcb426a16f | ||
|
|
eea1a6a83c | ||
|
|
9d470cbdfa | ||
|
|
6e140d673c | ||
|
|
c75760e9e6 | ||
|
|
172b6becc6 | ||
|
|
475e9a87ba | ||
|
|
ea141f851f | ||
|
|
7fa3baa76a | ||
|
|
2c5eac92ea | ||
|
|
048a3c6375 | ||
|
|
a65ec946c0 | ||
|
|
429aecbbad | ||
|
|
a7b69f99d0 | ||
|
|
b015c15a7e | ||
|
|
7a2f2d955b | ||
|
|
c611549f67 | ||
|
|
be3c5bf312 | ||
|
|
f6ddeb4689 | ||
|
|
f6006d3305 | ||
|
|
eca48c6546 | ||
|
|
cd5f6721dc | ||
|
|
e7445599cc | ||
|
|
6327585754 | ||
|
|
ec832d4e37 | ||
|
|
2fdad7bdb6 | ||
|
|
c5c889679b | ||
|
|
ad2c64625c | ||
|
|
39d4f39932 | ||
|
|
57fe3fef2a | ||
|
|
4ba9accf4b |
38
.github/workflows/build.yml
vendored
@@ -60,22 +60,22 @@ jobs:
|
||||
path: gazebo/build/*.so
|
||||
retention-days: 1
|
||||
|
||||
build_simulator_macos:
|
||||
runs-on: macos-latest
|
||||
steps:
|
||||
- name: Install Arduino CLI
|
||||
run: brew install arduino-cli
|
||||
- uses: actions/checkout@v4
|
||||
- name: Clean up python binaries # Workaround for https://github.com/actions/setup-python/issues/577
|
||||
run: |
|
||||
rm -f /usr/local/bin/2to3*
|
||||
rm -f /usr/local/bin/idle3*
|
||||
rm -f /usr/local/bin/pydoc3*
|
||||
rm -f /usr/local/bin/python3*
|
||||
rm -f /usr/local/bin/python3*-config
|
||||
- name: Install Gazebo
|
||||
run: brew update && brew tap osrf/simulation && brew install gazebo11
|
||||
- name: Install SDL2
|
||||
run: brew install sdl2
|
||||
- name: Build simulator
|
||||
run: make build_simulator
|
||||
# build_simulator_macos:
|
||||
# runs-on: macos-latest
|
||||
# steps:
|
||||
# - name: Install Arduino CLI
|
||||
# run: brew install arduino-cli
|
||||
# - uses: actions/checkout@v4
|
||||
# - name: Clean up python binaries # Workaround for https://github.com/actions/setup-python/issues/577
|
||||
# run: |
|
||||
# rm -f /usr/local/bin/2to3*
|
||||
# rm -f /usr/local/bin/idle3*
|
||||
# rm -f /usr/local/bin/pydoc3*
|
||||
# rm -f /usr/local/bin/python3*
|
||||
# rm -f /usr/local/bin/python3*-config
|
||||
# - name: Install Gazebo
|
||||
# run: brew update && brew tap osrf/simulation && brew install gazebo11
|
||||
# - name: Install SDL2
|
||||
# run: brew install sdl2
|
||||
# - name: Build simulator
|
||||
# run: make build_simulator
|
||||
|
||||
51
.github/workflows/docs.yml
vendored
Normal 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
@@ -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
|
||||
}
|
||||
51
.vscode/c_cpp_properties.json
vendored
@@ -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.0.7/cores/esp32",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32",
|
||||
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/**",
|
||||
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include",
|
||||
"~/Arduino/libraries/**",
|
||||
"/usr/include/**"
|
||||
],
|
||||
"forcedInclude": [
|
||||
"${workspaceFolder}/.vscode/intellisense.h",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.0.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.0.7/cores/esp32/Arduino.h",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h",
|
||||
"${workspaceFolder}/flix/cli.ino",
|
||||
"${workspaceFolder}/flix/control.ino",
|
||||
"${workspaceFolder}/flix/estimate.ino",
|
||||
@@ -29,7 +29,8 @@
|
||||
"${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++",
|
||||
"cStandard": "c11",
|
||||
@@ -52,18 +53,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.0.7/cores/esp32",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32",
|
||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/include/**",
|
||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include",
|
||||
"~/Documents/Arduino/libraries/**",
|
||||
"/opt/homebrew/include/**"
|
||||
],
|
||||
"forcedInclude": [
|
||||
"${workspaceFolder}/.vscode/intellisense.h",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.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.0.7/cores/esp32/Arduino.h",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h",
|
||||
"${workspaceFolder}/flix/flix.ino",
|
||||
"${workspaceFolder}/flix/cli.ino",
|
||||
"${workspaceFolder}/flix/control.ino",
|
||||
@@ -76,7 +77,8 @@
|
||||
"${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++",
|
||||
"cStandard": "c11",
|
||||
@@ -100,17 +102,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.0.7/cores/esp32",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/**",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include",
|
||||
"~/Documents/Arduino/libraries/**"
|
||||
],
|
||||
"forcedInclude": [
|
||||
"${workspaceFolder}/.vscode/intellisense.h",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.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.0.7/cores/esp32/Arduino.h",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h",
|
||||
"${workspaceFolder}/flix/cli.ino",
|
||||
"${workspaceFolder}/flix/control.ino",
|
||||
"${workspaceFolder}/flix/estimate.ino",
|
||||
@@ -123,7 +125,8 @@
|
||||
"${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",
|
||||
"cStandard": "c11",
|
||||
|
||||
4
Makefile
@@ -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.0.7 --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
|
||||
|
||||
44
README.md
@@ -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).
|
||||
|
||||
@@ -53,25 +53,27 @@ 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|
|
||||
|IMU (and barometer²) board|GY‑91 (or other MPU‑9250/MPU‑6500 board), ICM‑20948³|<img src="docs/img/gy-91.jpg" width=90 align=center><img src="docs/img/icm-20948.jpg" width=100>|1|
|
||||
|Motor|8520 3.7V brushed motor (**shaft 0.8mm!**)|<img src="docs/img/motor.jpeg" width=100>|4|
|
||||
|Propeller|Hubsan 55 mm|<img src="docs/img/prop.jpg" width=100>|4|
|
||||
|MOSFET (transistor)|100N03A or [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|
|
||||
|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.stl`](docs/assets/flix-frame.stl) [`flix-frame.step`](docs/assets/flix-frame.step)|<img src="docs/img/frame1.jpg" width=100>|1|
|
||||
|Frame top part|3D printed:<br>[`esp32-holder.stl`](docs/assets/esp32-holder.stl) [`esp32-holder.step`](docs/assets/esp32-holder.step)|<img src="docs/img/esp32-holder.jpg" width=100>|1|
|
||||
|Washer for IMU board mounting|3D printed:<br>[`washer-m3.stl`](docs/assets/washer-m3.stl) [`washer-m3.step`](docs/assets/washer-m3.step)|<img src="docs/img/washer-m3.jpg" width=100>|1|
|
||||
|*RC transmitter (optional)*|*KINGKONG TINY X8 or other⁵*|<img src="docs/img/tx.jpg" width=100>|1|
|
||||
|*RC receiver (optional)*|*DF500 or other⁵*|<img src="docs/img/rx.jpg" width=100>|1|
|
||||
|Wires|28 AWG recommended|<img src="docs/img/wire-28awg.jpg" width=100>||
|
||||
|Tape, double-sided tape||||
|
||||
|
||||
*² — 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:
|
||||
|
||||
@@ -98,15 +100,15 @@ Complete diagram is Work-in-Progress.
|
||||
### 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.
|
||||
@@ -127,9 +129,19 @@ Complete diagram is Work-in-Progress.
|
||||
|-|-|
|
||||
|GND|GND|
|
||||
|VIN|VC (or 3.3V depending on the receiver)|
|
||||
|Signal|GPIO4⁴|
|
||||
|Signal|GPIO4⁶|
|
||||
|
||||
*⁴ — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.*
|
||||
*⁶ — 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
@@ -0,0 +1,10 @@
|
||||
build:
|
||||
mdbook build
|
||||
|
||||
serve:
|
||||
mdbook serve
|
||||
|
||||
clean:
|
||||
mdbook clean
|
||||
|
||||
.PHONY: build serve clean
|
||||
31
docs/alerts.py
Normal 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))
|
||||
1150
docs/assets/esp32-holder.step
Normal file
5113
docs/assets/flix-frame.step
Normal file
200
docs/assets/washer-m3.step
Normal 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
@@ -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
@@ -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
@@ -0,0 +1,10 @@
|
||||
# Flix
|
||||
|
||||
> [!IMPORTANT]
|
||||
> Flix — это проект по созданию открытого квадрокоптера на базе ESP32 с нуля и учебника по разработке полетных контроллеров.
|
||||
|
||||
<img src="img/flix1.jpg" class="border" width=500 alt="Flix quadcopter">
|
||||
|
||||
<p class="github">GitHub: <a href="https://github.com/okalachev/flix">github.com/okalachev/flix</a>.</p>
|
||||
|
||||
<p class="telegram">Telegram-канал: <a href="https://t.me/opensourcequadcopter">@opensourcequadcopter</a>.</p>
|
||||
22
docs/book/SUMMARY.md
Normal file
@@ -0,0 +1,22 @@
|
||||
<!-- markdownlint-disable MD041 -->
|
||||
<!-- markdownlint-disable MD042 -->
|
||||
|
||||
[Главная](./README.md)
|
||||
|
||||
* [Архитектура прошивки](firmware.md)
|
||||
|
||||
# Учебник
|
||||
|
||||
* [Основы]()
|
||||
* [Светодиод]()
|
||||
* [Моторы]()
|
||||
* [Радиоуправление]()
|
||||
* [Гироскоп](gyro.md)
|
||||
* [Акселерометр]()s
|
||||
* [Оценка состояния]()
|
||||
* [PID-регулятор]()
|
||||
* [Режим ACRO]()
|
||||
* [Режим STAB]()
|
||||
* [Wi-Fi]()
|
||||
* [MAVLink]()
|
||||
* [Симуляция]()
|
||||
32
docs/book/firmware.md
Normal file
@@ -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
@@ -0,0 +1,262 @@
|
||||
# Гироскоп
|
||||
|
||||
<div class="firmware">
|
||||
<strong>Файл прошивки Flix:</strong>
|
||||
<a href="https://github.com/okalachev/flix/blob/canonical/flix/imu.ino"><code>imu.ino</code></a> <small>(каноничная версия)</small>.<br>
|
||||
Текущая версия: <a href="https://github.com/okalachev/flix/blob/master/flix/imu.ino"><code>imu.ino</code></a>.
|
||||
</div>
|
||||
|
||||
Поддержание стабильного полета квадрокоптера невозможно без датчиков обратной связи. Важнейший из них — это **MEMS-гироскоп**. MEMS-гироскоп это микроэлектромеханический аналог классического механического гироскопа.
|
||||
|
||||
Механический гироскоп состоит из вращающегося диска, который сохраняет свою ориентацию в пространстве. Благодаря этому эффекту возможно определить ориентацию объекта в пространстве.
|
||||
|
||||
В MEMS-гироскопе нет вращающихся частей, и он помещается в крошечную микросхему. Он может измерять только текущую угловую скорость вращения объекта вокруг трех осей: X, Y и Z.
|
||||
|
||||
|Механический гироскоп|MEMS-гироскоп|
|
||||
|-|-|
|
||||
|<img src="img/gyroscope.jpg" width="300" alt="Механический гироскоп">|<img src="img/mpu9250.jpg" width="100" alt="MEMS-гироскоп MPU-9250">|
|
||||
|
||||
MEMS-гироскоп обычно интегрирован в инерциальный модуль (IMU), в котором также находятся акселерометр и магнитометр. Модуль IMU часто называют 9-осевым датчиком, потому что он измеряет:
|
||||
|
||||
* Угловую скорость вращения по трем осям (гироскоп).
|
||||
* Ускорение по трем осям (акселерометр).
|
||||
* Магнитное поле по трем осям (магнитометр).
|
||||
|
||||
Flix поддерживает следующие модели IMU:
|
||||
|
||||
* InvenSense MPU-9250.
|
||||
* InvenSense MPU-6500.
|
||||
* InvenSense ICM-20948.
|
||||
|
||||
> [!NOTE]
|
||||
> MEMS-гироскоп измеряет угловую скорость вращения объекта.
|
||||
|
||||
## Интерфейс подключения
|
||||
|
||||
Большинство модулей IMU подключаются к микроконтроллеру через интерфейсы I²C и SPI. Оба этих интерфейса являются *шинами данных*, то есть позволяют подключить к одному микроконтроллеру несколько устройств.
|
||||
|
||||
**Интерфейс I²C** использует два провода для передачи данных и тактового сигнала. Выбор устройства для коммуникации происходит при помощи передачи адреса устройства на шину. Разные устройства имеют разные адреса, и микроконтроллер может последовательно общаться с несколькими устройствами.
|
||||
|
||||
**Интерфейс SPI** использует два провода для передачи данных, еще один для тактового сигнала и еще один для выбора устройства. При этом для каждого устройства на шине выделяется отдельный GPIO-пин для выбора. В разных реализациях этот пин называется CS/NCS (Chip Select) или SS (Slave Select). Когда CS-пин устройства активен (напряжение на нем низкое), устройство выбрано для общения.
|
||||
|
||||
В полетных контроллерах IMU обычно подключают через SPI, потому что он обеспечивает значительно бо́льшую скорость передачи данных и меньшую задержку. Подключение IMU через интерфейс I²C (например, в случае нехватки пинов микроконтроллера) возможно, но не рекомендуется.
|
||||
|
||||
Подключение IMU к микроконтроллеру ESP32 через интерфейс SPI выглядит так:
|
||||
|
||||
|Пин платы IMU|Пин ESP32|
|
||||
|-|-|
|
||||
|VCC/3V3|3V3|
|
||||
|GND|GND|
|
||||
|SCL|IO18|
|
||||
|SDA *(MOSI)*|IO23|
|
||||
|SAO/AD0 *(MISO)*|IO19|
|
||||
|NCS|IO5|
|
||||
|
||||
Кроме того, многие IMU могут «будить» микроконтроллер при наличии новых данных. Для этого используется пин INT, который подключается к любому GPIO-пину микроконтроллера. При такой конфигурации можно использовать прерывания для обработки новых данных с IMU, вместо периодического опроса датчика. Это позволяет снизить нагрузку на микроконтроллер в сложных алгоритмах управления.
|
||||
|
||||
> [!WARNING]
|
||||
> На некоторых платах IMU, например, на ICM-20948, отсутствует стабилизатор напряжения, поэтому их нельзя подключать к пину VIN ESP32, который подает напряжение 5 В. Допустимо питание только от пина 3V3.
|
||||
|
||||
## Работа с гироскопом
|
||||
|
||||
Для взаимодействия с IMU, включая работу с гироскопом, в Flix используется библиотека *FlixPeriph*. Библиотека устанавливается через менеджер библиотек Arduino IDE:
|
||||
|
||||
<img src="img/flixperiph.png" width="300">
|
||||
|
||||
Чтобы работать с IMU, используется класс, соответствующий модели IMU: `MPU9250`, `MPU6500` или `ICM20948`. Классы для работы с разными IMU имеют единообразный интерфейс для основных операций, поэтому возможно легко переключаться между разными моделями IMU. Датчик MPU-6500 практически полностью совместим с MPU-9250, поэтому фактически класс `MPU9250` поддерживает обе модели.
|
||||
|
||||
## Ориентация осей гироскопа
|
||||
|
||||
Данные с гироскопа представляют собой угловую скорость вокруг трех осей: X, Y и Z. Ориентацию этих осей у IMU InvenSense можно легко определить по небольшой точке в углу чипа. Оси координат и направление вращения для измерений гироскопа обозначены на диаграмме:
|
||||
|
||||
<img src="img/imu-axes.svg" width="300" alt="Оси координат IMU">
|
||||
|
||||
Расположение осей координат в популярных платах IMU:
|
||||
|
||||
|GY-91|MPU-92/65|ICM-20948|
|
||||
|-|-|-|
|
||||
|<img src="https://github.com/okalachev/flixperiph/raw/refs/heads/master/img/gy91-axes.svg" width="200" alt="Оси координат платы GY-91">|<img src="https://github.com/okalachev/flixperiph/raw/refs/heads/master/img/mpu9265-axes.svg" width="200" alt="Оси координат платы MPU-9265">|<img src="https://github.com/okalachev/flixperiph/raw/refs/heads/master/img/icm20948-axes.svg" width="200" alt="Оси координат платы ICM-20948">|
|
||||
|
||||
Магнитометр IMU InvenSense обычно является отдельным устройством, интегрированным в чип, поэтому его оси координат могут отличаться. Библиотека FlixPeriph скрывает это различие и приводит данные с магнитометра к системе координат гироскопа и акселерометра.
|
||||
|
||||
## Чтение данных
|
||||
|
||||
Интерфейс библиотеки FlixPeriph соответствует стилю, принятому в Arduino. Для начала работы с IMU необходимо создать объект соответствующего класса и вызвать метод `begin()`. В конструктор класса передается интерфейс, по которому подключен IMU (SPI или I²C):
|
||||
|
||||
```cpp
|
||||
#include <FlixPeriph.h>
|
||||
#include <SPI.h>
|
||||
|
||||
MPU9250 IMU(SPI);
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
bool success = IMU.begin();
|
||||
if (!success) {
|
||||
Serial.println("Failed to initialize IMU");
|
||||
}
|
||||
}
|
||||
```
|
||||
|
||||
Для однократного считывания данных используется метод `read()`. Затем данные с гироскопа получаются при помощи метода `getGyro(x, y, z)`. Этот метод записывает в переменные `x`, `y` и `z` угловые скорости вокруг соответствующих осей в радианах в секунду.
|
||||
|
||||
Если нужно гарантировать, что будут считаны новые данные, можно использовать метод `waitForData()`. Этот метод блокирует выполнение программы до тех пор, пока в IMU не появятся новые данные. Метод `waitForData()` позволяет привязать частоту главного цикла `loop` к частоте обновления данных IMU. Это удобно для организации главного цикла управления квадрокоптером.
|
||||
|
||||
Программа для чтения данных с гироскопа и вывода их в консоль для построения графиков в Serial Plotter выглядит так:
|
||||
|
||||
```cpp
|
||||
#include <FlixPeriph.h>
|
||||
#include <SPI.h>
|
||||
|
||||
MPU9250 IMU(SPI);
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
bool success = IMU.begin();
|
||||
if (!success) {
|
||||
Serial.println("Failed to initialize IMU");
|
||||
}
|
||||
}
|
||||
|
||||
void loop() {
|
||||
IMU.waitForData();
|
||||
|
||||
float gx, gy, gz;
|
||||
IMU.getGyro(gx, gy, gz);
|
||||
|
||||
Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
|
||||
delay(50); // замедление вывода
|
||||
}
|
||||
```
|
||||
|
||||
После запуска программы в Serial Plotter можно увидеть графики угловых скоростей. Например, при вращениях IMU вокруг вертикальной оси Z графики будут выглядеть так:
|
||||
|
||||
<img src="img/gyro-plotter.png">
|
||||
|
||||
## Конфигурация гироскопа
|
||||
|
||||
В коде Flix настройка IMU происходит в функции `configureIMU`. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплов и частота LPF-фильтра.
|
||||
|
||||
### Частота сэмплов
|
||||
|
||||
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер. В Flix используется частота сэмплов 1 кГц.
|
||||
|
||||
Частота сэмплов устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
|
||||
|
||||
```cpp
|
||||
IMU.setRate(IMU.RATE_1KHZ_APPROX);
|
||||
```
|
||||
|
||||
Поскольку не все поддерживаемые IMU могут работать строго на частоте 1 кГц, в библиотеке FlixPeriph существует возможность приближенной настройки частоты сэмплов. Например, у IMU ICM-20948 при такой настройке реальная частота сэмплирования будет равна 1125 Гц.
|
||||
|
||||
Другие доступные для установки в библиотеке FlixPeriph частоты сэмплирования:
|
||||
|
||||
* `RATE_MIN` — минимальная частота сэмплов для конкретного IMU.
|
||||
* `RATE_50HZ_APPROX` — значение, близкое к 50 Гц.
|
||||
* `RATE_1KHZ_APPROX` — значение, близкое к 1 кГц.
|
||||
* `RATE_8KHZ_APPROX` — значение, близкое к 8 кГц.
|
||||
* `RATE_MAX` — максимальная частота сэмплов для конкретного IMU.
|
||||
|
||||
#### Диапазон измерений
|
||||
|
||||
Большинство MEMS-гироскопов поддерживают несколько диапазонов измерений угловой скорости. Главное преимущество выбора меньшего диапазона — бо́льшая чувствительность. В полетных контроллерах обычно выбирается максимальный диапазон измерений от –2000 до 2000 градусов в секунду, чтобы обеспечить возможность динамичных маневров.
|
||||
|
||||
В библиотеке FlixPeriph диапазон измерений гироскопа устанавливается методом `setGyroRange()`:
|
||||
|
||||
```cpp
|
||||
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
|
||||
```
|
||||
|
||||
### LPF-фильтр
|
||||
|
||||
IMU InvenSense могут фильтровать измерения на аппаратном уровне при помощи фильтра нижних частот (LPF). Flix реализует собственный фильтр для гироскопа, чтобы иметь больше гибкости при поддержке разных IMU. Поэтому для встроенного LPF устанавливается максимальная частота среза:
|
||||
|
||||
```cpp
|
||||
IMU.setDLPF(IMU.DLPF_MAX);
|
||||
```
|
||||
|
||||
## Калибровка гироскопа
|
||||
|
||||
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения (*bias*) и случайный шум (*noise*):
|
||||
|
||||
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]
|
||||
|
||||
Для качественной работы подсистемы оценки ориентации и управления дроном необходимо оценить *bias* гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции `calibrateGyro()`. Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются *bias* гироскопа и в дальнейшем вычитаются из измерений.
|
||||
|
||||
Программа для вывода данных с гироскопа с калибровкой:
|
||||
|
||||
```cpp
|
||||
#include <FlixPeriph.h>
|
||||
#include <SPI.h>
|
||||
|
||||
MPU9250 IMU(SPI);
|
||||
|
||||
float gyroBiasX, gyroBiasY, gyroBiasZ; // bias гироскопа
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
bool success = IMU.begin();
|
||||
if (!success) {
|
||||
Serial.println("Failed to initialize IMU");
|
||||
}
|
||||
calibrateGyro();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
float gx, gy, gz;
|
||||
IMU.waitForData();
|
||||
IMU.getGyro(gx, gy, gz);
|
||||
|
||||
// Устранение bias гироскопа
|
||||
gx -= gyroBiasX;
|
||||
gy -= gyroBiasY;
|
||||
gz -= gyroBiasZ;
|
||||
|
||||
Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
|
||||
delay(50); // замедление вывода
|
||||
}
|
||||
|
||||
void calibrateGyro() {
|
||||
const int samples = 1000;
|
||||
Serial.println("Calibrating gyro, stand still");
|
||||
|
||||
gyroBiasX = 0;
|
||||
gyroBiasY = 0;
|
||||
gyroBiasZ = 0;
|
||||
|
||||
// Получение 1000 измерений гироскопа
|
||||
for (int i = 0; i < samples; i++) {
|
||||
IMU.waitForData();
|
||||
float gx, gy, gz;
|
||||
IMU.getGyro(gx, gy, gz);
|
||||
gyroBiasX += gx;
|
||||
gyroBiasY += gy;
|
||||
gyroBiasZ += gz;
|
||||
}
|
||||
|
||||
// Усреднение значений
|
||||
gyroBiasX = gyroBiasX / samples;
|
||||
gyroBiasY = gyroBiasY / samples;
|
||||
gyroBiasZ = gyroBiasZ / samples;
|
||||
|
||||
Serial.printf("Gyro bias X: %f\n", gyroBiasX);
|
||||
Serial.printf("Gyro bias Y: %f\n", gyroBiasY);
|
||||
Serial.printf("Gyro bias Z: %f\n", gyroBiasZ);
|
||||
}
|
||||
```
|
||||
|
||||
График данных с гироскопа в состоянии покоя без калибровки. Можно увидеть статическую ошибку каждой из осей:
|
||||
|
||||
<img src="img/gyro-uncalibrated-plotter.png">
|
||||
|
||||
График данных с гироскопа в состоянии покоя после калибровки:
|
||||
|
||||
<img src="img/gyro-calibrated-plotter.png">
|
||||
|
||||
Откалиброванные данные с гироскопа вместе с данными с акселерометра поступают в *подсистему оценки состояния*.
|
||||
|
||||
## Дополнительные материалы
|
||||
|
||||
* [MPU-9250 datasheet](https://invensense.tdk.com/wp-content/uploads/2015/02/PS-MPU-9250A-01-v1.1.pdf).
|
||||
* [MPU-6500 datasheet](https://invensense.tdk.com/wp-content/uploads/2020/06/PS-MPU-6500A-01-v1.3.pdf).
|
||||
* [ICM-20948 datasheet](https://invensense.tdk.com/wp-content/uploads/2016/06/DS-000189-ICM-20948-v1.3.pdf).
|
||||
1
docs/book/img
Symbolic link
@@ -0,0 +1 @@
|
||||
../img
|
||||
@@ -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:
|
||||
|
||||
@@ -94,20 +96,19 @@ 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.
|
||||
2. Install ESP32 core, version 3.0.7 (version 2.x is not supported). See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
|
||||
3. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
|
||||
* `FlixPeriph`.
|
||||
* `MAVLink`, version 2.0.10.
|
||||
* `FlixPeriph`, the latest version.
|
||||
* `MAVLink`, version 2.0.12.
|
||||
4. Clone the project using git or [download the source code as a ZIP archive](https://codeload.github.com/okalachev/flix/zip/refs/heads/master).
|
||||
5. Open the downloaded Arduino sketch `flix/flix.ino` in Arduino IDE.
|
||||
6. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
|
||||
@@ -141,8 +142,7 @@ See other available Make commands in the [Makefile](../Makefile).
|
||||
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`).
|
||||
2. Type `ca` command there and follow the instructions.
|
||||
|
||||
#### Control with smartphone
|
||||
|
||||
@@ -158,11 +158,13 @@ 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`).
|
||||
2. Type `cr` command there and follow the instructions.
|
||||
|
||||
Then you can use your remote control to fly the drone!
|
||||
|
||||
> [!NOTE]
|
||||
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.
|
||||
|
||||
### Firmware code structure
|
||||
|
||||
See [firmware overview](firmware.md) for more details.
|
||||
|
||||
BIN
docs/img/flixperiph.png
Normal file
|
After Width: | Height: | Size: 17 KiB |
78
docs/img/gy91-lfd.svg
Normal file
|
After Width: | Height: | Size: 47 KiB |
BIN
docs/img/gyro-calibrated-plotter.png
Normal file
|
After Width: | Height: | Size: 115 KiB |
BIN
docs/img/gyro-plotter.png
Normal file
|
After Width: | Height: | Size: 114 KiB |
BIN
docs/img/gyro-uncalibrated-plotter.png
Normal file
|
After Width: | Height: | Size: 105 KiB |
BIN
docs/img/gyroscope.jpg
Normal file
|
After Width: | Height: | Size: 36 KiB |
BIN
docs/img/icm-20948.jpg
Normal file
|
After Width: | Height: | Size: 36 KiB |
119
docs/img/imu-axes.svg
Normal 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
|
After Width: | Height: | Size: 12 KiB |
|
Before Width: | Height: | Size: 5.9 KiB After Width: | Height: | Size: 6.7 KiB |
7
docs/js.js
Normal 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
@@ -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>
|
||||
© 2024 Олег Калачев
|
||||
</footer>
|
||||
</mdbook-sidebar-scrollbox>
|
||||
<noscript>
|
||||
<iframe class="sidebar-iframe-outer" src="{{ path_to_root }}toc.html"></iframe>
|
||||
</noscript>
|
||||
<div id="sidebar-resize-handle" class="sidebar-resize-handle">
|
||||
<div class="sidebar-resize-indicator"></div>
|
||||
</div>
|
||||
</nav>
|
||||
|
||||
<div id="page-wrapper" class="page-wrapper">
|
||||
|
||||
<div class="page">
|
||||
{{> header}}
|
||||
<div id="menu-bar-hover-placeholder"></div>
|
||||
<div id="menu-bar" class="menu-bar sticky">
|
||||
<div class="left-buttons">
|
||||
<label id="sidebar-toggle" class="icon-button" for="sidebar-toggle-anchor" title="Toggle Table of Contents" aria-label="Toggle Table of Contents" aria-controls="sidebar">
|
||||
<i class="fa fa-bars"></i>
|
||||
</label>
|
||||
<button id="theme-toggle" class="icon-button" type="button" title="Change theme" aria-label="Change theme" aria-haspopup="true" aria-expanded="false" aria-controls="theme-list">
|
||||
<i class="fa fa-paint-brush"></i>
|
||||
</button>
|
||||
<ul id="theme-list" class="theme-popup" aria-label="Themes" role="menu">
|
||||
<li role="none"><button role="menuitem" class="theme" id="light">Light</button></li>
|
||||
<li role="none"><button role="menuitem" class="theme" id="rust">Rust</button></li>
|
||||
<li role="none"><button role="menuitem" class="theme" id="coal">Coal</button></li>
|
||||
<li role="none"><button role="menuitem" class="theme" id="navy">Navy</button></li>
|
||||
<li role="none"><button role="menuitem" class="theme" id="ayu">Ayu</button></li>
|
||||
</ul>
|
||||
{{#if search_enabled}}
|
||||
<button id="search-toggle" class="icon-button" type="button" title="Search. (Shortkey: s)" aria-label="Toggle Searchbar" aria-expanded="false" aria-keyshortcuts="S" aria-controls="searchbar">
|
||||
<i class="fa fa-search"></i>
|
||||
</button>
|
||||
{{/if}}
|
||||
</div>
|
||||
|
||||
<h1 class="menu-title">{{ book_title }}</h1>
|
||||
|
||||
<div class="right-buttons">
|
||||
{{#if print_enable}}
|
||||
<a href="{{ path_to_root }}print.html" title="Print this book" aria-label="Print this book">
|
||||
<i id="print-button" class="fa fa-print"></i>
|
||||
</a>
|
||||
{{/if}}
|
||||
{{#if git_repository_url}}
|
||||
<a href="{{git_repository_url}}" title="Git repository" aria-label="Git repository">
|
||||
<i id="git-repository-button" class="fa {{git_repository_icon}}"></i>
|
||||
</a>
|
||||
{{/if}}
|
||||
{{#if git_repository_edit_url}}
|
||||
<a href="{{git_repository_edit_url}}" title="Suggest an edit" aria-label="Suggest an edit">
|
||||
<i id="git-edit-button" class="fa fa-edit"></i>
|
||||
</a>
|
||||
{{/if}}
|
||||
|
||||
</div>
|
||||
</div>
|
||||
|
||||
{{#if search_enabled}}
|
||||
<div id="search-wrapper" class="hidden">
|
||||
<form id="searchbar-outer" class="searchbar-outer">
|
||||
<input type="search" id="searchbar" name="searchbar" placeholder="Search this book ..." aria-controls="searchresults-outer" aria-describedby="searchresults-header">
|
||||
</form>
|
||||
<div id="searchresults-outer" class="searchresults-outer hidden">
|
||||
<div id="searchresults-header" class="searchresults-header"></div>
|
||||
<ul id="searchresults">
|
||||
</ul>
|
||||
</div>
|
||||
</div>
|
||||
{{/if}}
|
||||
|
||||
<!-- Apply ARIA attributes after the sidebar and the sidebar toggle button are added to the DOM -->
|
||||
<script>
|
||||
document.getElementById('sidebar-toggle').setAttribute('aria-expanded', sidebar === 'visible');
|
||||
document.getElementById('sidebar').setAttribute('aria-hidden', sidebar !== 'visible');
|
||||
Array.from(document.querySelectorAll('#sidebar a')).forEach(function(link) {
|
||||
link.setAttribute('tabIndex', sidebar === 'visible' ? 0 : -1);
|
||||
});
|
||||
</script>
|
||||
|
||||
<div id="content" class="content">
|
||||
<main>
|
||||
{{{ content }}}
|
||||
</main>
|
||||
|
||||
<nav class="nav-wrapper" aria-label="Page navigation">
|
||||
<!-- Mobile navigation buttons -->
|
||||
{{#previous}}
|
||||
<a rel="prev" href="{{ path_to_root }}{{link}}" class="mobile-nav-chapters previous" title="Previous chapter" aria-label="Previous chapter" aria-keyshortcuts="Left">
|
||||
<i class="fa fa-angle-left"></i>
|
||||
</a>
|
||||
{{/previous}}
|
||||
|
||||
{{#next}}
|
||||
<a rel="next prefetch" href="{{ path_to_root }}{{link}}" class="mobile-nav-chapters next" title="Next chapter" aria-label="Next chapter" aria-keyshortcuts="Right">
|
||||
<i class="fa fa-angle-right"></i>
|
||||
</a>
|
||||
{{/next}}
|
||||
|
||||
<div style="clear: both"></div>
|
||||
</nav>
|
||||
</div>
|
||||
</div>
|
||||
|
||||
<nav class="nav-wide-wrapper" aria-label="Page navigation">
|
||||
{{#previous}}
|
||||
<a rel="prev" href="{{ path_to_root }}{{link}}" class="nav-chapters previous" title="Previous chapter" aria-label="Previous chapter" aria-keyshortcuts="Left">
|
||||
<i class="fa fa-angle-left"></i>
|
||||
</a>
|
||||
{{/previous}}
|
||||
|
||||
{{#next}}
|
||||
<a rel="next prefetch" href="{{ path_to_root }}{{link}}" class="nav-chapters next" title="Next chapter" aria-label="Next chapter" aria-keyshortcuts="Right">
|
||||
<i class="fa fa-angle-right"></i>
|
||||
</a>
|
||||
{{/next}}
|
||||
</nav>
|
||||
|
||||
</div>
|
||||
|
||||
{{#if live_reload_endpoint}}
|
||||
<!-- Livereload script (if served using the cli tool) -->
|
||||
<script>
|
||||
const wsProtocol = location.protocol === 'https:' ? 'wss:' : 'ws:';
|
||||
const wsAddress = wsProtocol + "//" + location.host + "/" + "{{{live_reload_endpoint}}}";
|
||||
const socket = new WebSocket(wsAddress);
|
||||
socket.onmessage = function (event) {
|
||||
if (event.data === "reload") {
|
||||
socket.close();
|
||||
location.reload();
|
||||
}
|
||||
};
|
||||
|
||||
window.onbeforeunload = function() {
|
||||
socket.close();
|
||||
}
|
||||
</script>
|
||||
{{/if}}
|
||||
|
||||
{{#if google_analytics}}
|
||||
<!-- Google Analytics Tag -->
|
||||
<script>
|
||||
var localAddrs = ["localhost", "127.0.0.1", ""];
|
||||
|
||||
// make sure we don't activate google analytics if the developer is
|
||||
// inspecting the book locally...
|
||||
if (localAddrs.indexOf(document.location.hostname) === -1) {
|
||||
(function(i,s,o,g,r,a,m){i['GoogleAnalyticsObject']=r;i[r]=i[r]||function(){
|
||||
(i[r].q=i[r].q||[]).push(arguments)},i[r].l=1*new Date();a=s.createElement(o),
|
||||
m=s.getElementsByTagName(o)[0];a.async=1;a.src=g;m.parentNode.insertBefore(a,m)
|
||||
})(window,document,'script','https://www.google-analytics.com/analytics.js','ga');
|
||||
|
||||
ga('create', '{{google_analytics}}', 'auto');
|
||||
ga('send', 'pageview');
|
||||
}
|
||||
</script>
|
||||
{{/if}}
|
||||
|
||||
{{#if playground_line_numbers}}
|
||||
<script>
|
||||
window.playground_line_numbers = true;
|
||||
</script>
|
||||
{{/if}}
|
||||
|
||||
{{#if playground_copyable}}
|
||||
<script>
|
||||
window.playground_copyable = true;
|
||||
</script>
|
||||
{{/if}}
|
||||
|
||||
{{#if playground_js}}
|
||||
<script src="{{ path_to_root }}ace.js"></script>
|
||||
<script src="{{ path_to_root }}editor.js"></script>
|
||||
<script src="{{ path_to_root }}mode-rust.js"></script>
|
||||
<script src="{{ path_to_root }}theme-dawn.js"></script>
|
||||
<script src="{{ path_to_root }}theme-tomorrow_night.js"></script>
|
||||
{{/if}}
|
||||
|
||||
{{#if search_js}}
|
||||
<script src="{{ path_to_root }}elasticlunr.min.js"></script>
|
||||
<script src="{{ path_to_root }}mark.min.js"></script>
|
||||
<script src="{{ path_to_root }}searcher.js"></script>
|
||||
{{/if}}
|
||||
|
||||
<script src="{{ path_to_root }}clipboard.min.js"></script>
|
||||
<script src="{{ path_to_root }}highlight.js"></script>
|
||||
<script src="{{ path_to_root }}book.js"></script>
|
||||
|
||||
<!-- Custom JS scripts -->
|
||||
{{#each additional_js}}
|
||||
<script src="{{ ../path_to_root }}{{this}}"></script>
|
||||
{{/each}}
|
||||
|
||||
{{#if is_print}}
|
||||
{{#if mathjax_support}}
|
||||
<script>
|
||||
window.addEventListener('load', function() {
|
||||
MathJax.Hub.Register.StartupHook('End', function() {
|
||||
window.setTimeout(window.print, 100);
|
||||
});
|
||||
});
|
||||
</script>
|
||||
{{else}}
|
||||
<script>
|
||||
window.addEventListener('load', function() {
|
||||
window.setTimeout(window.print, 100);
|
||||
});
|
||||
</script>
|
||||
{{/if}}
|
||||
{{/if}}
|
||||
|
||||
</div>
|
||||
</body>
|
||||
</html>
|
||||
33
docs/troubleshooting.md
Normal file
@@ -0,0 +1,33 @@
|
||||
# Troubleshooting
|
||||
|
||||
## The sketch doesn't compile
|
||||
|
||||
Do the following:
|
||||
|
||||
* **Check ESP32 core is installed**. Check if the version matches the one used in the [tutorial](build.md#firmware).
|
||||
* **Check libraries**. Install all the required libraries from the tutorial. Make sure there are no MPU9250 or other peripherals libraries that may conflict with the ones used in the tutorial.
|
||||
|
||||
## The drone doesn't fly
|
||||
|
||||
Do the following:
|
||||
|
||||
* **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V.
|
||||
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button to make sure you see the whole ESP32 output.
|
||||
* **Make sure correct IMU model is chosen**. If using ICM-20948 board, change `MPU9250` to `ICM20948` everywhere in the `imu.ino` file.
|
||||
* **Check if the CLI is working**. Perform `help` command in Serial Monitor. You should see the list of available commands.
|
||||
* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
|
||||
* **Make sure you're not moving the drone several seconds after the power on**. The drone calibrates its gyroscope on the start so it should stay still for a while.
|
||||
* **Check the IMU sample rate**. Perform `imu` command. The `rate` field should be about 1000 (Hz).
|
||||
* **Check the IMU data**. Perform `imu` command, check raw accelerometer and gyro output. The output should change as you move the drone.
|
||||
* **Calibrate the accelerometer.** if is wasn't done before. Type `ca` command in Serial Monitor and follow the instructions.
|
||||
* **Check the attitude estimation**. Connect to the drone using QGroundControl. Rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct.
|
||||
* **Check the IMU orientation is set correctly**. If the attitude estimation is rotated, make sure `rotateIMU` function is defined correctly in `imu.ino` file.
|
||||
* **Check the motors**. Perform the following commands using Serial Monitor:
|
||||
* `mfr` — should rotate front right motor (counter-clockwise).
|
||||
* `mfl` — should rotate front left motor (clockwise).
|
||||
* `mrl` — should rotate rear left motor (counter-clockwise).
|
||||
* `mrr` — should rotate rear right motor (clockwise).
|
||||
* **Calibrate the RC** if you use it. Type `cr` command in Serial Monitor and follow the instructions.
|
||||
* **Check the RC data** if you use it. Use `rc` command, `Control` should show correct values between -1 and 1, and between 0 and 1 for the throttle.
|
||||
* **Check the IMU output using QGroundControl**. Connect to the drone using QGroundControl on your computer. Go to the *Analyze* tab, *MAVLINK Inspector*. Plot the data from the `SCALED_IMU` message. The gyroscope and accelerometer data should change according to the drone movement.
|
||||
* **Check the gyroscope only attitude estimation**. Comment out `applyAcc();` line in `estimate.ino` and check if the attitude estimation in QGroundControl. It should be stable, but only drift very slowly.
|
||||
@@ -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).*
|
||||
|
||||
|
||||
31
docs/zoom.css
Normal 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
@@ -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()
|
||||
}()
|
||||
116
flix/cli.ino
@@ -19,61 +19,50 @@ const char* motd =
|
||||
"|__| |_______||__| /__/ \\__\\\n\n"
|
||||
"Commands:\n\n"
|
||||
"help - show help\n"
|
||||
"show - show all parameters\n"
|
||||
"<name> <value> - set parameter\n"
|
||||
"p - show all parameters\n"
|
||||
"p <name> - show parameter\n"
|
||||
"p <name> <value> - set parameter\n"
|
||||
"preset - reset parameters\n"
|
||||
"ps - show pitch/roll/yaw\n"
|
||||
"psq - show attitude quaternion\n"
|
||||
"imu - show IMU data\n"
|
||||
"rc - show RC data\n"
|
||||
"mot - show motor data\n"
|
||||
"mot - show motor output\n"
|
||||
"log - dump in-RAM log\n"
|
||||
"cr - calibrate RC\n"
|
||||
"cg - calibrate gyro\n"
|
||||
"ca - calibrate accel\n"
|
||||
"mfr, mfl, mrr, mrl - test appropriate motor\n"
|
||||
"fullmot <n> - full motor test\n"
|
||||
"reset - reset drone's state\n";
|
||||
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
|
||||
"reset - reset drone's state\n"
|
||||
"reboot - reboot the drone\n";
|
||||
|
||||
const struct Param {
|
||||
const char* name;
|
||||
float* value;
|
||||
float* value2;
|
||||
} params[] = {
|
||||
{"rp", &rollRatePID.p, &pitchRatePID.p},
|
||||
{"ri", &rollRatePID.i, &pitchRatePID.i},
|
||||
{"rd", &rollRatePID.d, &pitchRatePID.d},
|
||||
|
||||
{"ap", &rollPID.p, &pitchPID.p},
|
||||
{"ai", &rollPID.i, &pitchPID.i},
|
||||
{"ad", &rollPID.d, &pitchPID.d},
|
||||
|
||||
{"yp", &yawRatePID.p, nullptr},
|
||||
{"yi", &yawRatePID.i, nullptr},
|
||||
{"yd", &yawRatePID.d, nullptr},
|
||||
|
||||
{"lpr", &ratesFilter.alpha, nullptr},
|
||||
{"lpd", &rollRatePID.lpf.alpha, &pitchRatePID.lpf.alpha},
|
||||
|
||||
{"ss", &loopFreq, nullptr},
|
||||
{"dt", &dt, nullptr},
|
||||
{"t", &t, nullptr},
|
||||
};
|
||||
|
||||
void doCommand(String& command, String& value) {
|
||||
void doCommand(String& command, String& arg0, String& arg1) {
|
||||
if (command == "help" || command == "motd") {
|
||||
Serial.println(motd);
|
||||
} else if (command == "show") {
|
||||
showTable();
|
||||
} else if (command == "p" && arg0 == "") {
|
||||
printParameters();
|
||||
} else if (command == "p" && arg0 != "" && arg1 == "") {
|
||||
Serial.printf("%s = %g\n", arg0.c_str(), getParameter(arg0.c_str()));
|
||||
} else if (command == "p") {
|
||||
bool success = setParameter(arg0.c_str(), arg1.toFloat());
|
||||
if (success) {
|
||||
Serial.printf("%s = %g\n", arg0.c_str(), arg1.toFloat());
|
||||
} else {
|
||||
Serial.printf("Parameter not found: %s\n", arg0.c_str());
|
||||
}
|
||||
} else if (command == "preset") {
|
||||
resetParameters();
|
||||
} else if (command == "ps") {
|
||||
Vector a = attitude.toEulerZYX();
|
||||
Serial.printf("roll: %f pitch: %f yaw: %f\n", a.x * RAD_TO_DEG, a.y * RAD_TO_DEG, a.z * RAD_TO_DEG);
|
||||
} else if (command == "psq") {
|
||||
Serial.printf("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
|
||||
} else if (command == "imu") {
|
||||
printIMUInfo();
|
||||
Serial.printf("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
|
||||
Serial.printf("acc: %f %f %f\n", acc.x, acc.y, acc.z);
|
||||
printIMUCal();
|
||||
Serial.printf("frequency: %f\n", loopFreq);
|
||||
Serial.printf("rate: %f\n", loopRate);
|
||||
} else if (command == "rc") {
|
||||
Serial.printf("Raw: throttle %d yaw %d pitch %d roll %d armed %d mode %d\n",
|
||||
channels[RC_CHANNEL_THROTTLE], channels[RC_CHANNEL_YAW], channels[RC_CHANNEL_PITCH],
|
||||
@@ -101,41 +90,23 @@ void doCommand(String& command, String& value) {
|
||||
cliTestMotor(MOTOR_REAR_RIGHT);
|
||||
} else if (command == "mrl") {
|
||||
cliTestMotor(MOTOR_REAR_LEFT);
|
||||
} else if (command == "fullmot") {
|
||||
fullMotorTest(value.toInt());
|
||||
} else if (command == "reset") {
|
||||
attitude = Quaternion();
|
||||
} else if (command == "reboot") {
|
||||
ESP.restart();
|
||||
} else if (command == "") {
|
||||
// do nothing
|
||||
} else {
|
||||
float val = value.toFloat();
|
||||
// TODO: on error returns 0, check invalid value
|
||||
|
||||
for (uint8_t i = 0; i < sizeof(params) / sizeof(params[0]); i++) {
|
||||
if (command == params[i].name) {
|
||||
*params[i].value = val;
|
||||
if (params[i].value2 != nullptr) *params[i].value2 = val;
|
||||
Serial.print(command);
|
||||
Serial.print(" = ");
|
||||
Serial.println(val, 4);
|
||||
return;
|
||||
}
|
||||
}
|
||||
Serial.println("Invalid command: " + command);
|
||||
}
|
||||
}
|
||||
|
||||
void showTable() {
|
||||
for (uint8_t i = 0; i < sizeof(params) / sizeof(params[0]); i++) {
|
||||
Serial.print(params[i].name);
|
||||
Serial.print(" ");
|
||||
Serial.println(*params[i].value, 5);
|
||||
}
|
||||
}
|
||||
|
||||
void cliTestMotor(uint8_t n) {
|
||||
Serial.printf("Testing motor %d\n", n);
|
||||
motors[n] = 1;
|
||||
delay(50); // ESP32 may need to wait until the end of the current cycle to change duty https://github.com/espressif/arduino-esp32/issues/5306
|
||||
sendMotors();
|
||||
delay(5000);
|
||||
delay(3000);
|
||||
motors[n] = 0;
|
||||
sendMotors();
|
||||
Serial.println("Done");
|
||||
@@ -143,9 +114,7 @@ void cliTestMotor(uint8_t n) {
|
||||
|
||||
void parseInput() {
|
||||
static bool showMotd = true;
|
||||
static String command;
|
||||
static String value;
|
||||
static bool parsingCommand = true;
|
||||
static String input;
|
||||
|
||||
if (showMotd) {
|
||||
Serial.println(motd);
|
||||
@@ -155,16 +124,21 @@ void parseInput() {
|
||||
while (Serial.available()) {
|
||||
char c = Serial.read();
|
||||
if (c == '\n') {
|
||||
parsingCommand = true;
|
||||
if (!command.isEmpty()) {
|
||||
doCommand(command, value);
|
||||
}
|
||||
command.clear();
|
||||
value.clear();
|
||||
} else if (c == ' ') {
|
||||
parsingCommand = false;
|
||||
char chars[input.length() + 1];
|
||||
input.toCharArray(chars, input.length() + 1);
|
||||
String command = stringToken(chars, " ");
|
||||
String arg0 = stringToken(NULL, " ");
|
||||
String arg1 = stringToken(NULL, "");
|
||||
doCommand(command, arg0, arg1);
|
||||
input.clear();
|
||||
} else {
|
||||
(parsingCommand ? command : value) += c;
|
||||
input += c;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Helper function for parsing input
|
||||
String stringToken(char* str, const char* delim) {
|
||||
char* token = strtok(str, delim);
|
||||
return token == NULL ? "" : token;
|
||||
}
|
||||
|
||||
@@ -52,6 +52,7 @@ float thrustTarget;
|
||||
|
||||
void control() {
|
||||
interpretRC();
|
||||
failsafe();
|
||||
if (mode == STAB) {
|
||||
controlAttitude();
|
||||
controlRate();
|
||||
|
||||
@@ -7,7 +7,6 @@
|
||||
#include "vector.h"
|
||||
#include "lpf.h"
|
||||
|
||||
#define ONE_G 9.807f
|
||||
#define WEIGHT_ACC 0.5f
|
||||
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||
|
||||
@@ -16,7 +15,6 @@ LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
|
||||
void estimate() {
|
||||
applyGyro();
|
||||
applyAcc();
|
||||
signalizeHorizontality();
|
||||
}
|
||||
|
||||
void applyGyro() {
|
||||
@@ -33,6 +31,7 @@ void applyAcc() {
|
||||
float accNorm = acc.norm();
|
||||
bool landed = !motorsActive() && abs(accNorm - ONE_G) < ONE_G * 0.1f;
|
||||
|
||||
setLED(landed);
|
||||
if (!landed) return;
|
||||
|
||||
// calculate accelerometer correction
|
||||
@@ -43,8 +42,3 @@ void applyAcc() {
|
||||
attitude *= Quaternion::fromAngularRates(correction);
|
||||
attitude.normalize();
|
||||
}
|
||||
|
||||
void signalizeHorizontality() {
|
||||
float angle = Vector::angleBetweenVectors(attitude.rotate(Vector(0, 0, 1)), Vector(0, 0, 1));
|
||||
setLED(angle < radians(15));
|
||||
}
|
||||
|
||||
23
flix/failsafe.ino
Normal file
@@ -0,0 +1,23 @@
|
||||
// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// Fail-safe for RC loss
|
||||
|
||||
#define RC_LOSS_TIMEOUT 0.2
|
||||
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
|
||||
|
||||
void failsafe() {
|
||||
if (t - controlsTime > RC_LOSS_TIMEOUT) {
|
||||
descend();
|
||||
}
|
||||
}
|
||||
|
||||
void descend() {
|
||||
// Smooth descend on RC lost
|
||||
mode = STAB;
|
||||
controls[RC_CHANNEL_ROLL] = 0;
|
||||
controls[RC_CHANNEL_PITCH] = 0;
|
||||
controls[RC_CHANNEL_YAW] = 0;
|
||||
controls[RC_CHANNEL_THROTTLE] -= dt / DESCEND_TIME;
|
||||
if (controls[RC_CHANNEL_THROTTLE] < 0) controls[RC_CHANNEL_THROTTLE] = 0;
|
||||
}
|
||||
@@ -23,21 +23,26 @@
|
||||
#define MOTOR_FRONT_RIGHT 2
|
||||
#define MOTOR_FRONT_LEFT 3
|
||||
|
||||
#define ONE_G 9.80665
|
||||
|
||||
float t = NAN; // current step time, s
|
||||
float dt; // time delta from previous step, s
|
||||
float loopFreq; // loop frequency, Hz
|
||||
float loopRate; // loop rate, Hz
|
||||
int16_t channels[RC_CHANNELS]; // raw rc channels
|
||||
float controls[RC_CHANNELS]; // normalized controls in range [-1..1] ([0..1] for throttle)
|
||||
float controlsTime; // time of the last controls update
|
||||
Vector gyro; // gyroscope data
|
||||
Vector acc; // accelerometer data, m/s/s
|
||||
Vector rates; // filtered angular rates, rad/s
|
||||
Quaternion attitude; // estimated attitude
|
||||
bool landed; // are we landed and stationary
|
||||
float motors[4]; // normalized motors thrust in range [-1..1]
|
||||
|
||||
void setup() {
|
||||
Serial.begin(SERIAL_BAUDRATE);
|
||||
Serial.println("Initializing flix");
|
||||
disableBrownOut();
|
||||
setupParameters();
|
||||
setupLED();
|
||||
setupMotors();
|
||||
setLED(true);
|
||||
@@ -63,4 +68,5 @@ void loop() {
|
||||
processMavlink();
|
||||
#endif
|
||||
logData();
|
||||
flushParameters();
|
||||
}
|
||||
|
||||
52
flix/imu.ino
@@ -2,21 +2,15 @@
|
||||
// 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);
|
||||
|
||||
MPU9250 IMU(SPI);
|
||||
|
||||
Vector accBias;
|
||||
Vector gyroBias;
|
||||
Vector accScale(1, 1, 1);
|
||||
|
||||
void setupIMU() {
|
||||
Serial.println("Setup IMU");
|
||||
@@ -27,23 +21,42 @@ void setupIMU() {
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
calibrateGyro();
|
||||
configureIMU();
|
||||
// calibrateGyro();
|
||||
}
|
||||
|
||||
void configureIMU() {
|
||||
IMU.setAccelRange(IMU.ACCEL_RANGE_4G);
|
||||
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
|
||||
IMU.setDlpfBandwidth(IMU.DLPF_BANDWIDTH_184HZ);
|
||||
IMU.setSrd(0); // set sample rate to 1000 Hz
|
||||
IMU.setDLPF(IMU.DLPF_MAX);
|
||||
IMU.setRate(IMU.RATE_1KHZ_APPROX);
|
||||
}
|
||||
|
||||
void readIMU() {
|
||||
IMU.waitForData();
|
||||
IMU.getGyro(gyro.x, gyro.y, gyro.z);
|
||||
IMU.getAccel(acc.x, acc.y, acc.z);
|
||||
calibrateGyroOnce();
|
||||
// apply scale and bias
|
||||
acc = (acc - accBias) / accScale;
|
||||
gyro = gyro - gyroBias;
|
||||
// rotate
|
||||
rotateIMU(acc);
|
||||
rotateIMU(gyro);
|
||||
}
|
||||
|
||||
void rotateIMU(Vector& data) {
|
||||
// Rotate from LFD to FLU
|
||||
// NOTE: In case of using other IMU orientation, change this line:
|
||||
data = Vector(data.y, data.x, -data.z);
|
||||
// Axes orientation for various boards: https://github.com/okalachev/flixperiph#imu-axes-orientation
|
||||
}
|
||||
|
||||
void calibrateGyroOnce() {
|
||||
if (!landed) return;
|
||||
static float samples = 0; // overflows after 49 days at 1000 Hz
|
||||
samples++;
|
||||
gyroBias = gyroBias + (gyro - gyroBias) / samples; // running average
|
||||
}
|
||||
|
||||
void calibrateGyro() {
|
||||
@@ -66,8 +79,6 @@ void calibrateGyro() {
|
||||
void calibrateAccel() {
|
||||
Serial.println("Calibrating accelerometer");
|
||||
IMU.setAccelRange(IMU.ACCEL_RANGE_2G); // the most sensitive mode
|
||||
IMU.setDlpfBandwidth(IMU.DLPF_BANDWIDTH_20HZ);
|
||||
IMU.setSrd(19);
|
||||
|
||||
Serial.setTimeout(60000);
|
||||
Serial.print("Place level [enter] "); Serial.readStringUntil('\n');
|
||||
@@ -88,7 +99,7 @@ void calibrateAccel() {
|
||||
}
|
||||
|
||||
void calibrateAccelOnce() {
|
||||
const int samples = 100;
|
||||
const int samples = 1000;
|
||||
static Vector accMax(-INFINITY, -INFINITY, -INFINITY);
|
||||
static Vector accMin(INFINITY, INFINITY, INFINITY);
|
||||
|
||||
@@ -118,7 +129,12 @@ void calibrateAccelOnce() {
|
||||
}
|
||||
|
||||
void printIMUCal() {
|
||||
Serial.printf("gyro bias: %f %f %f\n", gyroBias.x, gyroBias.y, gyroBias.z);
|
||||
Serial.printf("accel bias: %f %f %f\n", accBias.x, accBias.y, accBias.z);
|
||||
Serial.printf("accel scale: %f %f %f\n", accScale.x, accScale.y, accScale.z);
|
||||
Serial.printf("gyro bias: %f, %f, %f\n", gyroBias.x, gyroBias.y, gyroBias.z);
|
||||
Serial.printf("accel bias: %f, %f, %f\n", accBias.x, accBias.y, accBias.z);
|
||||
Serial.printf("accel scale: %f, %f, %f\n", accScale.x, accScale.y, accScale.z);
|
||||
}
|
||||
|
||||
void printIMUInfo() {
|
||||
Serial.printf("model: %s\n", IMU.getModel());
|
||||
Serial.printf("who am I: 0x%02X\n", IMU.whoAmI());
|
||||
}
|
||||
|
||||
@@ -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() {
|
||||
|
||||
@@ -84,6 +84,7 @@ void receiveMavlink() {
|
||||
|
||||
void handleMavlink(const void *_msg) {
|
||||
mavlink_message_t *msg = (mavlink_message_t *)_msg;
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
|
||||
mavlink_manual_control_t manualControl;
|
||||
mavlink_msg_manual_control_decode(msg, &manualControl);
|
||||
@@ -93,9 +94,72 @@ void handleMavlink(const void *_msg) {
|
||||
controls[RC_CHANNEL_YAW] = manualControl.r / 1000.0f * MAVLINK_CONTROL_SCALE;
|
||||
controls[RC_CHANNEL_MODE] = 1; // STAB mode
|
||||
controls[RC_CHANNEL_ARMED] = 1; // armed
|
||||
controlsTime = t;
|
||||
|
||||
if (abs(controls[RC_CHANNEL_YAW]) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controls[RC_CHANNEL_YAW] = 0;
|
||||
}
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
|
||||
mavlink_message_t msg;
|
||||
for (int i = 0; i < parametersCount(); i++) {
|
||||
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
getParameterName(i), getParameter(i), MAV_PARAM_TYPE_REAL32, parametersCount(), i);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
}
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_PARAM_REQUEST_READ) {
|
||||
mavlink_param_request_read_t paramRequestRead;
|
||||
mavlink_msg_param_request_read_decode(msg, ¶mRequestRead);
|
||||
char name[16 + 1];
|
||||
strlcpy(name, paramRequestRead.param_id, sizeof(name)); // param_id might be not null-terminated
|
||||
float value = strlen(name) == 0 ? getParameter(paramRequestRead.param_index) : getParameter(name);
|
||||
if (paramRequestRead.param_index != -1) {
|
||||
memcpy(name, getParameterName(paramRequestRead.param_index), 16);
|
||||
}
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
name, value, MAV_PARAM_TYPE_REAL32, parametersCount(), paramRequestRead.param_index);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_PARAM_SET) {
|
||||
mavlink_param_set_t paramSet;
|
||||
mavlink_msg_param_set_decode(msg, ¶mSet);
|
||||
char name[16 + 1];
|
||||
strlcpy(name, paramSet.param_id, sizeof(name)); // param_id might be not null-terminated
|
||||
setParameter(name, paramSet.param_value);
|
||||
// send ack
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
paramSet.param_id, paramSet.param_value, MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
|
||||
sendMessage(&msg);
|
||||
}
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_MISSION_REQUEST_LIST) { // handle to make qgc happy
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_mission_count_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, 0, 0, 0, MAV_MISSION_TYPE_MISSION, 0);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
|
||||
// Handle commands
|
||||
if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
|
||||
mavlink_command_long_t commandLong;
|
||||
mavlink_msg_command_long_decode(msg, &commandLong);
|
||||
mavlink_message_t ack;
|
||||
mavlink_message_t response;
|
||||
|
||||
if (commandLong.command == MAV_CMD_REQUEST_MESSAGE && commandLong.param1 == MAVLINK_MSG_ID_AUTOPILOT_VERSION) {
|
||||
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, commandLong.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg->sysid, msg->compid);
|
||||
sendMessage(&ack);
|
||||
mavlink_msg_autopilot_version_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &response,
|
||||
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MAVLINK2, 1, 0, 1, 1, 0, 0, 0, 0, 0, 0, 0);
|
||||
sendMessage(&response);
|
||||
} else {
|
||||
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, commandLong.command, MAV_RESULT_UNSUPPORTED, UINT8_MAX, 0, msg->sysid, msg->compid);
|
||||
sendMessage(&ack);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Convert Forward-Left-Up to Forward-Right-Down quaternion
|
||||
|
||||
@@ -37,14 +37,3 @@ void sendMotors() {
|
||||
ledcWrite(MOTOR_2_PIN, signalToDutyCycle(motors[2]));
|
||||
ledcWrite(MOTOR_3_PIN, signalToDutyCycle(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));
|
||||
}
|
||||
|
||||
133
flix/parameters.ino
Normal file
@@ -0,0 +1,133 @@
|
||||
#pragma once
|
||||
|
||||
#include <Preferences.h>
|
||||
#include <vector>
|
||||
|
||||
extern float channelNeutral[RC_CHANNELS];
|
||||
extern float channelMax[RC_CHANNELS];
|
||||
|
||||
Preferences storage;
|
||||
|
||||
struct Parameter {
|
||||
const char *name;
|
||||
float *variable;
|
||||
float value; // cache
|
||||
};
|
||||
|
||||
Parameter parameters[] = {
|
||||
// control
|
||||
{"ROLLRATE_P", &rollRatePID.p},
|
||||
{"ROLLRATE_I", &rollRatePID.i},
|
||||
{"ROLLRATE_D", &rollRatePID.d},
|
||||
{"ROLLRATE_I_LIM", &rollRatePID.windup},
|
||||
{"PITCHRATE_P", &pitchRatePID.p},
|
||||
{"PITCHRATE_I", &pitchRatePID.i},
|
||||
{"PITCHRATE_D", &pitchRatePID.d},
|
||||
{"PITCHRATE_I_LIM", &pitchRatePID.windup},
|
||||
{"YAWRATE_P", &yawRatePID.p},
|
||||
{"YAWRATE_I", &yawRatePID.i},
|
||||
{"YAWRATE_D", &yawRatePID.d},
|
||||
{"ROLL_P", &rollPID.p},
|
||||
{"ROLL_I", &rollPID.i},
|
||||
{"ROLL_D", &rollPID.d},
|
||||
{"PITCH_P", &pitchPID.p},
|
||||
{"PITCH_I", &pitchPID.i},
|
||||
{"PITCH_D", &pitchPID.d},
|
||||
{"YAW_P", &yawPID.p},
|
||||
// imu
|
||||
{"ACC_BIAS_X", &accBias.x},
|
||||
{"ACC_BIAS_Y", &accBias.y},
|
||||
{"ACC_BIAS_Z", &accBias.z},
|
||||
{"ACC_SCALE_X", &accScale.x},
|
||||
{"ACC_SCALE_Y", &accScale.y},
|
||||
{"ACC_SCALE_Z", &accScale.z},
|
||||
// {"GYRO_BIAS_X", &gyroBias.x},
|
||||
// {"GYRO_BIAS_Y", &gyroBias.y},
|
||||
// {"GYRO_BIAS_Z", &gyroBias.z},
|
||||
// rc
|
||||
{"RC_NEUTRAL_0", &channelNeutral[0]},
|
||||
{"RC_NEUTRAL_1", &channelNeutral[1]},
|
||||
{"RC_NEUTRAL_2", &channelNeutral[2]},
|
||||
{"RC_NEUTRAL_3", &channelNeutral[3]},
|
||||
{"RC_NEUTRAL_4", &channelNeutral[4]},
|
||||
{"RC_NEUTRAL_5", &channelNeutral[5]},
|
||||
{"RC_NEUTRAL_6", &channelNeutral[6]},
|
||||
{"RC_NEUTRAL_7", &channelNeutral[7]},
|
||||
{"RC_MAX_0", &channelMax[0]},
|
||||
{"RC_MAX_1", &channelMax[1]},
|
||||
{"RC_MAX_2", &channelMax[2]},
|
||||
{"RC_MAX_3", &channelMax[3]},
|
||||
{"RC_MAX_4", &channelMax[4]},
|
||||
{"RC_MAX_5", &channelMax[5]},
|
||||
{"RC_MAX_6", &channelMax[6]},
|
||||
{"RC_MAX_7", &channelMax[7]}
|
||||
};
|
||||
|
||||
void setupParameters() {
|
||||
storage.begin("flix", false);
|
||||
// Read parameters from storage
|
||||
for (auto ¶meter : parameters) {
|
||||
if (!storage.isKey(parameter.name)) {
|
||||
Serial.printf("Define new parameter %s = %f\n", parameter.name, *parameter.variable);
|
||||
storage.putFloat(parameter.name, *parameter.variable);
|
||||
}
|
||||
*parameter.variable = storage.getFloat(parameter.name, *parameter.variable);
|
||||
parameter.value = *parameter.variable;
|
||||
}
|
||||
}
|
||||
|
||||
int parametersCount() {
|
||||
return sizeof(parameters) / sizeof(parameters[0]);
|
||||
}
|
||||
|
||||
const char *getParameterName(int index) {
|
||||
return parameters[index].name;
|
||||
}
|
||||
|
||||
float getParameter(int index) {
|
||||
return *parameters[index].variable;
|
||||
}
|
||||
|
||||
float getParameter(const char *name) {
|
||||
for (auto ¶meter : parameters) {
|
||||
if (strcmp(parameter.name, name) == 0) {
|
||||
return *parameter.variable;
|
||||
}
|
||||
}
|
||||
return NAN;
|
||||
}
|
||||
|
||||
bool setParameter(const char *name, const float value) {
|
||||
for (auto ¶meter : parameters) {
|
||||
if (strcmp(parameter.name, name) == 0) {
|
||||
*parameter.variable = value;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void flushParameters() {
|
||||
static float lastFlush = 0;
|
||||
if (t - lastFlush < 1) return; // flush once per second
|
||||
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
|
||||
lastFlush = t;
|
||||
|
||||
for (auto ¶meter : 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 ¶meter : parameters) {
|
||||
Serial.printf("%s = %g\n", parameter.name, *parameter.variable);
|
||||
}
|
||||
}
|
||||
|
||||
void resetParameters() {
|
||||
storage.clear();
|
||||
ESP.restart();
|
||||
}
|
||||
@@ -5,11 +5,10 @@
|
||||
|
||||
#include <SBUS.h>
|
||||
|
||||
// NOTE: use 'cr' command to calibrate the RC and put the values here
|
||||
int channelNeutral[] = {995, 883, 200, 972, 512, 512, 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};
|
||||
float channelNeutral[RC_CHANNELS] = {NAN}; // first element NAN means not calibrated
|
||||
float channelMax[RC_CHANNELS];
|
||||
|
||||
SBUS RC(Serial2, 16, 17); // NOTE: remove pin numbers (16, 17) if you use the new default pins for Serial2 (4, 25)
|
||||
SBUS RC(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
|
||||
|
||||
void setupRC() {
|
||||
Serial.println("Setup RC");
|
||||
@@ -21,10 +20,12 @@ void readRC() {
|
||||
SBUSData data = RC.data();
|
||||
memcpy(channels, data.ch, sizeof(channels)); // copy channels data
|
||||
normalizeRC();
|
||||
controlsTime = t;
|
||||
}
|
||||
}
|
||||
|
||||
void normalizeRC() {
|
||||
if (isnan(channelNeutral[0])) return; // skip if not calibrated
|
||||
for (uint8_t i = 0; i < RC_CHANNELS; i++) {
|
||||
controls[i] = mapf(channels[i], channelNeutral[i], channelMax[i], 0, 1);
|
||||
}
|
||||
|
||||
@@ -12,16 +12,16 @@ void step() {
|
||||
dt = 0; // assume dt to be zero on first step and on reset
|
||||
}
|
||||
|
||||
computeLoopFreq();
|
||||
computeLoopRate();
|
||||
}
|
||||
|
||||
void computeLoopFreq() {
|
||||
void computeLoopRate() {
|
||||
static float windowStart = 0;
|
||||
static uint32_t freq = 0;
|
||||
freq++;
|
||||
static uint32_t rate = 0;
|
||||
rate++;
|
||||
if (t - windowStart >= 1) { // 1 second window
|
||||
loopFreq = freq;
|
||||
loopRate = rate;
|
||||
windowStart = t;
|
||||
freq = 0;
|
||||
rate = 0;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -15,14 +15,6 @@ float mapff(float x, float in_min, float in_max, float out_min, float out_max) {
|
||||
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
}
|
||||
|
||||
int8_t sign(float x) {
|
||||
return (x > 0) - (x < 0);
|
||||
}
|
||||
|
||||
float randomFloat(float min, float max) {
|
||||
return min + (max - min) * (float)rand() / RAND_MAX;
|
||||
}
|
||||
|
||||
// Wrap angle to [-PI, PI)
|
||||
float wrapAngle(float angle) {
|
||||
angle = fmodf(angle, 2 * PI);
|
||||
|
||||
@@ -27,15 +27,27 @@ long map(long x, long in_min, long in_max, long out_min, long out_max) {
|
||||
return (delta * rise) / run + out_min;
|
||||
}
|
||||
|
||||
size_t strlcpy(char* dst, const char* src, size_t len) {
|
||||
size_t l = strlen(src);
|
||||
size_t i = 0;
|
||||
while (i < len - 1 && *src != '\0') { *dst++ = *src++; i++; }
|
||||
*dst = '\0';
|
||||
return l;
|
||||
}
|
||||
|
||||
class __FlashStringHelper;
|
||||
|
||||
// Arduino String partial implementation
|
||||
// https://www.arduino.cc/reference/en/language/variables/data-types/stringobject/
|
||||
class String: public std::string {
|
||||
public:
|
||||
String(const char *str = "") : std::string(str) {}
|
||||
long toInt() const { return atol(this->c_str()); }
|
||||
float toFloat() const { return atof(this->c_str()); }
|
||||
bool isEmpty() const { return this->empty(); }
|
||||
void toCharArray(char *buf, unsigned int bufsize, unsigned int index = 0) const {
|
||||
strlcpy(buf, this->c_str() + index, bufsize);
|
||||
}
|
||||
};
|
||||
|
||||
class Print;
|
||||
@@ -129,6 +141,11 @@ public:
|
||||
|
||||
HardwareSerial Serial, Serial2;
|
||||
|
||||
class EspClass {
|
||||
public:
|
||||
void restart() { Serial.println("Ignore reboot in simulation"); }
|
||||
} ESP;
|
||||
|
||||
void delay(uint32_t ms) {
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(ms));
|
||||
}
|
||||
|
||||
63
gazebo/Preferences.h
Normal file
@@ -0,0 +1,63 @@
|
||||
// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// Partial implementation of the ESP32 Preferences library for the simulation
|
||||
|
||||
#include <map>
|
||||
#include <fstream>
|
||||
#include "util.h"
|
||||
|
||||
class Preferences {
|
||||
private:
|
||||
std::map<std::string, float> storage;
|
||||
std::string storagePath;
|
||||
|
||||
void readFromFile() {
|
||||
std::ifstream file(storagePath);
|
||||
std::string key;
|
||||
float value;
|
||||
while (file >> key >> value) {
|
||||
storage[key] = value;
|
||||
}
|
||||
}
|
||||
|
||||
void writeToFile() {
|
||||
std::ofstream file(storagePath);
|
||||
for (auto &pair : storage) {
|
||||
file << pair.first << " " << pair.second << std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
public:
|
||||
bool begin(const char *name, bool readOnly = false, const char *partition_label = NULL) {
|
||||
storagePath = getPluginPath().parent_path() / (std::string(name) + ".txt");
|
||||
gzmsg << "Preferences initialized: " << storagePath << std::endl;
|
||||
readFromFile();
|
||||
return true;
|
||||
}
|
||||
|
||||
void end();
|
||||
|
||||
bool isKey(const char *key) {
|
||||
return storage.find(key) != storage.end();
|
||||
}
|
||||
|
||||
size_t putFloat(const char *key, float value) {
|
||||
storage[key] = value;
|
||||
writeToFile();
|
||||
return sizeof(value);
|
||||
}
|
||||
|
||||
float getFloat(const char *key, float defaultValue = NAN) {
|
||||
if (!isKey(key)) {
|
||||
return defaultValue;
|
||||
}
|
||||
return storage[key];
|
||||
}
|
||||
|
||||
bool clear() {
|
||||
storage.clear();
|
||||
writeToFile();
|
||||
return true;
|
||||
}
|
||||
};
|
||||
@@ -14,12 +14,10 @@ public:
|
||||
SBUS(HardwareSerial& bus, const bool inv = true) {};
|
||||
SBUS(HardwareSerial& bus, const int8_t rxpin, const int8_t txpin, const bool inv = true) {};
|
||||
void begin() {};
|
||||
bool read() { return joystickGet(); };
|
||||
bool read() { return joystickInitialized; };
|
||||
SBUSData data() {
|
||||
SBUSData data;
|
||||
for (uint8_t i = 0; i < 16; i++) {
|
||||
data.ch[i] = channels[i];
|
||||
}
|
||||
joystickGet(data.ch);
|
||||
return data;
|
||||
};
|
||||
};
|
||||
|
||||
@@ -19,22 +19,24 @@
|
||||
|
||||
#define WIFI_ENABLED 1
|
||||
|
||||
#define ONE_G 9.80665
|
||||
|
||||
float t = NAN;
|
||||
float dt;
|
||||
float loopFreq;
|
||||
float loopRate;
|
||||
float motors[4];
|
||||
int16_t channels[16]; // raw rc channels
|
||||
float controls[RC_CHANNELS];
|
||||
float controlsTime;
|
||||
Vector acc;
|
||||
Vector gyro;
|
||||
Vector rates;
|
||||
Quaternion attitude;
|
||||
|
||||
// declarations
|
||||
void computeLoopFreq();
|
||||
void computeLoopRate();
|
||||
void applyGyro();
|
||||
void applyAcc();
|
||||
void signalizeHorizontality();
|
||||
void control();
|
||||
void interpretRC();
|
||||
void controlAttitude();
|
||||
@@ -43,18 +45,23 @@ void controlTorque();
|
||||
void showTable();
|
||||
bool motorsActive();
|
||||
void cliTestMotor(uint8_t n);
|
||||
String stringToken(char* str, const char* delim);
|
||||
void normalizeRC();
|
||||
void printRCCal();
|
||||
void processMavlink();
|
||||
void sendMavlink();
|
||||
void sendMessage(const void *msg);
|
||||
void receiveMavlink();
|
||||
void handleMavlink(const void *_msg);
|
||||
void failsafe();
|
||||
void descend();
|
||||
inline Quaternion FLU2FRD(const Quaternion &q);
|
||||
|
||||
// mocks
|
||||
void setLED(bool on) {};
|
||||
void calibrateGyro() { printf("Skip gyro calibrating\n"); };
|
||||
void calibrateAccel() { printf("Skip accel calibrating\n"); };
|
||||
void fullMotorTest(int n) { printf("Skip full motor test\n"); };
|
||||
void sendMotors() {};
|
||||
void printIMUCal() { printf("cal: N/A\n"); };
|
||||
void printIMUInfo() {};
|
||||
Vector accBias, gyroBias, accScale(1, 1, 1);
|
||||
|
||||
@@ -7,10 +7,6 @@
|
||||
#include <gazebo/gazebo.hh>
|
||||
#include <iostream>
|
||||
|
||||
// simulation calibration overrides, NOTE: use `cr` command and replace with the actual values
|
||||
const int channelNeutralOverride[] = {-258, -258, -27349, 0, -27349, 0};
|
||||
const int channelMaxOverride[] = {27090, 27090, 27090, 27090, -5676, 1};
|
||||
|
||||
#define RC_CHANNEL_ROLL 0
|
||||
#define RC_CHANNEL_PITCH 1
|
||||
#define RC_CHANNEL_THROTTLE 2
|
||||
@@ -21,8 +17,6 @@ const int channelMaxOverride[] = {27090, 27090, 27090, 27090, -5676, 1};
|
||||
SDL_Joystick *joystick;
|
||||
bool joystickInitialized = false, warnShown = false;
|
||||
|
||||
void normalizeRC();
|
||||
|
||||
void joystickInit() {
|
||||
SDL_Init(SDL_INIT_JOYSTICK);
|
||||
joystick = SDL_JoystickOpen(0);
|
||||
@@ -33,15 +27,9 @@ void joystickInit() {
|
||||
gzwarn << "Joystick not found, begin waiting for joystick..." << std::endl;
|
||||
warnShown = true;
|
||||
}
|
||||
|
||||
// apply calibration overrides
|
||||
extern int channelNeutral[RC_CHANNELS];
|
||||
extern int channelMax[RC_CHANNELS];
|
||||
memcpy(channelNeutral, channelNeutralOverride, sizeof(channelNeutralOverride));
|
||||
memcpy(channelMax, channelMaxOverride, sizeof(channelMaxOverride));
|
||||
}
|
||||
|
||||
bool joystickGet() {
|
||||
bool joystickGet(int16_t ch[16]) {
|
||||
if (!joystickInitialized) {
|
||||
joystickInit();
|
||||
return false;
|
||||
@@ -49,8 +37,8 @@ bool joystickGet() {
|
||||
|
||||
SDL_JoystickUpdate();
|
||||
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
channels[i] = SDL_JoystickGetAxis(joystick, i);
|
||||
for (uint8_t i = 0; i < sizeof(channels) / sizeof(channels[0]); i++) {
|
||||
ch[i] = SDL_JoystickGetAxis(joystick, i);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
@@ -23,8 +23,10 @@
|
||||
#include "estimate.ino"
|
||||
#include "control.ino"
|
||||
#include "log.ino"
|
||||
#include "parameters.ino"
|
||||
#include "cli.ino"
|
||||
#include "mavlink.ino"
|
||||
#include "failsafe.ino"
|
||||
#include "lpf.h"
|
||||
|
||||
using ignition::math::Vector3d;
|
||||
@@ -50,6 +52,7 @@ public:
|
||||
this->resetConnection = event::Events::ConnectWorldReset(std::bind(&ModelFlix::OnReset, this));
|
||||
initNode();
|
||||
Serial.begin(0);
|
||||
setupParameters();
|
||||
gzmsg << "Flix plugin loaded" << endl;
|
||||
}
|
||||
|
||||
@@ -84,6 +87,7 @@ public:
|
||||
applyMotorForces();
|
||||
publishTopics();
|
||||
logData();
|
||||
flushParameters();
|
||||
}
|
||||
|
||||
void applyMotorForces() {
|
||||
|
||||
9
gazebo/util.h
Normal file
@@ -0,0 +1,9 @@
|
||||
#include <filesystem>
|
||||
|
||||
std::filesystem::path getPluginPath() {
|
||||
Dl_info dl_info;
|
||||
if (dladdr((void*)&getPluginPath, &dl_info) == 0) {
|
||||
throw std::runtime_error("Unable to determine plugin path using dladdr.");
|
||||
}
|
||||
return std::filesystem::path(dl_info.dli_fname);
|
||||
}
|
||||