Compare commits
1 Commits
af86699eb3
...
gyro-calib
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
073c860b90 |
53
.github/workflows/build.yml
vendored
@@ -5,7 +5,6 @@ on:
|
||||
branches: [ '*' ]
|
||||
pull_request:
|
||||
branches: [ master ]
|
||||
workflow_dispatch:
|
||||
|
||||
jobs:
|
||||
build_linux:
|
||||
@@ -15,16 +14,7 @@ jobs:
|
||||
- name: Install Arduino CLI
|
||||
run: curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=/usr/local/bin sh
|
||||
- name: Build firmware
|
||||
env:
|
||||
ARDUINO_SKETCH_ALWAYS_EXPORT_BINARIES: 1
|
||||
run: make
|
||||
- name: Upload binaries
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: firmware-binary
|
||||
path: flix/build
|
||||
- name: Build firmware without Wi-Fi
|
||||
run: sed -i 's/^#define WIFI_ENABLED 1$/#define WIFI_ENABLED 0/' flix/flix.ino && make
|
||||
- name: Check c_cpp_properties.json
|
||||
run: tools/check_c_cpp_properties.py
|
||||
|
||||
@@ -53,7 +43,7 @@ jobs:
|
||||
run: python3 tools/check_c_cpp_properties.py
|
||||
|
||||
build_simulator:
|
||||
runs-on: ubuntu-22.04
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- name: Install Arduino CLI
|
||||
uses: arduino/setup-arduino-cli@v1.1.1
|
||||
@@ -64,29 +54,28 @@ jobs:
|
||||
run: sudo apt-get install libsdl2-dev
|
||||
- name: Build simulator
|
||||
run: make build_simulator
|
||||
- uses: actions/upload-artifact@v4
|
||||
- uses: actions/upload-artifact@v3
|
||||
with:
|
||||
name: gazebo-plugin-binary
|
||||
path: gazebo/build/*.so
|
||||
retention-days: 1
|
||||
|
||||
build_simulator_macos:
|
||||
runs-on: macos-latest
|
||||
if: github.event_name == 'workflow_dispatch'
|
||||
steps:
|
||||
- name: Install Arduino CLI
|
||||
run: brew install arduino-cli
|
||||
- uses: actions/checkout@v4
|
||||
- name: Clean up python binaries # Workaround for https://github.com/actions/setup-python/issues/577
|
||||
run: |
|
||||
rm -f /usr/local/bin/2to3*
|
||||
rm -f /usr/local/bin/idle3*
|
||||
rm -f /usr/local/bin/pydoc3*
|
||||
rm -f /usr/local/bin/python3*
|
||||
rm -f /usr/local/bin/python3*-config
|
||||
- name: Install Gazebo
|
||||
run: brew update && brew tap osrf/simulation && brew install gazebo11
|
||||
- name: Install SDL2
|
||||
run: brew install sdl2
|
||||
- name: Build simulator
|
||||
run: make build_simulator
|
||||
# build_simulator_macos:
|
||||
# runs-on: macos-latest
|
||||
# steps:
|
||||
# - name: Install Arduino CLI
|
||||
# run: brew install arduino-cli
|
||||
# - uses: actions/checkout@v4
|
||||
# - name: Clean up python binaries # Workaround for https://github.com/actions/setup-python/issues/577
|
||||
# run: |
|
||||
# rm -f /usr/local/bin/2to3*
|
||||
# rm -f /usr/local/bin/idle3*
|
||||
# rm -f /usr/local/bin/pydoc3*
|
||||
# rm -f /usr/local/bin/python3*
|
||||
# rm -f /usr/local/bin/python3*-config
|
||||
# - name: Install Gazebo
|
||||
# run: brew update && brew tap osrf/simulation && brew install gazebo11
|
||||
# - name: Install SDL2
|
||||
# run: brew install sdl2
|
||||
# - name: Build simulator
|
||||
# run: make build_simulator
|
||||
|
||||
15
.github/workflows/tools.yml
vendored
@@ -19,21 +19,6 @@ jobs:
|
||||
echo -e "t,x,y,z\n0,1,2,3\n1,4,5,6" > log.csv
|
||||
./csv_to_ulog log.csv
|
||||
test $(stat -c %s log.ulg) -eq 196
|
||||
pyflix:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install Python build tools
|
||||
run: pip install build
|
||||
- name: Build pyflix
|
||||
run: python3 -m build tools
|
||||
- name: Upload artifacts
|
||||
uses: actions/upload-artifact@v4
|
||||
with:
|
||||
name: pyflix
|
||||
path: |
|
||||
tools/dist/pyflix-*.tar.gz
|
||||
tools/dist/pyflix-*.whl
|
||||
python_tools:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
|
||||
2
.gitignore
vendored
@@ -2,8 +2,6 @@
|
||||
*.elf
|
||||
build/
|
||||
tools/log/
|
||||
tools/dist/
|
||||
*.egg-info/
|
||||
.dependencies
|
||||
.vscode/*
|
||||
!.vscode/settings.json
|
||||
|
||||
@@ -34,7 +34,6 @@
|
||||
"MPU-6050",
|
||||
"MPU-9250",
|
||||
"GY-91",
|
||||
"GY-521",
|
||||
"ICM-20948",
|
||||
"Linux",
|
||||
"Windows",
|
||||
|
||||
53
.vscode/c_cpp_properties.json
vendored
@@ -5,18 +5,18 @@
|
||||
"includePath": [
|
||||
"${workspaceFolder}/flix",
|
||||
"${workspaceFolder}/gazebo",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
||||
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**",
|
||||
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
||||
"~/.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.2.0/cores/esp32/Arduino.h",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/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",
|
||||
@@ -28,10 +28,11 @@
|
||||
"${workspaceFolder}/flix/motors.ino",
|
||||
"${workspaceFolder}/flix/rc.ino",
|
||||
"${workspaceFolder}/flix/time.ino",
|
||||
"${workspaceFolder}/flix/util.ino",
|
||||
"${workspaceFolder}/flix/wifi.ino",
|
||||
"${workspaceFolder}/flix/parameters.ino"
|
||||
],
|
||||
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
|
||||
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2302/bin/xtensa-esp32-elf-g++",
|
||||
"cStandard": "c11",
|
||||
"cppStandard": "c++17",
|
||||
"defines": [
|
||||
@@ -51,19 +52,19 @@
|
||||
"name": "Mac",
|
||||
"includePath": [
|
||||
"${workspaceFolder}/flix",
|
||||
// "${workspaceFolder}/gazebo",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/include/**",
|
||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
||||
"${workspaceFolder}/gazebo",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32",
|
||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/include/**",
|
||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include",
|
||||
"~/Documents/Arduino/libraries/**",
|
||||
"/opt/homebrew/include/**"
|
||||
],
|
||||
"forcedInclude": [
|
||||
"${workspaceFolder}/.vscode/intellisense.h",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/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",
|
||||
@@ -75,10 +76,11 @@
|
||||
"${workspaceFolder}/flix/motors.ino",
|
||||
"${workspaceFolder}/flix/rc.ino",
|
||||
"${workspaceFolder}/flix/time.ino",
|
||||
"${workspaceFolder}/flix/util.ino",
|
||||
"${workspaceFolder}/flix/wifi.ino",
|
||||
"${workspaceFolder}/flix/parameters.ino"
|
||||
],
|
||||
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
|
||||
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2302/bin/xtensa-esp32-elf-g++",
|
||||
"cStandard": "c11",
|
||||
"cppStandard": "c++17",
|
||||
"defines": [
|
||||
@@ -100,17 +102,17 @@
|
||||
"includePath": [
|
||||
"${workspaceFolder}/flix",
|
||||
"${workspaceFolder}/gazebo",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/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.2.0/cores/esp32/Arduino.h",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/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",
|
||||
@@ -122,10 +124,11 @@
|
||||
"${workspaceFolder}/flix/motors.ino",
|
||||
"${workspaceFolder}/flix/rc.ino",
|
||||
"${workspaceFolder}/flix/time.ino",
|
||||
"${workspaceFolder}/flix/util.ino",
|
||||
"${workspaceFolder}/flix/wifi.ino",
|
||||
"${workspaceFolder}/flix/parameters.ino"
|
||||
],
|
||||
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++.exe",
|
||||
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2302/bin/xtensa-esp32-elf-g++.exe",
|
||||
"cStandard": "c11",
|
||||
"cppStandard": "c++17",
|
||||
"defines": [
|
||||
|
||||
1
.vscode/extensions.json
vendored
@@ -2,6 +2,7 @@
|
||||
// See https://go.microsoft.com/fwlink/?LinkId=827846 to learn about workspace recommendations.
|
||||
"recommendations": [
|
||||
"ms-vscode.cpptools",
|
||||
"twxs.cmake",
|
||||
"ms-vscode.cmake-tools",
|
||||
"ms-python.python"
|
||||
],
|
||||
|
||||
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.2.0 --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.16
|
||||
arduino-cli lib install "MAVLink"@2.0.12
|
||||
touch .dependencies
|
||||
|
||||
gazebo/build cmake: gazebo/CMakeLists.txt
|
||||
|
||||
93
README.md
@@ -4,87 +4,74 @@
|
||||
|
||||
<table>
|
||||
<tr>
|
||||
<td align=center><strong>Version 1.1</strong> (3D-printed frame)</td>
|
||||
<td align=center><strong>Version 1</strong> (3D-printed frame)</td>
|
||||
<td align=center><strong>Version 0</strong></td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td><img src="docs/img/flix1.1.jpg" width=500 alt="Flix quadcopter"></td>
|
||||
<td><img src="docs/img/flix1.jpg" width=500 alt="Flix quadcopter"></td>
|
||||
<td><img src="docs/img/flix.jpg" width=500 alt="Flix quadcopter"></td>
|
||||
</tr>
|
||||
</table>
|
||||
|
||||
## Features
|
||||
|
||||
* Dedicated for education and research.
|
||||
* Made from general-purpose components.
|
||||
* Simple and clean source code in Arduino.
|
||||
* Control using remote control or smartphone.
|
||||
* Precise simulation with Gazebo.
|
||||
* Wi-Fi and MAVLink support.
|
||||
* Wireless command line interface and analyzing.
|
||||
* Python library.
|
||||
* Textbook on flight control theory and practice ([in development](https://quadcopter.dev)).
|
||||
* *Position control (using external camera) and autonomous flights¹*.
|
||||
* Simple and clean Arduino based source code.
|
||||
* Acro and Stabilized flight using remote control.
|
||||
* Precise simulation using Gazebo.
|
||||
* [In-RAM logging](docs/log.md).
|
||||
* Command line interface through USB port.
|
||||
* Wi-Fi support.
|
||||
* MAVLink support.
|
||||
* Control using mobile phone (with QGroundControl app).
|
||||
* Completely 3D-printed frame.
|
||||
* Textbook for students on writing a flight controller ([in development](https://quadcopter.dev)).
|
||||
* *Position control and autonomous flights using external camera¹*.
|
||||
* [Building and running instructions](docs/build.md).
|
||||
|
||||
*¹ — planned.*
|
||||
|
||||
## It actually flies
|
||||
|
||||
See detailed demo video: https://youtu.be/hT46CZ1CgC4.
|
||||
|
||||
<a href="https://youtu.be/hT46CZ1CgC4"><img width=500 src="https://i3.ytimg.com/vi/hT46CZ1CgC4/maxresdefault.jpg"></a>
|
||||
|
||||
Version 0 demo video: https://youtu.be/8GzzIQ3C6DQ.
|
||||
See detailed demo video (for version 0): https://youtu.be/8GzzIQ3C6DQ.
|
||||
|
||||
<a href="https://youtu.be/8GzzIQ3C6DQ"><img width=500 src="https://i3.ytimg.com/vi/8GzzIQ3C6DQ/maxresdefault.jpg"></a>
|
||||
|
||||
See the [user builds gallery](docs/user.md).
|
||||
Version 1 test flight: https://t.me/opensourcequadcopter/42.
|
||||
|
||||
<a href="docs/user.md"><img src="docs/img/user/user.jpg" width=500></a>
|
||||
<a href="https://t.me/opensourcequadcopter/42"><img width=500 src="docs/img/flight-video.jpg"></a>
|
||||
|
||||
## Simulation
|
||||
|
||||
The simulator is implemented using Gazebo and runs the original Arduino code:
|
||||
|
||||
<img src="docs/img/simulator1.png" width=500 alt="Flix simulator">
|
||||
<img src="docs/img/simulator.png" width=500 alt="Flix simulator">
|
||||
|
||||
## Articles
|
||||
See [instructions on running the simulation](docs/build.md).
|
||||
|
||||
* [Assembly instructions](docs/assembly.md).
|
||||
* [Building and running the code](docs/build.md).
|
||||
* [Troubleshooting](docs/troubleshooting.md).
|
||||
* [Firmware architecture overview](docs/firmware.md).
|
||||
* [Python library tutorial](tools/pyflix/README.md).
|
||||
* [Log analysis](docs/log.md).
|
||||
* [User builds gallery](docs/user.md).
|
||||
|
||||
## Components
|
||||
## Components (version 1)
|
||||
|
||||
|Type|Part|Image|Quantity|
|
||||
|-|-|:-:|:-:|
|
||||
|Microcontroller board|ESP32 Mini|<img src="docs/img/esp32.jpg" width=100>|1|
|
||||
|IMU (and barometer²) board|GY‑91, MPU-9265 (or other MPU‑9250/MPU‑6500 board)<br>ICM‑20948³<br>GY-521 (MPU-6050)³⁻¹|<img src="docs/img/gy-91.jpg" width=90 align=center><br><img src="docs/img/icm-20948.jpg" width=100><br><img src="docs/img/gy-521.jpg" width=100>|1|
|
||||
|<span style="background:yellow">(Recommended) Buck-boost converter</span>|To be determined, output 5V or 3.3V, see [user-contributed schematics](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612179508274&cot=14)|<img src="docs/img/buck-boost.jpg" width=100>|1|
|
||||
|Motor|8520 3.7V brushed motor (shaft 0.8mm).<br>Motor with exact 3.7V voltage is needed, not ranged working voltage (3.7V — 6V).|<img src="docs/img/motor.jpeg" width=100>|4|
|
||||
|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 [analog](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4|
|
||||
|Pull-down resistor|10 kΩ|<img src="docs/img/resistor10k.jpg" width=100>|4|
|
||||
|3.7V Li-Po battery|LW 952540 (or any compatible by the size)|<img src="docs/img/battery.jpg" width=100>|1|
|
||||
|Battery connector cable|MX2.0 2P female|<img src="docs/img/mx.png" width=100>|1|
|
||||
|Li-Po Battery charger|Any|<img src="docs/img/charger.jpg" width=100>|1|
|
||||
|Screws for IMU board mounting|M3x5|<img src="docs/img/screw-m3.jpg" width=100>|2|
|
||||
|Screws for frame assembly|M1.4x5|<img src="docs/img/screw-m1.4.jpg" height=30 align=center>|4|
|
||||
|Frame main part|3D printed⁴:<br>[`flix-frame-1.1.stl`](docs/assets/flix-frame-1.1.stl) [`flix-frame-1.1.step`](docs/assets/flix-frame-1.1.step)<br>Recommended settings: layer 0.2 mm, line 0.4 mm, infill 100%.|<img src="docs/img/frame1.jpg" width=100>|1|
|
||||
|Frame 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>|2|
|
||||
|*RC transmitter (optional)*|*KINGKONG TINY X8 (warning: lacks USB support) or other⁵*|<img src="docs/img/tx.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>
|
||||
*³ — change `MPU9250` to `ICM20948` in `imu.ino` file if using ICM-20948 board.*<br>
|
||||
*³⁻¹ — MPU-6050 supports I²C interface only (not recommended). To use it change IMU declaration to `MPU6050 IMU(Wire)`.*<br>
|
||||
*⁴ — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*<br>
|
||||
*⁵ — you may use any transmitter-receiver pair with SBUS interface.*
|
||||
|
||||
@@ -98,7 +85,7 @@ Tools required for assembly:
|
||||
|
||||
Feel free to modify the design and or code, and create your own improved versions of Flix! Send your results to the [official Telegram chat](https://t.me/opensourcequadcopterchat), or directly to the author ([E-mail](mailto:okalachev@gmail.com), [Telegram](https://t.me/okalachev)).
|
||||
|
||||
## Schematics
|
||||
## Schematics (version 1)
|
||||
|
||||
### Simplified connection diagram
|
||||
|
||||
@@ -108,9 +95,7 @@ Motor connection scheme:
|
||||
|
||||
<img src="docs/img/mosfet-connection.png" height=400 alt="MOSFET connection scheme">
|
||||
|
||||
You can see a user-contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612338222067&cot=14) of the drone.
|
||||
|
||||
See [assembly guide](docs/assembly.md) for instructions on assembling the drone.
|
||||
Complete diagram is Work-in-Progress.
|
||||
|
||||
### Notes
|
||||
|
||||
@@ -131,10 +116,10 @@ See [assembly guide](docs/assembly.md) for instructions on assembling the drone.
|
||||
|
||||
|Motor|Position|Direction|Wires|GPIO|
|
||||
|-|-|-|-|-|
|
||||
|Motor 0|Rear left|Counter-clockwise|Black & White|GPIO12 (*TDI*)|
|
||||
|Motor 1|Rear right|Clockwise|Blue & Red|GPIO13 (*TCK*)|
|
||||
|Motor 2|Front right|Counter-clockwise|Black & White|GPIO14 (*TMS*)|
|
||||
|Motor 3|Front left|Clockwise|Blue & Red|GPIO15 (*TD0*)|
|
||||
|Motor 0|Rear left|Counter-clockwise|Black & White|GPIO12|
|
||||
|Motor 1|Rear right|Clockwise|Blue & Red|GPIO13|
|
||||
|Motor 2|Front right|Counter-clockwise|Black & White|GPIO14|
|
||||
|Motor 3|Front left|Clockwise|Blue & Red|GPIO15|
|
||||
|
||||
Counter-clockwise motors have black and white wires and clockwise motors have blue and red wires.
|
||||
|
||||
@@ -143,8 +128,8 @@ See [assembly guide](docs/assembly.md) for instructions on assembling the drone.
|
||||
|Receiver pin|ESP32 pin|
|
||||
|-|-|
|
||||
|GND|GND|
|
||||
|VIN|VCC (or 3.3V depending on the receiver)|
|
||||
|Signal (TX)|GPIO4⁶|
|
||||
|VIN|VC (or 3.3V depending on the receiver)|
|
||||
|Signal|GPIO4⁶|
|
||||
|
||||
*⁶ — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.*
|
||||
|
||||
@@ -158,6 +143,10 @@ In case of using other IMU orientation, modify the `rotateIMU` function in the `
|
||||
|
||||
See [FlixPeriph documentation](https://github.com/okalachev/flixperiph?tab=readme-ov-file#imu-axes-orientation) to learn axis orientation of other IMU boards.
|
||||
|
||||
## Version 0
|
||||
|
||||
See the information on the obsolete version 0 in the [corresponding article](docs/version0.md).
|
||||
|
||||
## Materials
|
||||
|
||||
Subscribe to the Telegram channel on developing the drone and the flight controller (in Russian): https://t.me/opensourcequadcopter.
|
||||
@@ -165,11 +154,3 @@ Subscribe to the Telegram channel on developing the drone and the flight control
|
||||
Join the official Telegram chat: https://t.me/opensourcequadcopterchat.
|
||||
|
||||
Detailed article on Habr.com about the development of the drone (in Russian): https://habr.com/ru/articles/814127/.
|
||||
|
||||
See the information on the obsolete version 0 in the [corresponding article](docs/version0.md).
|
||||
|
||||
## Disclaimer
|
||||
|
||||
This is a fun DIY project, and I hope you find it interesting and useful. However, it's not easy to assemble and set up, and it's provided "as is" without any warranties. There’s no guarantee that it will work perfectly — or even work at all.
|
||||
|
||||
⚠️ The author is not responsible for any damage, injury, or loss resulting from the use of this project. Use at your own risk!
|
||||
|
||||
@@ -1,5 +1,3 @@
|
||||
board_manager:
|
||||
additional_urls:
|
||||
- https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json
|
||||
network:
|
||||
connection_timeout: 1h
|
||||
|
||||
@@ -1,29 +0,0 @@
|
||||
# Brief assembly guide
|
||||
|
||||
Soldered components ([schematics variant](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612338222067&cot=14)):
|
||||
|
||||
<img src="img/assembly/1.jpg" width=600>
|
||||
|
||||
<br>Use double-sided tape to attach ESP32 to the top frame part (ESP32 holder):
|
||||
|
||||
<img src="img/assembly/2.jpg" width=600>
|
||||
|
||||
<br>Use two washers to screw the IMU board to the frame:
|
||||
|
||||
<img src="img/assembly/3.jpg" width=600>
|
||||
|
||||
<br>Screw the IMU with M3x5 screws as shown:
|
||||
|
||||
<img src="img/assembly/4.jpg" width=600>
|
||||
|
||||
<br>Install the motors, attach MOSFETs to the frame using tape:
|
||||
|
||||
<img src="img/assembly/5.jpg" width=600>
|
||||
|
||||
<br>Screw the ESP32 holder with M1.4x5 screws to the frame:
|
||||
|
||||
<img src="img/assembly/6.jpg" width=600>
|
||||
|
||||
<br>Assembled drone:
|
||||
|
||||
<img src="img/assembly/7.jpg" width=600>
|
||||
@@ -53,12 +53,6 @@ footer a.telegram, footer a.github {
|
||||
border: 1px solid #c9c9c9;
|
||||
}
|
||||
|
||||
@media (max-width: 600px) {
|
||||
.MathJax_Display {
|
||||
overflow-x: auto;
|
||||
}
|
||||
}
|
||||
|
||||
.firmware {
|
||||
position: relative;
|
||||
margin: 20px 0;
|
||||
|
||||
@@ -10,7 +10,7 @@ description = "Учебник по разработке полетного ко
|
||||
build-dir = "build"
|
||||
|
||||
[output.html]
|
||||
additional-css = ["book.css", "zoom.css", "rotation.css"]
|
||||
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
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
> [!IMPORTANT]
|
||||
> Flix — это проект по созданию открытого квадрокоптера на базе ESP32 с нуля и учебника по разработке полетных контроллеров.
|
||||
|
||||
<img src="img/flix1.1.jpg" class="border" width=500 alt="Flix quadcopter">
|
||||
<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>
|
||||
|
||||
|
||||
@@ -11,9 +11,8 @@
|
||||
* [Светодиод]()
|
||||
* [Моторы]()
|
||||
* [Радиоуправление]()
|
||||
* [Вектор, кватернион](geometry.md)
|
||||
* [Гироскоп](gyro.md)
|
||||
* [Акселерометр]()
|
||||
* [Акселерометр]()s
|
||||
* [Оценка состояния]()
|
||||
* [PID-регулятор]()
|
||||
* [Режим ACRO]()
|
||||
|
||||
@@ -10,8 +10,8 @@
|
||||
* `acc` *(Vector)* — данные с акселерометра, *м/с<sup>2</sup>*.
|
||||
* `rates` *(Vector)* — отфильтрованные угловые скорости, *рад/с*.
|
||||
* `attitude` *(Quaternion)* — оценка ориентации (положения) дрона.
|
||||
* `controlRoll`, `controlPitch`, ... *(float[])* — команды управления от пилота, в диапазоне [-1, 1].
|
||||
* `motors` *(float[])* — выходные сигналы на моторы, в диапазоне [0, 1].
|
||||
* `controls` *(float[])* — пользовательские управляющие сигналы с пульта, нормализованные в диапазоне [-1, 1].
|
||||
* `motors` *(float[])* — выходные сигналы на моторы, нормализованные в диапазоне [-1, 1] (возможно вращение в обратную сторону).
|
||||
|
||||
## Исходные файлы
|
||||
|
||||
|
||||
@@ -1,309 +0,0 @@
|
||||
# Вектор, кватернион
|
||||
|
||||
В алгоритме управления квадрокоптером широко применяются геометрические (и алгебраические) объекты, такие как **векторы** и **кватернионы**. Они позволяют упростить математические вычисления и улучшить читаемость кода. В этой главе мы рассмотрим именно те геометрические объекты, которые используются в алгоритме управления квадрокоптером Flix, причем акцент будет сделан на практических аспектах их использования.
|
||||
|
||||
## Система координат
|
||||
|
||||
### Оси координат
|
||||
|
||||
Для работы с объектами в трехмерном пространстве необходимо определить *систему координат*. Как известно, система координат задается тремя взаимно перпендикулярными осями, которые обозначаются как *X*, *Y* и *Z*. Порядок обозначения этих осей зависит от того, какую систему координат мы выбрали — *левую* или *правую*:
|
||||
|
||||
|Левая система координат|Правая система координат|
|
||||
|-----------------------|------------------------|
|
||||
|<img src="img/left-axes.svg" alt="Левая система координат" width="200">|<img src="img/right-axes.svg" alt="Правая система координат" width="200">|
|
||||
|
||||
В Flix для всех математических расчетов используется **правая система координат**, что является стандартом в робототехнике и авиации.
|
||||
|
||||
Также необходимо выбрать направление осей — в Flix они выбраны в соответствии со стандартом [REP-103](https://www.ros.org/reps/rep-0103.html). Для величин, заданных в подвижной системе координат, связанной с корпусом дрона, применяется порядок <abbr title="Forward Left Up">FLU</abbr>:
|
||||
|
||||
* ось X — направлена **вперед**;
|
||||
* ось Y — направлена **влево**;
|
||||
* ось Z — направлена **вверх**.
|
||||
|
||||
Для величин, заданных в *мировой* системе координат (относительно фиксированной точки в пространстве) — <abbr title="East North Up">ENU</abbr>:
|
||||
|
||||
* ось X — направлена на **восток** (условный);
|
||||
* ось Y — направлена на **север** (условный);
|
||||
* ось Z — направлена **вверх**.
|
||||
|
||||
> [!NOTE]
|
||||
> Для системы ENU важно только взаимное направление осей. Если доступен магнитометр, то используются реальные восток и север, но если нет — то произвольно выбранные.
|
||||
|
||||
Углы и угловые скорости определяются в соответствии с правилами математики: значения увеличиваются против часовой стрелки, если смотреть в сторону начала координат. Общий вид системы координат:
|
||||
|
||||
<img src="img/axes-rotation.svg" alt="Система координат" width="200">
|
||||
|
||||
> [!TIP]
|
||||
> Оси координат <i>X</i>, <i>Y</i> и <i>Z</i> часто обозначаются красными, зелеными и синими цветами соответственно. Запомнить это можно с помощью сокращения <abbr title="Red Green Blue">RGB</abbr>.
|
||||
|
||||
## Вектор
|
||||
|
||||
<div class="firmware">
|
||||
<strong>Файл прошивки:</strong>
|
||||
<a href="https://github.com/okalachev/flix/blob/master/flix/vector.h"><code>vector.h</code></a>.<br>
|
||||
</div>
|
||||
|
||||
**Вектор** — простой геометрический объект, который содержит три значения, соответствующие координатам *X*, *Y* и *Z*. Эти значения называются *компонентами вектора*. Вектор может описывать точку в пространстве, направление или ось вращения, скорость, ускорение, угловые скорости и другие физические величины. В Flix векторы задаются объектами `Vector` из библиотеки `vector.h`:
|
||||
|
||||
```cpp
|
||||
Vector v(1, 2, 3);
|
||||
v.x = 5;
|
||||
v.y = 10;
|
||||
v.z = 15;
|
||||
```
|
||||
|
||||
> [!TIP]
|
||||
> Не следует путать геометрический вектор — <code>vector</code> и динамический массив в стандартной библиотеке C++ — <code>std::vector</code>.
|
||||
|
||||
В прошивке в виде векторов представлены, например:
|
||||
|
||||
* `acc` собственное ускорение с акселерометра.
|
||||
* `gyro` — угловые скорости с гироскопа.
|
||||
* `rates` — рассчитанная угловая скорость дрона.
|
||||
* `accBias`, `accScale`, `gyroBias` — параметры калибровки IMU.
|
||||
|
||||
### Операции с векторами
|
||||
|
||||
**Длина вектора** рассчитывается при помощи теоремы Пифагора; в прошивке используется метод `norm()`:
|
||||
|
||||
```cpp
|
||||
Vector v(3, 4, 5);
|
||||
float length = v.norm(); // 7.071
|
||||
```
|
||||
|
||||
Любой вектор можно привести к **единичному вектору** (сохранить направление, но сделать длину равной 1) при помощи метода `normalize()`:
|
||||
|
||||
```cpp
|
||||
Vector v(3, 4, 5);
|
||||
v.normalize(); // 0.424, 0.566, 0.707
|
||||
```
|
||||
|
||||
**Сложение и вычитание** векторов реализуется через простое покомпонентное сложение и вычитание. Геометрически сумма векторов представляет собой вектор, который соединяет начало первого вектора с концом второго. Разность векторов представляет собой вектор, который соединяет конец первого вектора с концом второго. Это удобно для расчета относительных позиций, суммарных скоростей и решения других задач. В коде эти операции интуитивно понятны:
|
||||
|
||||
```cpp
|
||||
Vector a(1, 2, 3);
|
||||
Vector b(4, 5, 6);
|
||||
Vector sum = a + b; // 5, 7, 9
|
||||
Vector diff = a - b; // -3, -3, -3
|
||||
```
|
||||
|
||||
Операция **умножения на число** `n` увеличивает (или уменьшает) длину вектора в `n` раз (сохраняя направление):
|
||||
|
||||
```cpp
|
||||
Vector a(1, 2, 3);
|
||||
Vector b = a * 2; // 2, 4, 6
|
||||
```
|
||||
|
||||
В некоторых случаях полезна операция **покомпонентного умножения** (или деления) векторов. Например, для применения коэффициентов калибровки к данным с IMU. В разных библиотеках эта операция обозначается по разному, но в библиотеке `vector.h` используется простые знаки `*` и `/`:
|
||||
|
||||
```cpp
|
||||
acc = acc / accScale;
|
||||
```
|
||||
|
||||
**Угол между векторами** можно найти при помощи статического метода `Vector::angleBetween()`:
|
||||
|
||||
```cpp
|
||||
Vector a(1, 0, 0);
|
||||
Vector b(0, 1, 0);
|
||||
float angle = Vector::angleBetween(a, b); // 1.57 (90 градусов)
|
||||
```
|
||||
|
||||
#### Скалярное произведение
|
||||
|
||||
Скалярное произведение векторов (*dot product*) — это произведение длин двух векторов на косинус угла между ними. В математике оно обозначается знаком `·` или слитным написанием векторов. Интуитивно, результат скалярного произведения показывает, насколько два вектора *сонаправлены*.
|
||||
|
||||
В Flix используется статический метод `Vector::dot()`:
|
||||
|
||||
```cpp
|
||||
Vector a(1, 2, 3);
|
||||
Vector b(4, 5, 6);
|
||||
float dotProduct = Vector::dot(a, b); // 32
|
||||
```
|
||||
|
||||
Операция скалярного произведения может помочь, например, при расчете проекции одного вектора на другой.
|
||||
|
||||
#### Векторное произведение
|
||||
|
||||
Векторное произведение (*cross product*) позволяет найти вектор, перпендикулярный двум другим векторам. В математике оно обозначается знаком `×`, а в прошивке используется статический метод `Vector::cross()`:
|
||||
|
||||
```cpp
|
||||
Vector a(1, 2, 3);
|
||||
Vector b(4, 5, 6);
|
||||
Vector crossProduct = Vector::cross(a, b); // -3, 6, -3
|
||||
```
|
||||
|
||||
## Кватернион
|
||||
|
||||
### Ориентация в трехмерном пространстве
|
||||
|
||||
В отличие от позиции и скорости, у ориентации в трехмерном пространстве нет универсального для всех случаев способа представления. В зависимости от задачи ориентация может быть представлена в виде *углов Эйлера*, *матрицы поворота*, *вектора вращения* или *кватерниона*. Рассмотрим используемые в полетной прошивке способы представления ориентации.
|
||||
|
||||
### Углы Эйлера
|
||||
|
||||
**Углы Эйлера** — *крен*, *тангаж* и *рыскание* — это наиболее «естественный» для человека способ представления ориентации. Они описывают последовательные вращения объекта вокруг трех осей координат.
|
||||
|
||||
В прошивке углы Эйлера сохраняются в обычный объект `Vector` (хоть и, строго говоря, не являются вектором):
|
||||
|
||||
* Угол по крену (*roll*) — `vector.x`.
|
||||
* Угол по тангажу (*pitch*) — `vector.y`.
|
||||
* Угол по рысканию (*yaw*) — `vector.z`.
|
||||
|
||||
Особенности углов Эйлера:
|
||||
|
||||
1. Углы Эйлера зависят от порядка применения вращений, то есть существует 6 типов углов Эйлера. Порядок вращений, принятый в Flix (и в роботехнике в целом) — рыскание, тангаж, крен (ZYX).
|
||||
2. Для некоторых ориентаций углы Эйлера «вырождаются». Так, если объект «смотрит» строго вниз, то угол по рысканию и угол по крену становятся неразличимыми. Эта ситуация называется *gimbal lock* — потеря одной степени свободы.
|
||||
|
||||
Ввиду этих особенности для углов Эйлера не существует общих формул для самых базовых задач с ориентациями, таких как применение одного вращения (ориентации) к другому, расчет разницы между ориентациями и подобных. Поэтому в основном углы Эйлера применяются в пользовательском интерфейсе, но редко используются в математических расчетах.
|
||||
|
||||
> [!IMPORTANT]
|
||||
> Для углов Эйлера не существует общих формул для самых базовых операций с ориентациями.
|
||||
|
||||
### Axis-angle
|
||||
|
||||
Помимо углов Эйлера, любую ориентацию в трехмерном пространстве можно представить в виде вращения вокруг некоторой оси на некоторый угол. В геометрии это доказывается, как **теорема вращения Эйлера**. В таком представлении ориентация задается двумя величинами:
|
||||
|
||||
* **Ось вращения** (*axis*) — единичный вектор, определяющий ось вращения.
|
||||
* **Угол поворота** (*angle* или *θ*) — угол, на который нужно повернуть объект вокруг этой оси.
|
||||
|
||||
В Flix ось вращения задается объектом `Vector`, а угол поворота — числом типа `float` в радианах:
|
||||
|
||||
```cpp
|
||||
// Вращение на 45 градусов вокруг оси (1, 2, 3)
|
||||
Vector axis(1, 2, 3);
|
||||
float angle = radians(45);
|
||||
```
|
||||
|
||||
Этот способ более удобен для расчетов, чем углы Эйлера, но все еще не является оптимальным.
|
||||
|
||||
### Вектор вращения
|
||||
|
||||
Если умножить вектор *axis* на угол поворота *θ*, то получится **вектор вращения** (*rotation vector*). Этот вектор играет важную роль в алгоритмах управления ориентацией летательного аппарата.
|
||||
|
||||
Вектор вращения обладает замечательным свойством: если угловые скорости объекта (в собственной системе координат) в каждый момент времени совпадают с компонентами этого вектора, то за единичное время объект придет к заданной этим вектором ориентации. Это свойство позволяет использовать вектор вращения для управления ориентацией объекта посредством управления угловыми скоростями.
|
||||
|
||||
> [!IMPORTANT]
|
||||
> Чтобы за единичное время прийти к заданной ориентации, собственные угловые скорости объекта должны быть равны компонентам вектора вращения.
|
||||
|
||||
Вектора вращения в Flix представляются в виде объектов `Vector`:
|
||||
|
||||
```cpp
|
||||
// Вращение на 45 градусов вокруг оси (1, 2, 3)
|
||||
Vector rotation = radians(45) * Vector(1, 2, 3);
|
||||
```
|
||||
|
||||
### Кватернион
|
||||
|
||||
<div class="firmware">
|
||||
<strong>Файл прошивки:</strong>
|
||||
<a href="https://github.com/okalachev/flix/blob/master/flix/quaternion.h"><code>quaternion.h</code></a>.<br>
|
||||
</div>
|
||||
|
||||
Вектор вращения удобен, но еще удобнее использовать **кватернион**. В Flix кватернионы задаются объектами `Quaternion` из библиотеки `quaternion.h`. Кватернион состоит из четырех значений: *w*, *x*, *y*, *z* и рассчитывается из вектора оси вращения (*axis*) и угла поворота (*θ*) по формуле:
|
||||
|
||||
\\[ q = \left( \begin{array}{c} w \\\\ x \\\\ y \\\\ z \end{array} \right) = \left( \begin{array}{c} \cos\left(\frac{\theta}{2}\right) \\\\ axis\_x \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_y \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_z \cdot \sin\left(\frac{\theta}{2}\right) \end{array} \right) \\]
|
||||
|
||||
На практике оказывается, что **именно такое представление наиболее удобно для математических расчетов**.
|
||||
|
||||
Проиллюстрируем кватернион и описанные выше способы представления ориентации на интерактивной визуализации. Изменяйте угол поворота *θ* с помощью ползунка (ось вращения константна) и изучите, как меняется ориентация объекта, вектор вращения и кватернион:
|
||||
|
||||
<div id="rotation-diagram" class="diagram">
|
||||
<p>
|
||||
<label class="angle" for="angle-range"></label>
|
||||
<input type="range" name="angle" id="angle-range" min="0" max="360" value="0" step="1">
|
||||
</p>
|
||||
<p class="axis"></p>
|
||||
<p class="rotation-vector"></p>
|
||||
<p class="quaternion"></p>
|
||||
<p class="euler"></p>
|
||||
</div>
|
||||
|
||||
<script type="importmap">
|
||||
{
|
||||
"imports": {
|
||||
"three": "https://cdn.jsdelivr.net/npm/three@0.176.0/build/three.module.js",
|
||||
"three/addons/": "https://cdn.jsdelivr.net/npm/three@0.176.0/examples/jsm/"
|
||||
}
|
||||
}
|
||||
</script>
|
||||
<script type="module" src="js/rotation.js"></script>
|
||||
|
||||
> [!IMPORTANT]
|
||||
> В контексте управляющих алгоритмов кватернион — это оптимизированный для расчетов аналог вектора вращения.
|
||||
|
||||
Кватернион это наиболее часто используемый способ представления ориентации в алгоритмах. Кроме этого, у кватерниона есть большое значение в теории чисел и алгебре, как у расширения понятия комплексного числа, но рассмотрение этого аспекта выходит за рамки описания работы с вращениями с практической точки зрения.
|
||||
|
||||
В прошивке в виде кватернионов представлены, например:
|
||||
|
||||
* `attitude` — текущая ориентация квадрокоптера.
|
||||
* `attitudeTarget` — целевая ориентация квадрокоптера.
|
||||
|
||||
### Операции с кватернионами
|
||||
|
||||
Кватернион создается напрямую из четырех его компонент:
|
||||
|
||||
```cpp
|
||||
// Кватернион, представляющий нулевую (исходную) ориентацию
|
||||
Quaternion q(1, 0, 0, 0);
|
||||
```
|
||||
|
||||
Кватернион можно создать из оси вращения и угла поворота, вектора вращения или углов Эйлера:
|
||||
|
||||
```cpp
|
||||
Quaternion q1 = Quaternion::fromAxisAngle(axis, angle);
|
||||
Quaternion q2 = Quaternion::fromRotationVector(rotation);
|
||||
Quaternion q3 = Quaternion::fromEuler(Vector(roll, pitch, yaw));
|
||||
```
|
||||
|
||||
И наоборот:
|
||||
|
||||
```cpp
|
||||
q1.toAxisAngle(axis, angle);
|
||||
Vector rotation = q2.toRotationVector();
|
||||
Vector euler = q3.toEuler();
|
||||
```
|
||||
|
||||
Возможно рассчитать вращение между двумя обычными векторами:
|
||||
|
||||
```cpp
|
||||
Quaternion q = Quaternion::fromBetweenVectors(v1, v2); // в виде кватерниона
|
||||
Vector rotation = Vector::rotationVectorBetween(v1, v2); // в виде вектора вращения
|
||||
```
|
||||
|
||||
Шорткаты для работы с углом Эйлера по рысканью (удобно для алгоритмов управления полетом):
|
||||
|
||||
```cpp
|
||||
float yaw = q.getYaw();
|
||||
q.setYaw(yaw);
|
||||
```
|
||||
|
||||
#### Применения вращений
|
||||
|
||||
Чтобы применить вращение, выраженное в кватернионе, к другому кватерниону, в математике используется операция **умножения кватернионов**. При использовании этой операции, необходимо учитывать, что она не является коммутативной, то есть порядок операндов имеет значение. Формула умножения кватернионов выглядит так:
|
||||
|
||||
\\[ q_1 \times q_2 = \left( \begin{array}{c} w_1 \\\\ x_1 \\\\ y_1 \\\\ z_1 \end{array} \right) \times \left( \begin{array}{c} w_2 \\\\ x_2 \\\\ y_2 \\\\ z_2 \end{array} \right) = \left( \begin{array}{c} w_1 w_2 - x_1 x_2 - y_1 y_2 - z_1 z_2 \\\\ w_1 x_2 + x_1 w_2 + y_1 z_2 - z_1 y_2 \\\\ w_1 y_2 - x_1 z_2 + y_1 w_2 + z_1 x_2 \\\\ w_1 z_2 + x_1 y_2 - y_1 x_2 + z_1 w_2 \end{array} \right) \\]
|
||||
|
||||
В библиотеке `quaternion.h` для этой операции используется статический метод `Quaternion::rotate()`:
|
||||
|
||||
```cpp
|
||||
// Композиция вращений q1 и q2
|
||||
Quaternion result = Quaternion::rotate(q1, q2);
|
||||
```
|
||||
|
||||
Также полезной является операция применения вращения к вектору, которая делается похожим образом:
|
||||
|
||||
```cpp
|
||||
// Вращение вектора v кватернионом q
|
||||
Vector result = Quaternion::rotateVector(v, q);
|
||||
```
|
||||
|
||||
Для расчета разницы между двумя ориентациями используется метод `Quaternion::between()`:
|
||||
|
||||
```cpp
|
||||
// Расчет вращения от q1 к q2
|
||||
Quaternion q = Quaternion::between(q1, q2);
|
||||
```
|
||||
|
||||
## Дополнительные материалы
|
||||
|
||||
* [Интерактивный учебник по кватернионам](https://eater.net/quaternions).
|
||||
* [Визуализация вращения вектора с помощью кватернионов](https://quaternions.online).
|
||||
@@ -1,7 +1,7 @@
|
||||
# Гироскоп
|
||||
|
||||
<div class="firmware">
|
||||
<strong>Файл прошивки:</strong>
|
||||
<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>
|
||||
@@ -100,7 +100,7 @@ void setup() {
|
||||
|
||||
Для однократного считывания данных используется метод `read()`. Затем данные с гироскопа получаются при помощи метода `getGyro(x, y, z)`. Этот метод записывает в переменные `x`, `y` и `z` угловые скорости вокруг соответствующих осей в радианах в секунду.
|
||||
|
||||
Если нужно гарантировать, что будут считаны новые данные, можно использовать метод `waitForData()`. Этот метод блокирует выполнение программы до тех пор, пока в IMU не появятся новые данные. Метод `waitForData()` позволяет привязать частоту главного цикла `loop` к частоте обновления данных IMU. Это удобно для организации главного цикла управления квадрокоптером.
|
||||
Если нужно гарантировать, что будут считаны новые данные, можно использовать метод `waitForData()`. Этот метод блокирует выполнение программы до тех пор, пока в IMU не появятся новые данные. Метод `waitForData()` позволяет привязать частоту главного цикла `loop` к частоте обновления данных IMU. Это удобно для организации главного цикла управления квадрокоптером.
|
||||
|
||||
Программа для чтения данных с гироскопа и вывода их в консоль для построения графиков в Serial Plotter выглядит так:
|
||||
|
||||
@@ -139,7 +139,7 @@ void loop() {
|
||||
|
||||
### Частота сэмплов
|
||||
|
||||
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер.
|
||||
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер. В Flix используется частота сэмплов 1 кГц.
|
||||
|
||||
Частота сэмплов устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
|
||||
|
||||
@@ -153,7 +153,7 @@ IMU.setRate(IMU.RATE_1KHZ_APPROX);
|
||||
|
||||
* `RATE_MIN` — минимальная частота сэмплов для конкретного IMU.
|
||||
* `RATE_50HZ_APPROX` — значение, близкое к 50 Гц.
|
||||
* `RATE_1KHZ_APPROX` — значение, близкое к 1 кГц.
|
||||
* `RATE_1KHZ_APPROX` — значение, близкое к 1 кГц.
|
||||
* `RATE_8KHZ_APPROX` — значение, близкое к 8 кГц.
|
||||
* `RATE_MAX` — максимальная частота сэмплов для конкретного IMU.
|
||||
|
||||
|
||||
@@ -1,262 +0,0 @@
|
||||
import * as THREE from 'three';
|
||||
import { SVGRenderer, SVGObject } from 'three/addons/renderers/SVGRenderer.js';
|
||||
import { OrbitControls } from 'three/addons/controls/OrbitControls.js';
|
||||
|
||||
const diagramEl = document.getElementById('rotation-diagram');
|
||||
|
||||
const scene = new THREE.Scene();
|
||||
scene.background = new THREE.Color(0xffffff);
|
||||
|
||||
const camera = new THREE.OrthographicCamera();
|
||||
|
||||
camera.position.set(9, 26, 20);
|
||||
camera.up.set(0, 0, 1);
|
||||
camera.lookAt(0, 0, 0);
|
||||
|
||||
const renderer = new SVGRenderer();
|
||||
diagramEl.prepend(renderer.domElement);
|
||||
|
||||
const controls = new OrbitControls(camera, renderer.domElement);
|
||||
controls.enableZoom = false;
|
||||
|
||||
const LINE_WIDTH = 4;
|
||||
|
||||
function createLabel(text, x, y, z, min = false) {
|
||||
const label = document.createElementNS('http://www.w3.org/2000/svg', 'text');
|
||||
label.setAttribute('class', 'label' + (min ? ' min' : ''));
|
||||
label.textContent = text;
|
||||
label.setAttribute('y', -15);
|
||||
const object = new SVGObject(label);
|
||||
object.position.x = x;
|
||||
object.position.y = y;
|
||||
object.position.z = z;
|
||||
return object;
|
||||
}
|
||||
|
||||
function createLine(x1, y1, z1, x2, y2, z2, color) {
|
||||
const geometry = new THREE.BufferGeometry().setFromPoints([
|
||||
new THREE.Vector3(x1, y1, z1),
|
||||
new THREE.Vector3(x2, y2, z2)
|
||||
]);
|
||||
const material = new THREE.LineBasicMaterial({ color: color, linewidth: LINE_WIDTH, transparent: true, opacity: 0.8 });
|
||||
const line = new THREE.Line(geometry, material);
|
||||
scene.add(line);
|
||||
return line;
|
||||
}
|
||||
|
||||
function changeLine(line, x1, y1, z1, x2, y2, z2) {
|
||||
line.geometry.setFromPoints([new THREE.Vector3(x1, y1, z1), new THREE.Vector3(x2, y2, z2)]);
|
||||
return line;
|
||||
}
|
||||
|
||||
function createVector(x1, y1, z1, x2, y2, z2, color, label = '') {
|
||||
const HEAD_LENGTH = 1;
|
||||
const HEAD_WIDTH = 0.2;
|
||||
|
||||
const group = new THREE.Group();
|
||||
const direction = new THREE.Vector3(x2 - x1, y2 - y1, z2 - z1).normalize();
|
||||
const norm = new THREE.Vector3(x2 - x1, y2 - y1, z2 - z1).length();
|
||||
let end = new THREE.Vector3(x2, y2, z2);
|
||||
|
||||
if (norm > HEAD_LENGTH) {
|
||||
end = new THREE.Vector3(x2 - direction.x * HEAD_LENGTH / 2, y2 - direction.y * HEAD_LENGTH / 2, z2 - direction.z * HEAD_LENGTH / 2);
|
||||
}
|
||||
|
||||
// create line
|
||||
const geometry = new THREE.BufferGeometry().setFromPoints([new THREE.Vector3(x1, y1, z1), end]);
|
||||
const material = new THREE.LineBasicMaterial({ color: color, linewidth: LINE_WIDTH, transparent: true, opacity: 0.8 });
|
||||
const line = new THREE.Line(geometry, material);
|
||||
group.add(line);
|
||||
|
||||
if (norm > HEAD_LENGTH) {
|
||||
// Create arrow
|
||||
const arrowGeometry = new THREE.ConeGeometry(HEAD_WIDTH, HEAD_LENGTH, 16);
|
||||
const arrowMaterial = new THREE.MeshBasicMaterial({ color: color });
|
||||
const arrow = new THREE.Mesh(arrowGeometry, arrowMaterial);
|
||||
arrow.position.set(x2 - direction.x * HEAD_LENGTH / 2, y2 - direction.y * HEAD_LENGTH / 2, z2 - direction.z * HEAD_LENGTH / 2);
|
||||
arrow.lookAt(new THREE.Vector3(x1, y1, z1));
|
||||
arrow.rotateX(-Math.PI / 2);
|
||||
group.add(arrow);
|
||||
}
|
||||
|
||||
// create label
|
||||
if (label) group.add(createLabel(label, x2, y2, z2));
|
||||
scene.add(group);
|
||||
return group;
|
||||
}
|
||||
|
||||
function changeVector(vector, x1, y1, z1, x2, y2, z2, color, label = '') {
|
||||
vector.removeFromParent();
|
||||
return createVector(x1, y1, z1, x2, y2, z2, color, label);
|
||||
}
|
||||
|
||||
function createDrone(x, y, z) {
|
||||
const group = new THREE.Group();
|
||||
|
||||
// Fuselage and wing triangle (main body)
|
||||
const fuselageGeometry = new THREE.BufferGeometry();
|
||||
const fuselageVertices = new Float32Array([
|
||||
1, 0, 0,
|
||||
-1, 0.6, 0,
|
||||
-1, -0.6, 0
|
||||
]);
|
||||
fuselageGeometry.setAttribute('position', new THREE.BufferAttribute(fuselageVertices, 3));
|
||||
const fuselageMaterial = new THREE.MeshBasicMaterial({ color: 0xb3b3b3, side: THREE.DoubleSide, transparent: true, opacity: 0.8 });
|
||||
const fuselage = new THREE.Mesh(fuselageGeometry, fuselageMaterial);
|
||||
group.add(fuselage);
|
||||
|
||||
// Tail triangle
|
||||
const tailGeometry = new THREE.BufferGeometry();
|
||||
const tailVertices = new Float32Array([
|
||||
-0.2, 0, 0,
|
||||
-1, 0, 0,
|
||||
-1, 0, 0.5,
|
||||
]);
|
||||
tailGeometry.setAttribute('position', new THREE.BufferAttribute(tailVertices, 3));
|
||||
const tailMaterial = new THREE.MeshBasicMaterial({ color: 0xd80100, side: THREE.DoubleSide, transparent: true, opacity: 0.9 });
|
||||
const tail = new THREE.Mesh(tailGeometry, tailMaterial);
|
||||
group.add(tail);
|
||||
|
||||
group.position.set(x, y, z);
|
||||
group.scale.set(2, 2, 2);
|
||||
scene.add(group);
|
||||
return group;
|
||||
}
|
||||
|
||||
// Create axes
|
||||
const AXES_LENGTH = 10;
|
||||
createVector(0, 0, 0, AXES_LENGTH, 0, 0, 0xd80100, 'x');
|
||||
createVector(0, 0, 0, 0, AXES_LENGTH, 0, 0x0076ba, 'y');
|
||||
createVector(0, 0, 0, 0, 0, AXES_LENGTH, 0x57ed00, 'z');
|
||||
|
||||
// Rotation values
|
||||
const rotationAxisSrc = new THREE.Vector3(2, 1, 3);
|
||||
let rotationAngle = 0;
|
||||
let rotationAxis = rotationAxisSrc.clone().normalize();
|
||||
let rotationVector = new THREE.Vector3(rotationAxis.x * rotationAngle, rotationAxis.y * rotationAngle, rotationAxis.z * rotationAngle);
|
||||
|
||||
let rotationVectorObj = createVector(0, 0, 0, rotationVector.x, rotationVector.y, rotationVector.z, 0xff9900);
|
||||
let axisObj = createLine(0, 0, 0, rotationAxis.x * AXES_LENGTH, rotationAxis.y * AXES_LENGTH, rotationAxis.z * AXES_LENGTH, 0xe8e8e8);
|
||||
|
||||
const drone = createDrone(0, 0, 0);
|
||||
|
||||
// UI
|
||||
const angleInput = diagramEl.querySelector('input[name=angle]');
|
||||
const rotationVectorEl = diagramEl.querySelector('.rotation-vector');
|
||||
const angleEl = diagramEl.querySelector('.angle');
|
||||
const quaternionEl = diagramEl.querySelector('.quaternion');
|
||||
const eulerEl = diagramEl.querySelector('.euler');
|
||||
diagramEl.querySelector('.axis').innerHTML = `<b style='color:#b6b6b6'>Ось вращения:</b> (${rotationAxisSrc.x}, ${rotationAxisSrc.y}, ${rotationAxisSrc.z}) ∥ (${rotationAxis.x.toFixed(1)}, ${rotationAxis.y.toFixed(1)}, ${rotationAxis.z.toFixed(1)})`;
|
||||
|
||||
function updateScene() {
|
||||
rotationAngle = parseFloat(angleInput.value) * Math.PI / 180;
|
||||
rotationVector.set(rotationAxis.x * rotationAngle, rotationAxis.y * rotationAngle, rotationAxis.z * rotationAngle);
|
||||
rotationVectorObj = changeVector(rotationVectorObj, 0, 0, 0, rotationVector.x, rotationVector.y, rotationVector.z, 0xff9900);
|
||||
|
||||
// rotate drone
|
||||
drone.rotation.set(0, 0, 0);
|
||||
drone.rotateOnAxis(rotationAxis, rotationAngle);
|
||||
|
||||
// update labels
|
||||
angleEl.innerHTML = `<b>Угол вращения:</b> ${parseFloat(angleInput.value).toFixed(0)}° = ${(rotationAngle).toFixed(2)} рад`;
|
||||
rotationVectorEl.innerHTML = `<b style='color:#e49a44'>Вектор вращения:</b> (${rotationVector.x.toFixed(1)}, ${rotationVector.y.toFixed(1)}, ${rotationVector.z.toFixed(1)}) рад`;
|
||||
|
||||
let quaternion = new THREE.Quaternion();
|
||||
quaternion.setFromAxisAngle(rotationAxis, rotationAngle);
|
||||
|
||||
quaternionEl.innerHTML = `<b>Кватернион:</b>
|
||||
<math xmlns="http://www.w3.org/1998/Math/MathML">
|
||||
<mrow>
|
||||
<mo>(</mo>
|
||||
<mrow>
|
||||
<mi>cos</mi>
|
||||
<mo>(</mo>
|
||||
<mfrac>
|
||||
<mi>${rotationAngle.toFixed(2)}</mi>
|
||||
<mn>2</mn>
|
||||
</mfrac>
|
||||
<mo>)</mo>
|
||||
</mrow>
|
||||
<mo>, </mo>
|
||||
<mrow>
|
||||
<mi>${rotationAxis.x.toFixed(1)}</mi>
|
||||
<mo>·</mo>
|
||||
<mi>sin</mi>
|
||||
<mo>(</mo>
|
||||
<mfrac>
|
||||
<mi>${rotationAngle.toFixed(2)}</mi>
|
||||
<mn>2</mn>
|
||||
</mfrac>
|
||||
<mo>)</mo>
|
||||
</mrow>
|
||||
<mo>, </mo>
|
||||
<mrow>
|
||||
<mi>${rotationAxis.y.toFixed(1)}</mi>
|
||||
<mo>·</mo>
|
||||
<mi>sin</mi>
|
||||
<mo>(</mo>
|
||||
<mfrac>
|
||||
<mi>${rotationAngle.toFixed(2)}</mi>
|
||||
<mn>2</mn>
|
||||
</mfrac>
|
||||
<mo>)</mo>
|
||||
</mrow>
|
||||
<mo>,</mo>
|
||||
<mrow>
|
||||
<mi>${rotationAxis.z.toFixed(1)}</mi>
|
||||
<mo>·</mo>
|
||||
<mi>sin</mi>
|
||||
<mo>(</mo>
|
||||
<mfrac>
|
||||
<mi>${rotationAngle.toFixed(2)}</mi>
|
||||
<mn>2</mn>
|
||||
</mfrac>
|
||||
<mo>)</mo>
|
||||
</mrow>
|
||||
<mo>)</mo>
|
||||
</mrow>
|
||||
</math>
|
||||
= (${quaternion.w.toFixed(1)}, ${(quaternion.x).toFixed(1)}, ${(quaternion.y).toFixed(1)}, ${(quaternion.z).toFixed(1)})`;
|
||||
|
||||
eulerEl.innerHTML = `<b>Углы Эйлера:</b> крен ${(drone.rotation.x * 180 / Math.PI).toFixed(0)}°,
|
||||
тангаж ${(drone.rotation.y * 180 / Math.PI).toFixed(0)}°, рыскание ${(drone.rotation.z * 180 / Math.PI).toFixed(0)}°`;
|
||||
}
|
||||
|
||||
function updateCamera() {
|
||||
const RANGE = 8;
|
||||
const VERT_SHIFT = 2;
|
||||
const HOR_SHIFT = -2;
|
||||
const width = renderer.domElement.clientWidth;
|
||||
const height = renderer.domElement.clientHeight;
|
||||
const ratio = width / height;
|
||||
if (ratio > 1) {
|
||||
camera.left = -RANGE * ratio;
|
||||
camera.right = RANGE * ratio;
|
||||
camera.top = RANGE + VERT_SHIFT;
|
||||
camera.bottom = -RANGE + VERT_SHIFT;
|
||||
} else {
|
||||
camera.left = -RANGE + HOR_SHIFT;
|
||||
camera.right = RANGE + HOR_SHIFT;
|
||||
camera.top = RANGE / ratio + VERT_SHIFT;
|
||||
camera.bottom = -RANGE / ratio + VERT_SHIFT;
|
||||
}
|
||||
camera.updateProjectionMatrix();
|
||||
renderer.setSize(width, height);
|
||||
}
|
||||
|
||||
function update() {
|
||||
// requestAnimationFrame(update);
|
||||
updateCamera();
|
||||
updateScene();
|
||||
controls.update();
|
||||
renderer.render(scene, camera);
|
||||
}
|
||||
update();
|
||||
|
||||
window.addEventListener('resize', update);
|
||||
angleInput.addEventListener('input', update);
|
||||
angleInput.addEventListener('change', update);
|
||||
diagramEl.addEventListener('mousemove', update);
|
||||
diagramEl.addEventListener('touchmove', update);
|
||||
diagramEl.addEventListener('scroll', update);
|
||||
diagramEl.addEventListener('wheel', update);
|
||||
@@ -9,9 +9,9 @@ cd flix
|
||||
|
||||
## Simulation
|
||||
|
||||
### Ubuntu
|
||||
### Ubuntu 20.04
|
||||
|
||||
The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you have a newer version, consider using a virtual machine.
|
||||
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:
|
||||
|
||||
@@ -84,7 +84,7 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you h
|
||||
|
||||
#### Control with smartphone
|
||||
|
||||
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone. For **iOS**, use [QGroundControl build from TAJISOFT](https://apps.apple.com/ru/app/qgc-from-tajisoft/id1618653051).
|
||||
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone.
|
||||
2. Connect your smartphone to the same Wi-Fi network as the machine running the simulator.
|
||||
3. If you're using a virtual machine, make sure that its network is set to the **bridged** mode with Wi-Fi adapter selected.
|
||||
4. Run the simulation.
|
||||
@@ -105,26 +105,17 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you h
|
||||
### Arduino IDE (Windows, Linux, macOS)
|
||||
|
||||
1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended).
|
||||
2. Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).
|
||||
3. Install ESP32 core, version 3.2.0. See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
|
||||
4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
|
||||
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`, the latest version.
|
||||
* `MAVLink`, version 2.0.16.
|
||||
5. Clone the project using git or [download the source code as a ZIP archive](https://codeload.github.com/okalachev/flix/zip/refs/heads/master).
|
||||
6. Open the downloaded Arduino sketch `flix/flix.ino` in Arduino IDE.
|
||||
7. Connect your ESP32 board to the computer and choose correct board type in Arduino IDE (*WEMOS D1 MINI ESP32* for ESP32 Mini) and the port.
|
||||
8. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
|
||||
* `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.
|
||||
|
||||
### Command line (Windows, Linux, macOS)
|
||||
|
||||
1. [Install Arduino CLI](https://arduino.github.io/arduino-cli/installation/).
|
||||
|
||||
On Linux, use:
|
||||
|
||||
```bash
|
||||
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
|
||||
```
|
||||
|
||||
2. Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).
|
||||
3. Compile the firmware using `make`. Arduino dependencies will be installed automatically:
|
||||
|
||||
@@ -146,21 +137,18 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you h
|
||||
|
||||
See other available Make commands in the [Makefile](../Makefile).
|
||||
|
||||
> [!TIP]
|
||||
> You can test the firmware on a bare ESP32 board without connecting IMU and other peripherals. The Wi-Fi network `flix` should appear and all the basic functionality including CLI and QGroundControl connection should work.
|
||||
|
||||
### Setup and flight
|
||||
|
||||
Before flight you need to calibrate the accelerometer:
|
||||
|
||||
1. Open Serial Monitor in Arduino IDE (or use `make monitor` command in the command line).
|
||||
1. Open Serial Monitor in Arduino IDE (use use `make monitor` command in the command line).
|
||||
2. Type `ca` command there and follow the instructions.
|
||||
|
||||
#### Control with smartphone
|
||||
|
||||
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone.
|
||||
2. Power the drone using the battery.
|
||||
3. Connect your smartphone to the appeared `flix` Wi-Fi network (password: `flixwifi`).
|
||||
3. Connect your smartphone to the appeared `flix` Wi-Fi network.
|
||||
4. Open QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
|
||||
5. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
|
||||
6. Use the virtual joystick to fly the drone!
|
||||
@@ -169,33 +157,10 @@ 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 (or use `make monitor` command in the command line).
|
||||
1. Open Serial Monitor in Arduino IDE (use use `make monitor` command in the command line).
|
||||
2. Type `cr` command there and follow the instructions.
|
||||
3. Use the remote control to fly the drone!
|
||||
|
||||
#### Control with USB remote control
|
||||
|
||||
If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it.
|
||||
|
||||
1. Install [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html) app on your computer.
|
||||
2. Connect your USB remote control to the computer.
|
||||
3. Power up the drone.
|
||||
4. Connect your computer to the appeared `flix` Wi-Fi network (password: `flixwifi`).
|
||||
5. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
|
||||
6. Go the the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Joystick*. Calibrate you USB remote control there.
|
||||
7. Use the USB remote control to fly the drone!
|
||||
|
||||
#### Adjusting parameters
|
||||
|
||||
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl app. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*.
|
||||
|
||||
<img src="img/parameters.png" width="400">
|
||||
|
||||
#### CLI access
|
||||
|
||||
In addition to accessing the drone's command line interface (CLI) using the serial port, you can also access it with QGroundControl using Wi-Fi connection. To do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*.
|
||||
|
||||
<img src="img/cli.png" width="400">
|
||||
Then you can use your remote control to fly the drone!
|
||||
|
||||
> [!NOTE]
|
||||
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.
|
||||
|
||||
@@ -1,21 +1,19 @@
|
||||
# Firmware overview
|
||||
|
||||
The firmware is a regular Arduino sketch, and follows the classic Arduino one-threaded design. The initialization code is in the `setup()` function, and the main loop is in the `loop()` function. The sketch includes multiple files, each responsible for a specific part of the system.
|
||||
|
||||
## Dataflow
|
||||
|
||||
<img src="img/dataflow.svg" width=800 alt="Firmware dataflow diagram">
|
||||
|
||||
The main loop is running at 1000 Hz. All the dataflow is happening through global variables (for simplicity):
|
||||
|
||||
* `t` *(double)* — current step time, *s*.
|
||||
* `t` *(float)* — current step time, *s*.
|
||||
* `dt` *(float)* — time delta between the current and previous steps, *s*.
|
||||
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
|
||||
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*.
|
||||
* `rates` *(Vector)* — filtered angular rates, *rad/s*.
|
||||
* `attitude` *(Quaternion)* — estimated attitude (orientation) of drone.
|
||||
* `controlRoll`, `controlPitch`, ... *(float[])* — pilot's control inputs, range [-1, 1].
|
||||
* `motors` *(float[])* — motor outputs, range [0, 1].
|
||||
* `controls` *(float[])* — user control inputs from the RC, normalized to [-1, 1] range.
|
||||
* `motors` *(float[])* — motor outputs, normalized to [-1, 1] range; reverse rotation is possible.
|
||||
|
||||
## Source files
|
||||
|
||||
|
||||
|
Before Width: | Height: | Size: 157 KiB |
|
Before Width: | Height: | Size: 79 KiB |
|
Before Width: | Height: | Size: 115 KiB |
|
Before Width: | Height: | Size: 169 KiB |
|
Before Width: | Height: | Size: 147 KiB |
|
Before Width: | Height: | Size: 99 KiB |
|
Before Width: | Height: | Size: 152 KiB |
@@ -1,94 +0,0 @@
|
||||
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 533 646.91">
|
||||
<defs>
|
||||
<style>
|
||||
.a {
|
||||
font-size: 50px;
|
||||
font-family: Tahoma;
|
||||
}
|
||||
|
||||
.b {
|
||||
opacity: 0.8;
|
||||
}
|
||||
|
||||
.c, .e, .g, .i {
|
||||
fill: none;
|
||||
}
|
||||
|
||||
.c {
|
||||
stroke: #0076ba;
|
||||
}
|
||||
|
||||
.c, .e, .g {
|
||||
stroke-linejoin: bevel;
|
||||
stroke-width: 13px;
|
||||
}
|
||||
|
||||
.d {
|
||||
fill: #0076ba;
|
||||
}
|
||||
|
||||
.e {
|
||||
stroke: #d80100;
|
||||
}
|
||||
|
||||
.f {
|
||||
fill: #d80100;
|
||||
}
|
||||
|
||||
.g {
|
||||
stroke: #57ed00;
|
||||
}
|
||||
|
||||
.h {
|
||||
fill: #57ed00;
|
||||
}
|
||||
|
||||
.i {
|
||||
stroke: #000;
|
||||
stroke-miterlimit: 10;
|
||||
stroke-width: 10px;
|
||||
}
|
||||
</style>
|
||||
</defs>
|
||||
<g>
|
||||
<text class="a" transform="translate(58.62 636.12)">x</text>
|
||||
<text class="a" transform="translate(505.06 562.18)">y</text>
|
||||
<text class="a" transform="translate(370.06 43.18)">z</text>
|
||||
<g class="b">
|
||||
<g>
|
||||
<line class="c" x1="347" y1="420.2" x2="347" y2="61.78"/>
|
||||
<polygon class="d" points="370.34 68.61 347 28.2 323.66 68.61 370.34 68.61"/>
|
||||
</g>
|
||||
</g>
|
||||
<g class="b">
|
||||
<g>
|
||||
<line class="e" x1="347" y1="420.2" x2="29.31" y2="597.81"/>
|
||||
<polygon class="f" points="23.89 574.11 0 614.2 46.66 614.84 23.89 574.11"/>
|
||||
</g>
|
||||
</g>
|
||||
<g class="b">
|
||||
<g>
|
||||
<line class="g" x1="347" y1="420.2" x2="503.22" y2="501.67"/>
|
||||
<polygon class="h" points="486.38 519.2 533 517.2 507.96 477.82 486.38 519.2"/>
|
||||
</g>
|
||||
</g>
|
||||
<g class="b">
|
||||
<g>
|
||||
<path class="i" d="M103.19,617.68a52.66,52.66,0,1,0-55.51-89.19"/>
|
||||
<polygon points="41.63 516.97 34.76 541.97 59.85 535.42 41.63 516.97"/>
|
||||
</g>
|
||||
</g>
|
||||
<g class="b">
|
||||
<g>
|
||||
<path class="i" d="M295.58,87.51a52.66,52.66,0,1,0,103.78,16.31"/>
|
||||
<polygon points="412.03 106.78 397.6 85.24 386.16 108.51 412.03 106.78"/>
|
||||
</g>
|
||||
</g>
|
||||
<g class="b">
|
||||
<g>
|
||||
<path class="i" d="M505,452.58a52.66,52.66,0,1,0-76,72.53"/>
|
||||
<polygon points="418.96 533.38 444.84 535 433.31 511.78 418.96 533.38"/>
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</svg>
|
||||
|
Before Width: | Height: | Size: 2.1 KiB |
|
Before Width: | Height: | Size: 33 KiB |
BIN
docs/img/cli.png
|
Before Width: | Height: | Size: 28 KiB |
|
Before Width: | Height: | Size: 123 KiB |
|
Before Width: | Height: | Size: 30 KiB |
@@ -1,67 +0,0 @@
|
||||
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 533 646.68">
|
||||
<defs>
|
||||
<style>
|
||||
.a {
|
||||
font-size: 50px;
|
||||
font-family: Tahoma;
|
||||
}
|
||||
|
||||
.b {
|
||||
opacity: 0.8;
|
||||
}
|
||||
|
||||
.c, .e, .g {
|
||||
fill: none;
|
||||
stroke-linejoin: bevel;
|
||||
stroke-width: 13px;
|
||||
}
|
||||
|
||||
.c {
|
||||
stroke: #0076ba;
|
||||
}
|
||||
|
||||
.d {
|
||||
fill: #0076ba;
|
||||
}
|
||||
|
||||
.e {
|
||||
stroke: #57ed00;
|
||||
}
|
||||
|
||||
.f {
|
||||
fill: #57ed00;
|
||||
}
|
||||
|
||||
.g {
|
||||
stroke: #d80100;
|
||||
}
|
||||
|
||||
.h {
|
||||
fill: #d80100;
|
||||
}
|
||||
</style>
|
||||
</defs>
|
||||
<g>
|
||||
<text class="a" transform="translate(500.62 556.12)">x</text>
|
||||
<text class="a" transform="translate(370.06 43.18)">z</text>
|
||||
<g class="b">
|
||||
<g>
|
||||
<line class="c" x1="347" y1="420.2" x2="347" y2="61.78"/>
|
||||
<polygon class="d" points="370.34 68.61 347 28.2 323.66 68.61 370.34 68.61"/>
|
||||
</g>
|
||||
</g>
|
||||
<g class="b">
|
||||
<g>
|
||||
<line class="e" x1="347" y1="420.2" x2="29.31" y2="597.81"/>
|
||||
<polygon class="f" points="23.89 574.11 0 614.2 46.66 614.84 23.89 574.11"/>
|
||||
</g>
|
||||
</g>
|
||||
<g class="b">
|
||||
<g>
|
||||
<line class="g" x1="347" y1="420.2" x2="503.22" y2="501.67"/>
|
||||
<polygon class="h" points="486.38 519.2 533 517.2 507.96 477.82 486.38 519.2"/>
|
||||
</g>
|
||||
</g>
|
||||
<text class="a" transform="translate(58.06 635.89)">y</text>
|
||||
</g>
|
||||
</svg>
|
||||
|
Before Width: | Height: | Size: 1.4 KiB |
BIN
docs/img/mx.png
|
Before Width: | Height: | Size: 16 KiB |
|
Before Width: | Height: | Size: 27 KiB |
@@ -1,67 +0,0 @@
|
||||
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 533 646.91">
|
||||
<defs>
|
||||
<style>
|
||||
.a {
|
||||
opacity: 0.8;
|
||||
}
|
||||
|
||||
.b, .d, .f {
|
||||
fill: none;
|
||||
stroke-linejoin: bevel;
|
||||
stroke-width: 13px;
|
||||
}
|
||||
|
||||
.b {
|
||||
stroke: #57ed00;
|
||||
}
|
||||
|
||||
.c {
|
||||
fill: #57ed00;
|
||||
}
|
||||
|
||||
.d {
|
||||
stroke: #d80100;
|
||||
}
|
||||
|
||||
.e {
|
||||
fill: #d80100;
|
||||
}
|
||||
|
||||
.f {
|
||||
stroke: #0076ba;
|
||||
}
|
||||
|
||||
.g {
|
||||
fill: #0076ba;
|
||||
}
|
||||
|
||||
.h {
|
||||
font-size: 50px;
|
||||
font-family: Tahoma;
|
||||
}
|
||||
</style>
|
||||
</defs>
|
||||
<g>
|
||||
<g class="a">
|
||||
<g>
|
||||
<line class="b" x1="347" y1="420.2" x2="503.22" y2="501.67"/>
|
||||
<polygon class="c" points="486.38 519.2 533 517.2 507.96 477.82 486.38 519.2"/>
|
||||
</g>
|
||||
</g>
|
||||
<g class="a">
|
||||
<g>
|
||||
<line class="d" x1="347" y1="420.2" x2="29.31" y2="597.81"/>
|
||||
<polygon class="e" points="23.89 574.11 0 614.2 46.66 614.84 23.89 574.11"/>
|
||||
</g>
|
||||
</g>
|
||||
<g class="a">
|
||||
<g>
|
||||
<line class="f" x1="347" y1="420.2" x2="347" y2="61.78"/>
|
||||
<polygon class="g" points="370.34 68.61 347 28.2 323.66 68.61 370.34 68.61"/>
|
||||
</g>
|
||||
</g>
|
||||
<text class="h" transform="translate(58.62 636.12)">x</text>
|
||||
<text class="h" transform="translate(505.06 562.18)">y</text>
|
||||
<text class="h" transform="translate(370.06 43.18)">z</text>
|
||||
</g>
|
||||
</svg>
|
||||
|
Before Width: | Height: | Size: 1.4 KiB |
|
Before Width: | Height: | Size: 326 KiB |
|
Before Width: | Height: | Size: 68 KiB |
|
Before Width: | Height: | Size: 40 KiB |
|
Before Width: | Height: | Size: 45 KiB |
|
Before Width: | Height: | Size: 51 KiB |
|
Before Width: | Height: | Size: 52 KiB |
|
Before Width: | Height: | Size: 44 KiB |
|
Before Width: | Height: | Size: 54 KiB |
|
Before Width: | Height: | Size: 78 KiB |
|
Before Width: | Height: | Size: 76 KiB |
|
Before Width: | Height: | Size: 29 KiB |
|
Before Width: | Height: | Size: 40 KiB |
|
Before Width: | Height: | Size: 40 KiB |
|
Before Width: | Height: | Size: 49 KiB |
|
Before Width: | Height: | Size: 35 KiB |
|
Before Width: | Height: | Size: 36 KiB |
|
Before Width: | Height: | Size: 43 KiB |
|
Before Width: | Height: | Size: 28 KiB |
|
Before Width: | Height: | Size: 24 KiB |
|
Before Width: | Height: | Size: 45 KiB |
|
Before Width: | Height: | Size: 54 KiB |
|
Before Width: | Height: | Size: 30 KiB |
|
Before Width: | Height: | Size: 43 KiB |
|
Before Width: | Height: | Size: 70 KiB |
|
Before Width: | Height: | Size: 18 KiB |
|
Before Width: | Height: | Size: 33 KiB |
|
Before Width: | Height: | Size: 50 KiB |
|
Before Width: | Height: | Size: 40 KiB |
|
Before Width: | Height: | Size: 83 KiB |
|
Before Width: | Height: | Size: 58 KiB |
|
Before Width: | Height: | Size: 74 KiB |
|
Before Width: | Height: | Size: 56 KiB |
|
Before Width: | Height: | Size: 28 KiB |
|
Before Width: | Height: | Size: 57 KiB |
|
Before Width: | Height: | Size: 49 KiB |
|
Before Width: | Height: | Size: 78 KiB |
|
Before Width: | Height: | Size: 20 KiB |
|
Before Width: | Height: | Size: 73 KiB |
|
Before Width: | Height: | Size: 58 KiB |
|
Before Width: | Height: | Size: 66 KiB |
|
Before Width: | Height: | Size: 9.8 KiB |
|
Before Width: | Height: | Size: 87 KiB |
|
Before Width: | Height: | Size: 50 KiB |
|
Before Width: | Height: | Size: 58 KiB |
@@ -1,29 +0,0 @@
|
||||
.diagram svg {
|
||||
display: block;
|
||||
width: 100%;
|
||||
height: 400px;
|
||||
}
|
||||
.diagram .label {
|
||||
font-family: Arial, sans-serif;
|
||||
font-size: 20px;
|
||||
pointer-events: none;
|
||||
color: black;
|
||||
opacity: 0.8;
|
||||
user-select: none;
|
||||
}
|
||||
.diagram label {
|
||||
display: block;
|
||||
}
|
||||
@media (min-width: 800px) {
|
||||
.diagram b {
|
||||
width: 200px;
|
||||
display: inline-block;
|
||||
}
|
||||
}
|
||||
.diagram p.quaternion {
|
||||
overflow-x: auto;
|
||||
}
|
||||
.diagram input {
|
||||
text-align: center;
|
||||
width: 100%;
|
||||
}
|
||||
2
docs/theme/index.hbs
vendored
@@ -118,7 +118,7 @@
|
||||
<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>
|
||||
© 2025 Олег Калачев
|
||||
© 2024 Олег Калачев
|
||||
</footer>
|
||||
</mdbook-sidebar-scrollbox>
|
||||
<noscript>
|
||||
|
||||
@@ -13,19 +13,15 @@ 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.
|
||||
* **Check the baudrate is correct**. If you see garbage characters in the Serial Monitor, make sure the baudrate is set to 115200.
|
||||
* **Make sure correct IMU model is chosen**. If using ICM-20948 board, change `MPU9250` to `ICM20948` everywhere in the `imu.ino` file.
|
||||
* **Check if the CLI is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the CLI using QGroundControl (*Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*).
|
||||
* **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**.
|
||||
* **If QGroundControl doesn't connect**, you might need to disable the firewall and/or VPN on your computer.
|
||||
* **Check the IMU is working**. Perform `imu` command and check its output:
|
||||
* The `status` field should be `OK`.
|
||||
* The `rate` field should be about 1000 (Hz).
|
||||
* The `accel` and `gyro` fields should change as you move the drone.
|
||||
* **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 type**. Motors with exact 3.7V voltage are needed, not ranged working voltage (3.7V — 6V).
|
||||
* **Check the motors**. Perform the following commands using Serial Monitor:
|
||||
* `mfr` — should rotate front right motor (counter-clockwise).
|
||||
* `mfl` — should rotate front left motor (clockwise).
|
||||
|
||||
123
docs/user.md
@@ -1,123 +0,0 @@
|
||||
# Hall of fame
|
||||
|
||||
This page contains user-built drones based on the Flix project. Publish your projects into the official Telegram-chat: [@opensourcequadcopterchat](https://t.me/opensourcequadcopterchat) or send materials as a pull request.
|
||||
|
||||
---
|
||||
|
||||
Author: chkroko.<br>
|
||||
Description: the first Flix drone built with **brushless motors** (DShot interface).<br>
|
||||
Features: SpeedyBee BLS 35A Mini V2 ESC, ESP32-S3 board, EMAX ECO 2 2207 1700kv motors, ICM20948V2 IMU, INA226 power monitor and Bluetooth gamepad for control.<br>
|
||||
Patch for DShot ESC: https://github.com/Krokodilushka/flix/commit/568345a45ca7ed5b458a11a9d0a9f4c8a91e70ac.
|
||||
|
||||
**Flight video:**
|
||||
|
||||
<a href="https://drive.google.com/file/d/1GFRanASxKmXINi70fxS5RuzV3LJp7f3m/view?usp=share_link"><img height=300 src="img/user/chkroko-bldc/video.jpg"></a>
|
||||
|
||||
<img src="img/user/chkroko-bldc/1.jpg" height=150> <img src="img/user/chkroko-bldc/2.jpg" height=150> <img src="img/user/chkroko-bldc/3.jpg" height=150>
|
||||
|
||||
---
|
||||
|
||||
Author: chkroko.<br>
|
||||
Modification: Control using Bluetooth with **Flydigi Vader 3** gamepad. Source code: https://github.com/Krokodilushka/flix/tree/dev.<br>
|
||||
Features: ESP32-C3 SuperMini, BMP580 barometer, INA226 power monitor, IRLZ44N MOSFETs.<br>
|
||||
Full description: https://telegra.ph/Flix-dron-06-13.
|
||||
|
||||
**Flight video:**
|
||||
|
||||
<a href="https://drive.google.com/file/d/1orVKA_-gsezDTns2Xt8xW1BCWPcyPitR/view?usp=sharing"><img height=300 src="img/user/chkroko/video.jpg"></a>
|
||||
|
||||
<img src="img/user/chkroko/1.jpg" height=150> <img src="img/user/chkroko/2.jpg" height=150>
|
||||
|
||||
---
|
||||
|
||||
Author: chkroko.<br>
|
||||
Features: ESP32-C3 SuperMini board, INA226 power monitor, IRLZ44N MOSFETs, MPU-6500 IMU.
|
||||
|
||||
**Flight video:**
|
||||
|
||||
<a href="https://drive.google.com/file/d/1-4ciDsj8slTEaxxRl1-QAkx0cUDkb8iy/view?usp=sharing"><img height=300 src="img/user/cryptokobans/video.jpg"></a>
|
||||
|
||||
<img src="img/user/cryptokobans/1.jpg" height=150> <img src="img/user/cryptokobans/2.jpg" height=150>
|
||||
|
||||
---
|
||||
|
||||
Author: [@jeka_chex](https://t.me/jeka_chex).<br>
|
||||
Features: custom frame, FPV camera, 3-blade 31 mm propellers.<br>
|
||||
Motor drivers: AON7410 MOSFET + capacitors.<br>
|
||||
Custom frame files: https://drive.google.com/drive/folders/1QCIc-_YYFxJN4cMhVLjL5SflqegvCowm?usp=share_link.<br>
|
||||
|
||||
**Flight video:**
|
||||
|
||||
<a href="https://drive.google.com/file/d/1VnWI5YVPojfqsfpyLX4v2V9zHi9adwcd/view?usp=sharing"><img height=300 src="img/user/jeka_chex/video.jpg"></a>
|
||||
|
||||
**FPV flight video:**
|
||||
|
||||
<a href="https://drive.google.com/file/d/1RSU6VWs9omsge4hGloH5NQqnxvLyhMKB/view?usp=sharing"><img height=300 src="img/user/jeka_chex/video-fpv.jpg"></a>
|
||||
|
||||
<img src="img/user/jeka_chex/1.jpg" height=150> <img src="img/user/jeka_chex/2.jpg" height=150> <img src="img/user/jeka_chex/3.jpg" height=150> <img src="img/user/jeka_chex/4.jpg" height=150> <img src="img/user/jeka_chex/5.jpg" height=150>
|
||||
|
||||
---
|
||||
|
||||
Author: [@fisheyeu](https://t.me/fisheyeu).<br>
|
||||
[Video](https://drive.google.com/file/d/1IT4eMmWPZpmaZR_qsIRmNJ52hYkFB_0q/view?usp=share_link).
|
||||
|
||||
<img src="img/user/fisheyeu/1.jpg" height=300> <img src="img/user/fisheyeu/2.jpg" height=300>
|
||||
|
||||
---
|
||||
|
||||
Author: [@p_kabakov](https://t.me/p_kabakov).<br>
|
||||
Custom propellers guard 3D-model: https://drive.google.com/file/d/1TKnzwvrZYzYuRTLLERNmnKH71H9n4Xj_/view?usp=share_link.<br>
|
||||
Features: ESP32-C3 microcontroller is used.<br>
|
||||
[Video](https://drive.google.com/file/d/1B0NMcsk0fgwUgNr9XuLOdR2yYCuaj008/view?usp=share_link).
|
||||
|
||||
<img src="img/user/p_kabakov/1.jpg" width=150> <img src="img/user/p_kabakov/2.jpg" width=150> <img src="img/user/p_kabakov/3.jpg" width=150>
|
||||
|
||||
**Custom Wi-Fi RC control:**
|
||||
|
||||
<a href="https://github.com/pavelkabakov/flix/blob/master/rc_control_v1/IMG_20250221_195756.jpg"><img height=300 src="img/user/p_kabakov/wifirc.jpg"></a>
|
||||
|
||||
See source and description (in Russian): https://github.com/pavelkabakov/flix/tree/master/rc_control_v1.
|
||||
|
||||
---
|
||||
|
||||
Author: [@yi_lun](https://t.me/yi_lun).<br>
|
||||
[Video](https://drive.google.com/file/d/1TkSuvHQ_0qQPFUpY5XjJzmhnpX_07cTg/view?usp=share_link).
|
||||
|
||||
<img src="img/user/yi_lun/1.jpg" width=300> <img src="img/user/yi_lun/2.jpg" width=300>
|
||||
|
||||
---
|
||||
|
||||
Author: [@peter_ukhov](https://t.me/peter_ukhov).<br>
|
||||
Features: customized ESP32 holder, GY-ICM20948V2 IMU board, boost-converter for powering the ESP32.<br>
|
||||
Files for 3D-printing: https://drive.google.com/file/d/1Sma-FEzFBj2HA5ixJtUyH0uWixvr6vdK/view?usp=share_link.<br>
|
||||
Schematics: https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612179508274&cot=14.<br>
|
||||
|
||||
<a href="https://www.youtube.com/watch?v=wi4w_hOmKcQ"><img width=500 src="img/user/peter_ukhov-2/video.jpg"></a>
|
||||
|
||||
<img src="img/user/peter_ukhov-2/1.jpg" width=300> <img src="img/user/peter_ukhov-2/2.jpg" width=300>
|
||||
|
||||
---
|
||||
|
||||
Author: [@Alexey_Karakash](https://t.me/Alexey_Karakash).<br>
|
||||
Files for 3D printing of the custom frame: https://drive.google.com/file/d/1tkNmujrHrKpTMVtsRH3mor2zdAM0JHum/view?usp=share_link.<br>
|
||||
|
||||
<a href="https://t.me/opensourcequadcopter/61"><img width=500 src="img/user/alexey_karakash/video.jpg"></a>
|
||||
|
||||
<img src="img/user/alexey_karakash/1.jpg" height=150> <img src="img/user/alexey_karakash/2.jpg" height=150> <img src="img/user/alexey_karakash/3.jpg" height=150> <img src="img/user/alexey_karakash/4.jpg" height=150> <img src="img/user/alexey_karakash/5.jpg" height=150>
|
||||
|
||||
---
|
||||
|
||||
Author: [@rudpa](https://t.me/rudpa).<br>
|
||||
|
||||
<a href="https://t.me/opensourcequadcopter/46"><img width=500 src="img/user/rudpa/video.jpg"></a>
|
||||
|
||||
<img src="img/user/rudpa/1.jpg" height=150> <img src="img/user/rudpa/2.jpg" height=150> <img src="img/user/rudpa/3.jpg" height=150>
|
||||
|
||||
---
|
||||
|
||||
Author: [@peter_ukhov](https://t.me/peter_ukhov).<br>
|
||||
Schematics: https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612338222067&cot=14.<br>
|
||||
|
||||
<a href="https://t.me/opensourcequadcopter/24"><img width=500 src="img/user/peter_ukhov/video.jpg"></a>
|
||||
|
||||
<img src="img/user/peter_ukhov/1.jpg" height=150> <img src="img/user/peter_ukhov/2.jpg" height=150> <img src="img/user/peter_ukhov/3.jpg" height=150>
|
||||
@@ -27,4 +27,4 @@ Flix version 0 (obsolete):
|
||||
|
||||
<img src="img/schematics.svg" width=800 alt="Flix schematics">
|
||||
|
||||
You can also check a user contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764574482511443&cot=14) of the drone.
|
||||
You can also check a user contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/) of the drone.
|
||||
|
||||
164
flix/cli.ino
@@ -5,14 +5,9 @@
|
||||
|
||||
#include "pid.h"
|
||||
#include "vector.h"
|
||||
#include "util.h"
|
||||
|
||||
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
||||
extern float loopRate, dt;
|
||||
extern double t;
|
||||
extern uint16_t channels[16];
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlArmed, controlMode;
|
||||
extern bool armed;
|
||||
extern PID rollRatePID, pitchRatePID, yawRatePID, rollPID, pitchPID;
|
||||
extern LowPassFilter<Vector> ratesFilter;
|
||||
|
||||
const char* motd =
|
||||
"\nWelcome to\n"
|
||||
@@ -28,144 +23,73 @@ const char* motd =
|
||||
"p <name> - show parameter\n"
|
||||
"p <name> <value> - set parameter\n"
|
||||
"preset - reset parameters\n"
|
||||
"time - show time info\n"
|
||||
"ps - show pitch/roll/yaw\n"
|
||||
"psq - show attitude quaternion\n"
|
||||
"imu - show IMU data\n"
|
||||
"arm - arm the drone (when no armed switch)\n"
|
||||
"disarm - disarm the drone (when no armed switch)\n"
|
||||
"rc - show RC 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 motor (remove props)\n"
|
||||
"wifi - show Wi-Fi info\n"
|
||||
"sys - show system info\n"
|
||||
"reset - reset drone's state\n"
|
||||
"reboot - reboot the drone\n";
|
||||
|
||||
void print(const char* format, ...) {
|
||||
char buf[1000];
|
||||
va_list args;
|
||||
va_start(args, format);
|
||||
vsnprintf(buf, sizeof(buf), format, args);
|
||||
va_end(args);
|
||||
Serial.print(buf);
|
||||
#if WIFI_ENABLED
|
||||
mavlinkPrint(buf);
|
||||
#endif
|
||||
}
|
||||
|
||||
void pause(float duration) {
|
||||
double start = t;
|
||||
while (t - start < duration) {
|
||||
step();
|
||||
handleInput();
|
||||
#if WIFI_ENABLED
|
||||
processMavlink();
|
||||
#endif
|
||||
delay(50);
|
||||
}
|
||||
}
|
||||
|
||||
void doCommand(String str, bool echo = false) {
|
||||
// parse command
|
||||
String command, arg0, arg1;
|
||||
splitString(str, command, arg0, arg1);
|
||||
|
||||
// echo command
|
||||
if (echo && !command.isEmpty()) {
|
||||
print("> %s\n", str.c_str());
|
||||
}
|
||||
|
||||
command.toLowerCase();
|
||||
|
||||
// execute command
|
||||
void doCommand(String& command, String& arg0, String& arg1) {
|
||||
if (command == "help" || command == "motd") {
|
||||
print("%s\n", motd);
|
||||
Serial.println(motd);
|
||||
} else if (command == "p" && arg0 == "") {
|
||||
printParameters();
|
||||
} else if (command == "p" && arg0 != "" && arg1 == "") {
|
||||
print("%s = %g\n", arg0.c_str(), getParameter(arg0.c_str()));
|
||||
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) {
|
||||
print("%s = %g\n", arg0.c_str(), arg1.toFloat());
|
||||
Serial.printf("%s = %g\n", arg0.c_str(), arg1.toFloat());
|
||||
} else {
|
||||
print("Parameter not found: %s\n", arg0.c_str());
|
||||
Serial.printf("Parameter not found: %s\n", arg0.c_str());
|
||||
}
|
||||
} else if (command == "preset") {
|
||||
resetParameters();
|
||||
} else if (command == "time") {
|
||||
print("Time: %f\n", t);
|
||||
print("Loop rate: %.0f\n", loopRate);
|
||||
print("dt: %f\n", dt);
|
||||
} else if (command == "ps") {
|
||||
Vector a = attitude.toEuler();
|
||||
print("roll: %f pitch: %f yaw: %f\n", degrees(a.x), degrees(a.y), degrees(a.z));
|
||||
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") {
|
||||
print("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
|
||||
Serial.printf("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
|
||||
} else if (command == "imu") {
|
||||
printIMUInfo();
|
||||
print("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
|
||||
print("acc: %f %f %f\n", acc.x, acc.y, acc.z);
|
||||
printIMUCalibration();
|
||||
print("rate: %.0f\n", loopRate);
|
||||
print("landed: %d\n", landed);
|
||||
} else if (command == "arm") {
|
||||
armed = true;
|
||||
} else if (command == "disarm") {
|
||||
armed = false;
|
||||
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("rate: %f\n", loopRate);
|
||||
} else if (command == "rc") {
|
||||
print("channels: ");
|
||||
for (int i = 0; i < 16; i++) {
|
||||
print("%u ", channels[i]);
|
||||
}
|
||||
print("\nroll: %g pitch: %g yaw: %g throttle: %g armed: %g mode: %g\n",
|
||||
controlRoll, controlPitch, controlYaw, controlThrottle, controlArmed, controlMode);
|
||||
print("mode: %s\n", getModeName());
|
||||
print("armed: %d\n", armed);
|
||||
Serial.printf("Raw: throttle %d yaw %d pitch %d roll %d armed %d mode %d\n",
|
||||
channels[RC_CHANNEL_THROTTLE], channels[RC_CHANNEL_YAW], channels[RC_CHANNEL_PITCH],
|
||||
channels[RC_CHANNEL_ROLL], channels[RC_CHANNEL_ARMED], channels[RC_CHANNEL_MODE]);
|
||||
Serial.printf("Control: throttle %f yaw %f pitch %f roll %f armed %f mode %f\n",
|
||||
controls[RC_CHANNEL_THROTTLE], controls[RC_CHANNEL_YAW], controls[RC_CHANNEL_PITCH],
|
||||
controls[RC_CHANNEL_ROLL], controls[RC_CHANNEL_ARMED], controls[RC_CHANNEL_MODE]);
|
||||
Serial.printf("Mode: %s\n", getModeName());
|
||||
} else if (command == "mot") {
|
||||
print("front-right %g front-left %g rear-right %g rear-left %g\n",
|
||||
Serial.printf("MOTOR front-right %f front-left %f rear-right %f rear-left %f\n",
|
||||
motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]);
|
||||
} else if (command == "log") {
|
||||
dumpLog();
|
||||
} else if (command == "cr") {
|
||||
calibrateRC();
|
||||
} else if (command == "cg") {
|
||||
calibrateGyro();
|
||||
} else if (command == "ca") {
|
||||
calibrateAccel();
|
||||
} else if (command == "mfr") {
|
||||
testMotor(MOTOR_FRONT_RIGHT);
|
||||
cliTestMotor(MOTOR_FRONT_RIGHT);
|
||||
} else if (command == "mfl") {
|
||||
testMotor(MOTOR_FRONT_LEFT);
|
||||
cliTestMotor(MOTOR_FRONT_LEFT);
|
||||
} else if (command == "mrr") {
|
||||
testMotor(MOTOR_REAR_RIGHT);
|
||||
cliTestMotor(MOTOR_REAR_RIGHT);
|
||||
} else if (command == "mrl") {
|
||||
testMotor(MOTOR_REAR_LEFT);
|
||||
} else if (command == "wifi") {
|
||||
#if WIFI_ENABLED
|
||||
printWiFiInfo();
|
||||
#endif
|
||||
} else if (command == "sys") {
|
||||
#ifdef ESP32
|
||||
print("Chip: %s\n", ESP.getChipModel());
|
||||
print("Temperature: %.1f °C\n", temperatureRead());
|
||||
print("Free heap: %d\n", ESP.getFreeHeap());
|
||||
// Print tasks table
|
||||
print("Num Task Stack Prio Core CPU%%\n");
|
||||
int taskCount = uxTaskGetNumberOfTasks();
|
||||
TaskStatus_t *systemState = new TaskStatus_t[taskCount];
|
||||
uint32_t totalRunTime;
|
||||
uxTaskGetSystemState(systemState, taskCount, &totalRunTime);
|
||||
for (int i = 0; i < taskCount; i++) {
|
||||
String core = systemState[i].xCoreID == tskNO_AFFINITY ? "*" : String(systemState[i].xCoreID);
|
||||
int cpuPercentage = systemState[i].ulRunTimeCounter / (totalRunTime / 100);
|
||||
print("%-5d%-20s%-7d%-6d%-6s%d\n",systemState[i].xTaskNumber, systemState[i].pcTaskName,
|
||||
systemState[i].usStackHighWaterMark, systemState[i].uxCurrentPriority, core, cpuPercentage);
|
||||
}
|
||||
delete[] systemState;
|
||||
#endif
|
||||
cliTestMotor(MOTOR_REAR_LEFT);
|
||||
} else if (command == "reset") {
|
||||
attitude = Quaternion();
|
||||
} else if (command == "reboot") {
|
||||
@@ -173,26 +97,48 @@ void doCommand(String str, bool echo = false) {
|
||||
} else if (command == "") {
|
||||
// do nothing
|
||||
} else {
|
||||
print("Invalid command: %s\n", command.c_str());
|
||||
Serial.println("Invalid command: " + command);
|
||||
}
|
||||
}
|
||||
|
||||
void handleInput() {
|
||||
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(3000);
|
||||
motors[n] = 0;
|
||||
sendMotors();
|
||||
Serial.println("Done");
|
||||
}
|
||||
|
||||
void parseInput() {
|
||||
static bool showMotd = true;
|
||||
static String input;
|
||||
|
||||
if (showMotd) {
|
||||
print("%s\n", motd);
|
||||
Serial.println(motd);
|
||||
showMotd = false;
|
||||
}
|
||||
|
||||
while (Serial.available()) {
|
||||
char c = Serial.read();
|
||||
if (c == '\n') {
|
||||
doCommand(input);
|
||||
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 {
|
||||
input += c;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Helper function for parsing input
|
||||
String stringToken(char* str, const char* delim) {
|
||||
char* token = strtok(str, delim);
|
||||
return token == NULL ? "" : token;
|
||||
}
|
||||
|
||||
124
flix/control.ino
@@ -7,7 +7,6 @@
|
||||
#include "quaternion.h"
|
||||
#include "pid.h"
|
||||
#include "lpf.h"
|
||||
#include "util.h"
|
||||
|
||||
#define PITCHRATE_P 0.05
|
||||
#define PITCHRATE_I 0.2
|
||||
@@ -21,7 +20,7 @@
|
||||
#define YAWRATE_I 0.0
|
||||
#define YAWRATE_D 0.0
|
||||
#define YAWRATE_I_LIM 0.3
|
||||
#define ROLL_P 6
|
||||
#define ROLL_P 4.5
|
||||
#define ROLL_I 0
|
||||
#define ROLL_D 0
|
||||
#define PITCH_P ROLL_P
|
||||
@@ -30,11 +29,13 @@
|
||||
#define YAW_P 3
|
||||
#define PITCHRATE_MAX radians(360)
|
||||
#define ROLLRATE_MAX radians(360)
|
||||
#define YAWRATE_MAX radians(300)
|
||||
#define TILT_MAX radians(30)
|
||||
#define YAWRATE_MAX radians(360)
|
||||
#define MAX_TILT radians(30)
|
||||
|
||||
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||
|
||||
enum { MANUAL, ACRO, STAB, AUTO } mode = STAB;
|
||||
enum { MANUAL, ACRO, STAB, USER } mode = STAB;
|
||||
enum { YAW, YAW_RATE } yawMode = YAW;
|
||||
bool armed = false;
|
||||
|
||||
PID rollRatePID(ROLLRATE_P, ROLLRATE_I, ROLLRATE_D, ROLLRATE_I_LIM, RATES_D_LPF_ALPHA);
|
||||
@@ -43,63 +44,70 @@ PID yawRatePID(YAWRATE_P, YAWRATE_I, YAWRATE_D);
|
||||
PID rollPID(ROLL_P, ROLL_I, ROLL_D);
|
||||
PID pitchPID(PITCH_P, PITCH_I, PITCH_D);
|
||||
PID yawPID(YAW_P, 0, 0);
|
||||
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
|
||||
float tiltMax = TILT_MAX;
|
||||
|
||||
Quaternion attitudeTarget;
|
||||
Vector ratesTarget;
|
||||
Vector ratesExtra; // feedforward rates
|
||||
Vector torqueTarget;
|
||||
float thrustTarget;
|
||||
|
||||
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlArmed, controlMode;
|
||||
|
||||
void control() {
|
||||
interpretControls();
|
||||
interpretRC();
|
||||
failsafe();
|
||||
controlAttitude();
|
||||
controlRates();
|
||||
controlTorque();
|
||||
if (mode == STAB) {
|
||||
controlAttitude();
|
||||
controlRate();
|
||||
controlTorque();
|
||||
} else if (mode == ACRO) {
|
||||
controlRate();
|
||||
controlTorque();
|
||||
} else if (mode == MANUAL) {
|
||||
controlTorque();
|
||||
}
|
||||
}
|
||||
|
||||
void interpretControls() {
|
||||
void interpretRC() {
|
||||
armed = controls[RC_CHANNEL_THROTTLE] >= 0.05 && controls[RC_CHANNEL_ARMED] >= 0.5;
|
||||
|
||||
// NOTE: put ACRO or MANUAL modes there if you want to use them
|
||||
if (controlMode < 0.25) mode = STAB;
|
||||
if (controlMode < 0.75) mode = STAB;
|
||||
if (controlMode > 0.75) mode = AUTO;
|
||||
if (controlArmed < 0.5) armed = false;
|
||||
|
||||
if (mode == AUTO) return; // pilot is not effective in AUTO mode
|
||||
|
||||
if (landed && controlThrottle == 0 && controlYaw > 0.95) armed = true; // arm gesture
|
||||
if (landed && controlThrottle == 0 && controlYaw < -0.95) armed = false; // disarm gesture
|
||||
|
||||
thrustTarget = controlThrottle;
|
||||
|
||||
if (mode == STAB) {
|
||||
float yawTarget = attitudeTarget.getYaw();
|
||||
if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or pilot commands yaw rate
|
||||
attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget));
|
||||
ratesExtra = Vector(0, 0, -controlYaw * maxRate.z); // positive yaw stick means clockwise rotation in FLU
|
||||
if (controls[RC_CHANNEL_MODE] < 0.25) {
|
||||
mode = STAB;
|
||||
} else if (controls[RC_CHANNEL_MODE] < 0.75) {
|
||||
mode = STAB;
|
||||
} else {
|
||||
mode = STAB;
|
||||
}
|
||||
|
||||
thrustTarget = controls[RC_CHANNEL_THROTTLE];
|
||||
|
||||
if (mode == ACRO) {
|
||||
attitudeTarget.invalidate();
|
||||
ratesTarget.x = controlRoll * maxRate.x;
|
||||
ratesTarget.y = controlPitch * maxRate.y;
|
||||
ratesTarget.z = -controlYaw * maxRate.z; // positive yaw stick means clockwise rotation in FLU
|
||||
yawMode = YAW_RATE;
|
||||
ratesTarget.x = controls[RC_CHANNEL_ROLL] * ROLLRATE_MAX;
|
||||
ratesTarget.y = controls[RC_CHANNEL_PITCH] * PITCHRATE_MAX;
|
||||
ratesTarget.z = -controls[RC_CHANNEL_YAW] * YAWRATE_MAX; // positive yaw stick means clockwise rotation in FLU
|
||||
|
||||
} else if (mode == STAB) {
|
||||
yawMode = controls[RC_CHANNEL_YAW] == 0 ? YAW : YAW_RATE;
|
||||
|
||||
attitudeTarget = Quaternion::fromEulerZYX(Vector(
|
||||
controls[RC_CHANNEL_ROLL] * MAX_TILT,
|
||||
controls[RC_CHANNEL_PITCH] * MAX_TILT,
|
||||
attitudeTarget.getYaw()));
|
||||
ratesTarget.z = -controls[RC_CHANNEL_YAW] * YAWRATE_MAX; // positive yaw stick means clockwise rotation in FLU
|
||||
|
||||
} else if (mode == MANUAL) {
|
||||
// passthrough mode
|
||||
yawMode = YAW_RATE;
|
||||
torqueTarget = Vector(controls[RC_CHANNEL_ROLL], controls[RC_CHANNEL_PITCH], -controls[RC_CHANNEL_YAW]) * 0.01;
|
||||
}
|
||||
|
||||
if (mode == MANUAL) { // passthrough mode
|
||||
attitudeTarget.invalidate();
|
||||
ratesTarget.invalidate();
|
||||
torqueTarget = Vector(controlRoll, controlPitch, -controlYaw) * 0.01;
|
||||
if (yawMode == YAW_RATE || !motorsActive()) {
|
||||
// update yaw target as we don't have control over the yaw
|
||||
attitudeTarget.setYaw(attitude.getYaw());
|
||||
}
|
||||
}
|
||||
|
||||
void controlAttitude() {
|
||||
if (!armed || attitudeTarget.invalid()) { // skip attitude control
|
||||
if (!armed) {
|
||||
rollPID.reset();
|
||||
pitchPID.reset();
|
||||
yawPID.reset();
|
||||
@@ -107,20 +115,22 @@ void controlAttitude() {
|
||||
}
|
||||
|
||||
const Vector up(0, 0, 1);
|
||||
Vector upActual = Quaternion::rotateVector(up, attitude);
|
||||
Vector upTarget = Quaternion::rotateVector(up, attitudeTarget);
|
||||
Vector upActual = attitude.rotate(up);
|
||||
Vector upTarget = attitudeTarget.rotate(up);
|
||||
|
||||
Vector error = Vector::rotationVectorBetween(upTarget, upActual);
|
||||
Vector error = Vector::angularRatesBetweenVectors(upTarget, upActual);
|
||||
|
||||
ratesTarget.x = rollPID.update(error.x, dt) + ratesExtra.x;
|
||||
ratesTarget.y = pitchPID.update(error.y, dt) + ratesExtra.y;
|
||||
ratesTarget.x = rollPID.update(error.x, dt);
|
||||
ratesTarget.y = pitchPID.update(error.y, dt);
|
||||
|
||||
float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw());
|
||||
ratesTarget.z = yawPID.update(yawError, dt) + ratesExtra.z;
|
||||
if (yawMode == YAW) {
|
||||
float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw());
|
||||
ratesTarget.z = yawPID.update(yawError, dt);
|
||||
}
|
||||
}
|
||||
|
||||
void controlRates() {
|
||||
if (!armed || ratesTarget.invalid()) { // skip rates control
|
||||
void controlRate() {
|
||||
if (!armed) {
|
||||
rollRatePID.reset();
|
||||
pitchRatePID.reset();
|
||||
yawRatePID.reset();
|
||||
@@ -136,10 +146,8 @@ void controlRates() {
|
||||
}
|
||||
|
||||
void controlTorque() {
|
||||
if (!torqueTarget.valid()) return; // skip torque control
|
||||
|
||||
if (!armed || thrustTarget < 0.05) {
|
||||
memset(motors, 0, sizeof(motors)); // stop motors if no thrust
|
||||
if (!armed) {
|
||||
memset(motors, 0, sizeof(motors));
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -154,12 +162,16 @@ void controlTorque() {
|
||||
motors[3] = constrain(motors[3], 0, 1);
|
||||
}
|
||||
|
||||
bool motorsActive() {
|
||||
return motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0;
|
||||
}
|
||||
|
||||
const char* getModeName() {
|
||||
switch (mode) {
|
||||
case MANUAL: return "MANUAL";
|
||||
case ACRO: return "ACRO";
|
||||
case STAB: return "STAB";
|
||||
case AUTO: return "AUTO";
|
||||
case USER: return "USER";
|
||||
default: return "UNKNOWN";
|
||||
}
|
||||
}
|
||||
|
||||
@@ -6,9 +6,8 @@
|
||||
#include "quaternion.h"
|
||||
#include "vector.h"
|
||||
#include "lpf.h"
|
||||
#include "util.h"
|
||||
|
||||
#define WEIGHT_ACC 0.003
|
||||
#define WEIGHT_ACC 0.5f
|
||||
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||
|
||||
LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
|
||||
@@ -23,20 +22,23 @@ void applyGyro() {
|
||||
rates = ratesFilter.update(gyro);
|
||||
|
||||
// apply rates to attitude
|
||||
attitude = Quaternion::rotate(attitude, Quaternion::fromRotationVector(rates * dt));
|
||||
attitude *= Quaternion::fromAngularRates(rates * dt);
|
||||
attitude.normalize();
|
||||
}
|
||||
|
||||
void applyAcc() {
|
||||
// test should we apply accelerometer gravity correction
|
||||
float accNorm = acc.norm();
|
||||
landed = !motorsActive() && abs(accNorm - ONE_G) < ONE_G * 0.1f;
|
||||
bool landed = !motorsActive() && abs(accNorm - ONE_G) < ONE_G * 0.1f;
|
||||
|
||||
setLED(landed);
|
||||
if (!landed) return;
|
||||
|
||||
// calculate accelerometer correction
|
||||
Vector up = Quaternion::rotateVector(Vector(0, 0, 1), attitude);
|
||||
Vector correction = Vector::rotationVectorBetween(acc, up) * WEIGHT_ACC;
|
||||
Vector up = attitude.rotate(Vector(0, 0, 1));
|
||||
Vector correction = Vector::angularRatesBetweenVectors(acc, up) * dt * WEIGHT_ACC;
|
||||
|
||||
// apply correction
|
||||
attitude = Quaternion::rotate(attitude, Quaternion::fromRotationVector(correction));
|
||||
attitude *= Quaternion::fromAngularRates(correction);
|
||||
attitude.normalize();
|
||||
}
|
||||
|
||||
@@ -1,50 +1,23 @@
|
||||
// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// Fail-safe functions
|
||||
// Fail-safe for RC loss
|
||||
|
||||
#include "util.h"
|
||||
|
||||
#define RC_LOSS_TIMEOUT 0.5
|
||||
#define RC_LOSS_TIMEOUT 0.2
|
||||
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
|
||||
|
||||
extern double controlTime;
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
|
||||
|
||||
void failsafe() {
|
||||
rcLossFailsafe();
|
||||
autoFailsafe();
|
||||
}
|
||||
|
||||
// RC loss failsafe
|
||||
void rcLossFailsafe() {
|
||||
if (mode == AUTO) return;
|
||||
if (!armed) return;
|
||||
if (t - controlTime > RC_LOSS_TIMEOUT) {
|
||||
if (t - controlsTime > RC_LOSS_TIMEOUT) {
|
||||
descend();
|
||||
}
|
||||
}
|
||||
|
||||
// Allow pilot to interrupt automatic flight
|
||||
void autoFailsafe() {
|
||||
static float roll, pitch, yaw, throttle;
|
||||
|
||||
if (roll != controlRoll || pitch != controlPitch || yaw != controlYaw || abs(throttle - controlThrottle) > 0.05) {
|
||||
if (mode == AUTO && invalid(controlMode)) {
|
||||
mode = STAB; // regain control to the pilot
|
||||
}
|
||||
}
|
||||
|
||||
roll = controlRoll;
|
||||
pitch = controlPitch;
|
||||
yaw = controlYaw;
|
||||
throttle = controlThrottle;
|
||||
}
|
||||
|
||||
// Smooth descend on RC lost
|
||||
void descend() {
|
||||
mode = AUTO;
|
||||
thrustTarget -= dt / DESCEND_TIME;
|
||||
if (thrustTarget < 0) thrustTarget = 0;
|
||||
if (thrustTarget == 0) armed = false;
|
||||
// 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;
|
||||
}
|
||||
|
||||
@@ -5,37 +5,55 @@
|
||||
|
||||
#include "vector.h"
|
||||
#include "quaternion.h"
|
||||
#include "util.h"
|
||||
|
||||
#define SERIAL_BAUDRATE 115200
|
||||
|
||||
#define WIFI_ENABLED 1
|
||||
|
||||
double t = NAN; // current step time, s
|
||||
#define RC_CHANNELS 16
|
||||
#define RC_CHANNEL_ROLL 0
|
||||
#define RC_CHANNEL_PITCH 1
|
||||
#define RC_CHANNEL_THROTTLE 2
|
||||
#define RC_CHANNEL_YAW 3
|
||||
#define RC_CHANNEL_ARMED 4
|
||||
#define RC_CHANNEL_MODE 5
|
||||
|
||||
#define MOTOR_REAR_LEFT 0
|
||||
#define MOTOR_REAR_RIGHT 1
|
||||
#define MOTOR_FRONT_RIGHT 2
|
||||
#define MOTOR_FRONT_LEFT 3
|
||||
|
||||
#define ONE_G 9.80665
|
||||
|
||||
float t = NAN; // current step time, s
|
||||
float dt; // time delta from previous step, s
|
||||
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
|
||||
float controlArmed = NAN, controlMode = NAN;
|
||||
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 [0..1]
|
||||
float motors[4]; // normalized motors thrust in range [-1..1]
|
||||
|
||||
void setup() {
|
||||
Serial.begin(SERIAL_BAUDRATE);
|
||||
print("Initializing flix\n");
|
||||
Serial.println("Initializing flix");
|
||||
disableBrownOut();
|
||||
setupParameters();
|
||||
setupLED();
|
||||
setupMotors();
|
||||
setLED(true);
|
||||
#if WIFI_ENABLED
|
||||
#if WIFI_ENABLED == 1
|
||||
setupWiFi();
|
||||
#endif
|
||||
setupIMU();
|
||||
setupRC();
|
||||
|
||||
setLED(false);
|
||||
print("Initializing complete\n");
|
||||
Serial.println("Initializing complete");
|
||||
}
|
||||
|
||||
void loop() {
|
||||
@@ -45,10 +63,10 @@ void loop() {
|
||||
estimate();
|
||||
control();
|
||||
sendMotors();
|
||||
handleInput();
|
||||
#if WIFI_ENABLED
|
||||
parseInput();
|
||||
#if WIFI_ENABLED == 1
|
||||
processMavlink();
|
||||
#endif
|
||||
logData();
|
||||
syncParameters();
|
||||
flushParameters();
|
||||
}
|
||||
|
||||
81
flix/imu.ino
@@ -5,19 +5,24 @@
|
||||
|
||||
#include <SPI.h>
|
||||
#include <MPU9250.h>
|
||||
#include "lpf.h"
|
||||
#include "util.h"
|
||||
|
||||
MPU9250 IMU(SPI);
|
||||
|
||||
Vector accBias;
|
||||
Vector accScale(1, 1, 1);
|
||||
Vector gyroBias;
|
||||
Vector accScale(1, 1, 1);
|
||||
|
||||
void setupIMU() {
|
||||
print("Setup IMU\n");
|
||||
IMU.begin();
|
||||
Serial.println("Setup IMU");
|
||||
bool status = IMU.begin();
|
||||
if (!status) {
|
||||
while (true) {
|
||||
Serial.println("IMU begin error");
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
configureIMU();
|
||||
// calibrateGyro();
|
||||
}
|
||||
|
||||
void configureIMU() {
|
||||
@@ -25,7 +30,6 @@ void configureIMU() {
|
||||
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
|
||||
IMU.setDLPF(IMU.DLPF_MAX);
|
||||
IMU.setRate(IMU.RATE_1KHZ_APPROX);
|
||||
IMU.setupInterrupt();
|
||||
}
|
||||
|
||||
void readIMU() {
|
||||
@@ -49,39 +53,48 @@ void rotateIMU(Vector& data) {
|
||||
}
|
||||
|
||||
void calibrateGyroOnce() {
|
||||
static float landedTime = 0;
|
||||
landedTime = landed ? landedTime + dt : 0;
|
||||
if (landedTime < 2) return; // calibrate only if definitely stationary
|
||||
if (!landed) return;
|
||||
static float samples = 0; // overflows after 49 days at 1000 Hz
|
||||
samples++;
|
||||
gyroBias = gyroBias + (gyro - gyroBias) / samples; // running average
|
||||
}
|
||||
|
||||
static LowPassFilter<Vector> gyroCalibrationFilter(0.001);
|
||||
gyroBias = gyroCalibrationFilter.update(gyro);
|
||||
void calibrateGyro() {
|
||||
const int samples = 1000;
|
||||
Serial.println("Calibrating gyro, stand still");
|
||||
IMU.setGyroRange(IMU.GYRO_RANGE_250DPS); // the most sensitive mode
|
||||
|
||||
gyroBias = Vector(0, 0, 0);
|
||||
for (int i = 0; i < samples; i++) {
|
||||
IMU.waitForData();
|
||||
IMU.getGyro(gyro.x, gyro.y, gyro.z);
|
||||
gyroBias = gyroBias + gyro;
|
||||
}
|
||||
gyroBias = gyroBias / samples;
|
||||
|
||||
printIMUCal();
|
||||
configureIMU();
|
||||
}
|
||||
|
||||
void calibrateAccel() {
|
||||
print("Calibrating accelerometer\n");
|
||||
Serial.println("Calibrating accelerometer");
|
||||
IMU.setAccelRange(IMU.ACCEL_RANGE_2G); // the most sensitive mode
|
||||
|
||||
print("1/6 Place level [8 sec]\n");
|
||||
pause(8);
|
||||
Serial.setTimeout(60000);
|
||||
Serial.print("Place level [enter] "); Serial.readStringUntil('\n');
|
||||
calibrateAccelOnce();
|
||||
print("2/6 Place nose up [8 sec]\n");
|
||||
pause(8);
|
||||
Serial.print("Place nose up [enter] "); Serial.readStringUntil('\n');
|
||||
calibrateAccelOnce();
|
||||
print("3/6 Place nose down [8 sec]\n");
|
||||
pause(8);
|
||||
Serial.print("Place nose down [enter] "); Serial.readStringUntil('\n');
|
||||
calibrateAccelOnce();
|
||||
print("4/6 Place on right side [8 sec]\n");
|
||||
pause(8);
|
||||
Serial.print("Place on right side [enter] "); Serial.readStringUntil('\n');
|
||||
calibrateAccelOnce();
|
||||
print("5/6 Place on left side [8 sec]\n");
|
||||
pause(8);
|
||||
Serial.print("Place on left side [enter] "); Serial.readStringUntil('\n');
|
||||
calibrateAccelOnce();
|
||||
print("6/6 Place upside down [8 sec]\n");
|
||||
pause(8);
|
||||
Serial.print("Place upside down [enter] "); Serial.readStringUntil('\n');
|
||||
calibrateAccelOnce();
|
||||
|
||||
printIMUCalibration();
|
||||
print("✓ Calibration done!\n");
|
||||
printIMUCal();
|
||||
configureIMU();
|
||||
}
|
||||
|
||||
@@ -107,19 +120,21 @@ void calibrateAccelOnce() {
|
||||
if (acc.x < accMin.x) accMin.x = acc.x;
|
||||
if (acc.y < accMin.y) accMin.y = acc.y;
|
||||
if (acc.z < accMin.z) accMin.z = acc.z;
|
||||
Serial.printf("acc %f %f %f\n", acc.x, acc.y, acc.z);
|
||||
Serial.printf("max %f %f %f\n", accMax.x, accMax.y, accMax.z);
|
||||
Serial.printf("min %f %f %f\n", accMin.x, accMin.y, accMin.z);
|
||||
// Compute scale and bias
|
||||
accScale = (accMax - accMin) / 2 / ONE_G;
|
||||
accBias = (accMax + accMin) / 2;
|
||||
}
|
||||
|
||||
void printIMUCalibration() {
|
||||
print("gyro bias: %f %f %f\n", gyroBias.x, gyroBias.y, gyroBias.z);
|
||||
print("accel bias: %f %f %f\n", accBias.x, accBias.y, accBias.z);
|
||||
print("accel scale: %f %f %f\n", accScale.x, accScale.y, accScale.z);
|
||||
void 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);
|
||||
}
|
||||
|
||||
void printIMUInfo() {
|
||||
IMU.status() ? print("status: ERROR %d\n", IMU.status()) : print("status: OK\n");
|
||||
print("model: %s\n", IMU.getModel());
|
||||
print("who am I: 0x%02X\n", IMU.whoAmI());
|
||||
Serial.printf("model: %s\n", IMU.getModel());
|
||||
Serial.printf("who am I: 0x%02X\n", IMU.whoAmI());
|
||||
}
|
||||
|
||||
74
flix/log.ino
@@ -3,60 +3,36 @@
|
||||
|
||||
// In-RAM logging
|
||||
|
||||
#include "vector.h"
|
||||
|
||||
#define LOG_RATE 100
|
||||
#define LOG_DURATION 10
|
||||
#define LOG_PERIOD 1.0 / LOG_RATE
|
||||
#define LOG_SIZE LOG_DURATION * LOG_RATE
|
||||
#define LOG_COLUMNS 14
|
||||
|
||||
float tFloat;
|
||||
Vector attitudeEuler;
|
||||
Vector attitudeTargetEuler;
|
||||
|
||||
struct LogEntry {
|
||||
const char *name;
|
||||
float *value;
|
||||
};
|
||||
|
||||
LogEntry logEntries[] = {
|
||||
{"t", &tFloat},
|
||||
{"rates.x", &rates.x},
|
||||
{"rates.y", &rates.y},
|
||||
{"rates.z", &rates.z},
|
||||
{"ratesTarget.x", &ratesTarget.x},
|
||||
{"ratesTarget.y", &ratesTarget.y},
|
||||
{"ratesTarget.z", &ratesTarget.z},
|
||||
{"attitude.x", &attitudeEuler.x},
|
||||
{"attitude.y", &attitudeEuler.y},
|
||||
{"attitude.z", &attitudeEuler.z},
|
||||
{"attitudeTarget.x", &attitudeTargetEuler.x},
|
||||
{"attitudeTarget.y", &attitudeTargetEuler.y},
|
||||
{"attitudeTarget.z", &attitudeTargetEuler.z},
|
||||
{"thrustTarget", &thrustTarget}
|
||||
};
|
||||
|
||||
const int logColumns = sizeof(logEntries) / sizeof(logEntries[0]);
|
||||
float logBuffer[LOG_SIZE][logColumns];
|
||||
|
||||
void prepareLogData() {
|
||||
tFloat = t;
|
||||
attitudeEuler = attitude.toEuler();
|
||||
attitudeTargetEuler = attitudeTarget.toEuler();
|
||||
}
|
||||
float logBuffer[LOG_SIZE][LOG_COLUMNS]; // * 4 (float)
|
||||
int logPointer = 0;
|
||||
|
||||
void logData() {
|
||||
if (!armed) return;
|
||||
static int logPointer = 0;
|
||||
static double logTime = 0;
|
||||
|
||||
static float logTime = 0;
|
||||
if (t - logTime < LOG_PERIOD) return;
|
||||
logTime = t;
|
||||
|
||||
prepareLogData();
|
||||
|
||||
for (int i = 0; i < logColumns; i++) {
|
||||
logBuffer[logPointer][i] = *logEntries[i].value;
|
||||
}
|
||||
logBuffer[logPointer][0] = t;
|
||||
logBuffer[logPointer][1] = rates.x;
|
||||
logBuffer[logPointer][2] = rates.y;
|
||||
logBuffer[logPointer][3] = rates.z;
|
||||
logBuffer[logPointer][4] = ratesTarget.x;
|
||||
logBuffer[logPointer][5] = ratesTarget.y;
|
||||
logBuffer[logPointer][6] = ratesTarget.z;
|
||||
logBuffer[logPointer][7] = attitude.toEulerZYX().x;
|
||||
logBuffer[logPointer][8] = attitude.toEulerZYX().y;
|
||||
logBuffer[logPointer][9] = attitude.toEulerZYX().z;
|
||||
logBuffer[logPointer][10] = attitudeTarget.toEulerZYX().x;
|
||||
logBuffer[logPointer][11] = attitudeTarget.toEulerZYX().y;
|
||||
logBuffer[logPointer][12] = attitudeTarget.toEulerZYX().z;
|
||||
logBuffer[logPointer][13] = thrustTarget;
|
||||
|
||||
logPointer++;
|
||||
if (logPointer >= LOG_SIZE) {
|
||||
@@ -65,15 +41,13 @@ void logData() {
|
||||
}
|
||||
|
||||
void dumpLog() {
|
||||
// Print header
|
||||
for (int i = 0; i < logColumns; i++) {
|
||||
print("%s%s", logEntries[i].name, i < logColumns - 1 ? "," : "\n");
|
||||
}
|
||||
// Print data
|
||||
Serial.printf("t,rates.x,rates.y,rates.z,ratesTarget.x,ratesTarget.y,ratesTarget.z,"
|
||||
"attitude.x,attitude.y,attitude.z,attitudeTarget.x,attitudeTarget.y,attitudeTarget.z,thrustTarget\n");
|
||||
for (int i = 0; i < LOG_SIZE; i++) {
|
||||
if (logBuffer[i][0] == 0) continue; // skip empty records
|
||||
for (int j = 0; j < logColumns; j++) {
|
||||
print("%g%s", logBuffer[i][j], j < logColumns - 1 ? "," : "\n");
|
||||
for (int j = 0; j < LOG_COLUMNS - 1; j++) {
|
||||
Serial.printf("%f,", logBuffer[i][j]);
|
||||
}
|
||||
Serial.printf("%f\n", logBuffer[i][LOG_COLUMNS - 1]);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -22,8 +22,7 @@ public:
|
||||
output = input;
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return output += alpha * (input - output);
|
||||
return output = output * (1 - alpha) + input * alpha;
|
||||
}
|
||||
|
||||
void setCutOffFrequency(float cutOffFreq, float dt) {
|
||||
|
||||
212
flix/mavlink.ino
@@ -3,31 +3,24 @@
|
||||
|
||||
// MAVLink communication
|
||||
|
||||
#if WIFI_ENABLED
|
||||
#if WIFI_ENABLED == 1
|
||||
|
||||
#include <MAVLink.h>
|
||||
|
||||
#define SYSTEM_ID 1
|
||||
#define PERIOD_SLOW 1.0
|
||||
#define PERIOD_FAST 0.1
|
||||
#define MAVLINK_CONTROL_SCALE 0.7f
|
||||
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
||||
|
||||
float mavlinkControlScale = 0.7;
|
||||
String mavlinkPrintBuffer;
|
||||
|
||||
extern double controlTime;
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlArmed, controlMode;
|
||||
|
||||
void processMavlink() {
|
||||
sendMavlink();
|
||||
receiveMavlink();
|
||||
}
|
||||
|
||||
void sendMavlink() {
|
||||
sendMavlinkPrint();
|
||||
|
||||
static double lastSlow = 0;
|
||||
static double lastFast = 0;
|
||||
static float lastSlow = 0;
|
||||
static float lastFast = 0;
|
||||
|
||||
mavlink_message_t msg;
|
||||
uint32_t time = t * 1000;
|
||||
@@ -35,15 +28,9 @@ void sendMavlink() {
|
||||
if (t - lastSlow >= PERIOD_SLOW) {
|
||||
lastSlow = t;
|
||||
|
||||
mavlink_msg_heartbeat_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
|
||||
(armed * MAV_MODE_FLAG_SAFETY_ARMED) |
|
||||
(mode == STAB) * MAV_MODE_FLAG_STABILIZE_ENABLED |
|
||||
((mode == AUTO) ? MAV_MODE_FLAG_AUTO_ENABLED : MAV_MODE_FLAG_MANUAL_INPUT_ENABLED),
|
||||
mode, MAV_STATE_STANDBY);
|
||||
sendMessage(&msg);
|
||||
|
||||
mavlink_msg_extended_sys_state_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
MAV_VTOL_STATE_UNDEFINED, landed ? MAV_LANDED_STATE_ON_GROUND : MAV_LANDED_STATE_IN_AIR);
|
||||
mavlink_msg_heartbeat_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR,
|
||||
MAV_AUTOPILOT_GENERIC, MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (armed ? MAV_MODE_FLAG_SAFETY_ARMED : 0),
|
||||
0, MAV_STATE_STANDBY);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
|
||||
@@ -51,22 +38,25 @@ void sendMavlink() {
|
||||
lastFast = t;
|
||||
|
||||
const float zeroQuat[] = {0, 0, 0, 0};
|
||||
Quaternion attitudeFRD = FLU2FRD(attitude); // MAVLink uses FRD coordinate system
|
||||
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd
|
||||
time, attitudeFRD.w, attitudeFRD.x, attitudeFRD.y, attitudeFRD.z, rates.x, rates.y, rates.z, zeroQuat);
|
||||
sendMessage(&msg);
|
||||
|
||||
mavlink_msg_rc_channels_raw_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,
|
||||
channels[0], channels[1], channels[2], channels[3], channels[4], channels[5], channels[6], channels[7], UINT8_MAX);
|
||||
if (channels[0] != 0) sendMessage(&msg); // 0 means no RC input
|
||||
mavlink_msg_rc_channels_scaled_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0,
|
||||
controls[0] * 10000, controls[1] * 10000, controls[2] * 10000,
|
||||
controls[3] * 10000, controls[4] * 10000, controls[5] * 10000,
|
||||
INT16_MAX, INT16_MAX, UINT8_MAX);
|
||||
sendMessage(&msg);
|
||||
|
||||
float controls[8];
|
||||
memcpy(controls, motors, sizeof(motors));
|
||||
mavlink_msg_actuator_control_target_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0, controls);
|
||||
float actuator[32];
|
||||
memcpy(actuator, motors, sizeof(motors));
|
||||
mavlink_msg_actuator_output_status_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 4, actuator);
|
||||
sendMessage(&msg);
|
||||
|
||||
mavlink_msg_scaled_imu_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time,
|
||||
acc.x * 1000, -acc.y * 1000, -acc.z * 1000, // convert to frd
|
||||
gyro.x * 1000, -gyro.y * 1000, -gyro.z * 1000,
|
||||
acc.x * 1000, acc.y * 1000, acc.z * 1000,
|
||||
gyro.x * 1000, gyro.y * 1000, gyro.z * 1000,
|
||||
0, 0, 0, 0);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
@@ -93,29 +83,23 @@ void receiveMavlink() {
|
||||
}
|
||||
|
||||
void handleMavlink(const void *_msg) {
|
||||
const mavlink_message_t& msg = *(mavlink_message_t *)_msg;
|
||||
mavlink_message_t *msg = (mavlink_message_t *)_msg;
|
||||
|
||||
if (msg.msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
|
||||
mavlink_manual_control_t m;
|
||||
mavlink_msg_manual_control_decode(&msg, &m);
|
||||
if (m.target && m.target != SYSTEM_ID) return; // 0 is broadcast
|
||||
if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
|
||||
mavlink_manual_control_t manualControl;
|
||||
mavlink_msg_manual_control_decode(msg, &manualControl);
|
||||
controls[RC_CHANNEL_THROTTLE] = manualControl.z / 1000.0f;
|
||||
controls[RC_CHANNEL_PITCH] = manualControl.x / 1000.0f * MAVLINK_CONTROL_SCALE;
|
||||
controls[RC_CHANNEL_ROLL] = manualControl.y / 1000.0f * MAVLINK_CONTROL_SCALE;
|
||||
controls[RC_CHANNEL_YAW] = manualControl.r / 1000.0f * MAVLINK_CONTROL_SCALE;
|
||||
controls[RC_CHANNEL_MODE] = 1; // STAB mode
|
||||
controls[RC_CHANNEL_ARMED] = 1; // armed
|
||||
controlsTime = t;
|
||||
|
||||
controlThrottle = m.z / 1000.0f;
|
||||
controlPitch = m.x / 1000.0f * mavlinkControlScale;
|
||||
controlRoll = m.y / 1000.0f * mavlinkControlScale;
|
||||
controlYaw = m.r / 1000.0f * mavlinkControlScale;
|
||||
controlMode = NAN; // keep mode
|
||||
controlArmed = NAN;
|
||||
controlTime = t;
|
||||
|
||||
if (abs(controlYaw) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controlYaw = 0;
|
||||
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_param_request_list_t m;
|
||||
mavlink_msg_param_request_list_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
|
||||
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,
|
||||
@@ -124,141 +108,63 @@ void handleMavlink(const void *_msg) {
|
||||
}
|
||||
}
|
||||
|
||||
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_READ) {
|
||||
mavlink_param_request_read_t m;
|
||||
mavlink_msg_param_request_read_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
|
||||
char name[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
|
||||
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
|
||||
float value = strlen(name) == 0 ? getParameter(m.param_index) : getParameter(name);
|
||||
if (m.param_index != -1) {
|
||||
memcpy(name, getParameterName(m.param_index), 16);
|
||||
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(), m.param_index);
|
||||
name, value, MAV_PARAM_TYPE_REAL32, parametersCount(), paramRequestRead.param_index);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
|
||||
if (msg.msgid == MAVLINK_MSG_ID_PARAM_SET) {
|
||||
mavlink_param_set_t m;
|
||||
mavlink_msg_param_set_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
|
||||
char name[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN + 1];
|
||||
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
|
||||
setParameter(name, m.param_value);
|
||||
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,
|
||||
m.param_id, m.param_value, MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
|
||||
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_mission_request_list_t m;
|
||||
mavlink_msg_mission_request_list_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
if (msg.msgid == MAVLINK_MSG_ID_SERIAL_CONTROL) {
|
||||
mavlink_serial_control_t m;
|
||||
mavlink_msg_serial_control_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
|
||||
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
|
||||
strlcpy(data, (const char *)m.data, m.count); // data might be not null-terminated
|
||||
doCommand(data, true);
|
||||
}
|
||||
|
||||
if (msg.msgid == MAVLINK_MSG_ID_SET_ATTITUDE_TARGET) {
|
||||
if (mode != AUTO) return;
|
||||
|
||||
mavlink_set_attitude_target_t m;
|
||||
mavlink_msg_set_attitude_target_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
|
||||
// copy attitude, rates and thrust targets
|
||||
ratesTarget.x = m.body_roll_rate;
|
||||
ratesTarget.y = -m.body_pitch_rate; // convert to flu
|
||||
ratesTarget.z = -m.body_yaw_rate;
|
||||
attitudeTarget.w = m.q[0];
|
||||
attitudeTarget.x = m.q[1];
|
||||
attitudeTarget.y = -m.q[2];
|
||||
attitudeTarget.z = -m.q[3];
|
||||
thrustTarget = m.thrust;
|
||||
ratesExtra = Vector(0, 0, 0);
|
||||
|
||||
if (m.type_mask & ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE) attitudeTarget.invalidate();
|
||||
|
||||
armed = m.thrust > 0;
|
||||
}
|
||||
|
||||
if (msg.msgid == MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET) {
|
||||
if (mode != AUTO) return;
|
||||
|
||||
mavlink_set_actuator_control_target_t m;
|
||||
mavlink_msg_set_actuator_control_target_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
|
||||
memcpy(motors, m.controls, sizeof(motors)); // copy motor thrusts
|
||||
}
|
||||
|
||||
// Handle commands
|
||||
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
|
||||
mavlink_command_long_t m;
|
||||
mavlink_msg_command_long_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
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 (m.command == MAV_CMD_REQUEST_MESSAGE && m.param1 == MAVLINK_MSG_ID_AUTOPILOT_VERSION) {
|
||||
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
|
||||
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);
|
||||
}
|
||||
|
||||
if (m.command == MAV_CMD_DO_SET_MODE) {
|
||||
if (!(m.param2 >= 0 && m.param2 <= AUTO)) return;
|
||||
mode = static_cast<decltype(mode)>(m.param2);
|
||||
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
|
||||
sendMessage(&ack);
|
||||
}
|
||||
|
||||
if (m.command == MAV_CMD_COMPONENT_ARM_DISARM) {
|
||||
armed = m.param1 == 1;
|
||||
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
|
||||
} 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);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Send shell output to GCS
|
||||
void mavlinkPrint(const char* str) {
|
||||
mavlinkPrintBuffer += str;
|
||||
}
|
||||
|
||||
void sendMavlinkPrint() {
|
||||
// Send mavlink print data in chunks
|
||||
const char *str = mavlinkPrintBuffer.c_str();
|
||||
for (int i = 0; i < strlen(str); i += MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN) {
|
||||
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
|
||||
strlcpy(data, str + i, sizeof(data));
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_serial_control_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
SERIAL_CONTROL_DEV_SHELL,
|
||||
i + MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN < strlen(str) ? SERIAL_CONTROL_FLAG_MULTI : 0, // more chunks to go
|
||||
0, 0, strlen(data), (uint8_t *)data, 0, 0);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
mavlinkPrintBuffer.clear();
|
||||
// Convert Forward-Left-Up to Forward-Right-Down quaternion
|
||||
inline Quaternion FLU2FRD(const Quaternion &q) {
|
||||
return Quaternion(q.w, q.x, -q.y, -q.z);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
@@ -2,29 +2,19 @@
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// Motors output control using MOSFETs
|
||||
// In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400)
|
||||
|
||||
#include "util.h"
|
||||
// In case of using ESC, use this version of the code: https://gist.github.com/okalachev/8871d3a94b6b6c0a298f41a4edd34c61.
|
||||
// Motor: 8520 3.7V
|
||||
|
||||
#define MOTOR_0_PIN 12 // rear left
|
||||
#define MOTOR_1_PIN 13 // rear right
|
||||
#define MOTOR_2_PIN 14 // front right
|
||||
#define MOTOR_3_PIN 15 // front left
|
||||
|
||||
#define PWM_FREQUENCY 78000
|
||||
#define PWM_RESOLUTION 10
|
||||
#define PWM_STOP 0
|
||||
#define PWM_MIN 0
|
||||
#define PWM_MAX 1000000 / PWM_FREQUENCY
|
||||
|
||||
// Motors array indexes:
|
||||
const int MOTOR_REAR_LEFT = 0;
|
||||
const int MOTOR_REAR_RIGHT = 1;
|
||||
const int MOTOR_FRONT_RIGHT = 2;
|
||||
const int MOTOR_FRONT_LEFT = 3;
|
||||
#define PWM_FREQUENCY 200
|
||||
#define PWM_RESOLUTION 8
|
||||
|
||||
void setupMotors() {
|
||||
print("Setup Motors\n");
|
||||
Serial.println("Setup Motors");
|
||||
|
||||
// configure pins
|
||||
ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
||||
@@ -33,35 +23,17 @@ void setupMotors() {
|
||||
ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
||||
|
||||
sendMotors();
|
||||
print("Motors initialized\n");
|
||||
Serial.println("Motors initialized");
|
||||
}
|
||||
|
||||
int getDutyCycle(float value) {
|
||||
value = constrain(value, 0, 1);
|
||||
float pwm = mapff(value, 0, 1, PWM_MIN, PWM_MAX);
|
||||
if (value == 0) pwm = PWM_STOP;
|
||||
float duty = mapff(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
|
||||
return round(duty);
|
||||
uint8_t signalToDutyCycle(float control) {
|
||||
float duty = mapff(control, 0, 1, 0, (1 << PWM_RESOLUTION) - 1);
|
||||
return round(constrain(duty, 0, (1 << PWM_RESOLUTION) - 1));
|
||||
}
|
||||
|
||||
void sendMotors() {
|
||||
ledcWrite(MOTOR_0_PIN, getDutyCycle(motors[0]));
|
||||
ledcWrite(MOTOR_1_PIN, getDutyCycle(motors[1]));
|
||||
ledcWrite(MOTOR_2_PIN, getDutyCycle(motors[2]));
|
||||
ledcWrite(MOTOR_3_PIN, getDutyCycle(motors[3]));
|
||||
}
|
||||
|
||||
bool motorsActive() {
|
||||
return motors[0] != 0 || motors[1] != 0 || motors[2] != 0 || motors[3] != 0;
|
||||
}
|
||||
|
||||
void testMotor(int n) {
|
||||
print("Testing motor %d\n", n);
|
||||
motors[n] = 1;
|
||||
delay(50); // ESP32 may need to wait until the end of the current cycle to change duty https://github.com/espressif/arduino-esp32/issues/5306
|
||||
sendMotors();
|
||||
pause(3);
|
||||
motors[n] = 0;
|
||||
sendMotors();
|
||||
print("Done\n");
|
||||
ledcWrite(MOTOR_0_PIN, signalToDutyCycle(motors[0]));
|
||||
ledcWrite(MOTOR_1_PIN, signalToDutyCycle(motors[1]));
|
||||
ledcWrite(MOTOR_2_PIN, signalToDutyCycle(motors[2]));
|
||||
ledcWrite(MOTOR_3_PIN, signalToDutyCycle(motors[3]));
|
||||
}
|
||||
|
||||
@@ -1,19 +1,15 @@
|
||||
// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// Parameters storage in flash memory
|
||||
#pragma once
|
||||
|
||||
#include <Preferences.h>
|
||||
#include <vector>
|
||||
|
||||
extern float channelZero[16];
|
||||
extern float channelMax[16];
|
||||
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
||||
extern float mavlinkControlScale;
|
||||
extern float channelNeutral[RC_CHANNELS];
|
||||
extern float channelMax[RC_CHANNELS];
|
||||
|
||||
Preferences storage;
|
||||
|
||||
struct Parameter {
|
||||
const char *name; // max length is 16
|
||||
const char *name;
|
||||
float *variable;
|
||||
float value; // cache
|
||||
};
|
||||
@@ -38,10 +34,6 @@ Parameter parameters[] = {
|
||||
{"PITCH_I", &pitchPID.i},
|
||||
{"PITCH_D", &pitchPID.d},
|
||||
{"YAW_P", &yawPID.p},
|
||||
{"PITCHRATE_MAX", &maxRate.y},
|
||||
{"ROLLRATE_MAX", &maxRate.x},
|
||||
{"YAWRATE_MAX", &maxRate.z},
|
||||
{"TILT_MAX", &tiltMax},
|
||||
// imu
|
||||
{"ACC_BIAS_X", &accBias.x},
|
||||
{"ACC_BIAS_Y", &accBias.y},
|
||||
@@ -49,15 +41,18 @@ Parameter parameters[] = {
|
||||
{"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_ZERO_0", &channelZero[0]},
|
||||
{"RC_ZERO_1", &channelZero[1]},
|
||||
{"RC_ZERO_2", &channelZero[2]},
|
||||
{"RC_ZERO_3", &channelZero[3]},
|
||||
{"RC_ZERO_4", &channelZero[4]},
|
||||
{"RC_ZERO_5", &channelZero[5]},
|
||||
{"RC_ZERO_6", &channelZero[6]},
|
||||
{"RC_ZERO_7", &channelZero[7]},
|
||||
{"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]},
|
||||
@@ -65,17 +60,7 @@ Parameter parameters[] = {
|
||||
{"RC_MAX_4", &channelMax[4]},
|
||||
{"RC_MAX_5", &channelMax[5]},
|
||||
{"RC_MAX_6", &channelMax[6]},
|
||||
{"RC_MAX_7", &channelMax[7]},
|
||||
{"RC_ROLL", &rollChannel},
|
||||
{"RC_PITCH", &pitchChannel},
|
||||
{"RC_THROTTLE", &throttleChannel},
|
||||
{"RC_YAW", &yawChannel},
|
||||
{"RC_ARMED", &armedChannel},
|
||||
{"RC_MODE", &modeChannel},
|
||||
#if WIFI_ENABLED
|
||||
// MAVLink
|
||||
{"MAV_CTRL_SCALE", &mavlinkControlScale},
|
||||
#endif
|
||||
{"RC_MAX_7", &channelMax[7]}
|
||||
};
|
||||
|
||||
void setupParameters() {
|
||||
@@ -83,6 +68,7 @@ void setupParameters() {
|
||||
// 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);
|
||||
@@ -95,12 +81,10 @@ int parametersCount() {
|
||||
}
|
||||
|
||||
const char *getParameterName(int index) {
|
||||
if (index < 0 || index >= parametersCount()) return "";
|
||||
return parameters[index].name;
|
||||
}
|
||||
|
||||
float getParameter(int index) {
|
||||
if (index < 0 || index >= parametersCount()) return NAN;
|
||||
return *parameters[index].variable;
|
||||
}
|
||||
|
||||
@@ -123,11 +107,11 @@ bool setParameter(const char *name, const float value) {
|
||||
return false;
|
||||
}
|
||||
|
||||
void syncParameters() {
|
||||
static double lastSync = 0;
|
||||
if (t - lastSync < 1) return; // sync once per second
|
||||
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
|
||||
lastSync = t;
|
||||
lastFlush = t;
|
||||
|
||||
for (auto ¶meter : parameters) {
|
||||
if (parameter.value == *parameter.variable) continue;
|
||||
@@ -139,7 +123,7 @@ void syncParameters() {
|
||||
|
||||
void printParameters() {
|
||||
for (auto ¶meter : parameters) {
|
||||
print("%s = %g\n", parameter.name, *parameter.variable);
|
||||
Serial.printf("%s = %g\n", parameter.name, *parameter.variable);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -15,22 +15,22 @@ public:
|
||||
|
||||
Quaternion(float w, float x, float y, float z): w(w), x(x), y(y), z(z) {};
|
||||
|
||||
static Quaternion fromAxisAngle(const Vector& axis, float angle) {
|
||||
static Quaternion fromAxisAngle(float a, float b, float c, float angle) {
|
||||
float halfAngle = angle * 0.5;
|
||||
float sin2 = sin(halfAngle);
|
||||
float cos2 = cos(halfAngle);
|
||||
float sinNorm = sin2 / axis.norm();
|
||||
return Quaternion(cos2, axis.x * sinNorm, axis.y * sinNorm, axis.z * sinNorm);
|
||||
float sinNorm = sin2 / sqrt(a * a + b * b + c * c);
|
||||
return Quaternion(cos2, a * sinNorm, b * sinNorm, c * sinNorm);
|
||||
}
|
||||
|
||||
static Quaternion fromRotationVector(const Vector& rotation) {
|
||||
if (rotation.zero()) {
|
||||
static Quaternion fromAngularRates(const Vector& rates) {
|
||||
if (rates.zero()) {
|
||||
return Quaternion();
|
||||
}
|
||||
return Quaternion::fromAxisAngle(rotation, rotation.norm());
|
||||
return Quaternion::fromAxisAngle(rates.x, rates.y, rates.z, rates.norm());
|
||||
}
|
||||
|
||||
static Quaternion fromEuler(const Vector& euler) {
|
||||
static Quaternion fromEulerZYX(const Vector& euler) {
|
||||
float cx = cos(euler.x / 2);
|
||||
float cy = cos(euler.y / 2);
|
||||
float cz = cos(euler.z / 2);
|
||||
@@ -60,53 +60,14 @@ public:
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool finite() const {
|
||||
return isfinite(w) && isfinite(x) && isfinite(y) && isfinite(z);
|
||||
}
|
||||
|
||||
bool valid() const {
|
||||
return finite();
|
||||
}
|
||||
|
||||
bool invalid() const {
|
||||
return !valid();
|
||||
}
|
||||
|
||||
void invalidate() {
|
||||
w = NAN;
|
||||
x = NAN;
|
||||
y = NAN;
|
||||
z = NAN;
|
||||
}
|
||||
|
||||
float norm() const {
|
||||
return sqrt(w * w + x * x + y * y + z * z);
|
||||
}
|
||||
|
||||
void normalize() {
|
||||
float n = norm();
|
||||
w /= n;
|
||||
x /= n;
|
||||
y /= n;
|
||||
z /= n;
|
||||
}
|
||||
|
||||
void toAxisAngle(Vector& axis, float& angle) const {
|
||||
void toAxisAngle(float& a, float& b, float& c, float& angle) {
|
||||
angle = acos(w) * 2;
|
||||
axis.x = x / sin(angle / 2);
|
||||
axis.y = y / sin(angle / 2);
|
||||
axis.z = z / sin(angle / 2);
|
||||
a = x / sin(angle / 2);
|
||||
b = y / sin(angle / 2);
|
||||
c = z / sin(angle / 2);
|
||||
}
|
||||
|
||||
Vector toRotationVector() const {
|
||||
if (w == 1 && x == 0 && y == 0 && z == 0) return Vector(0, 0, 0); // neutral quaternion
|
||||
float angle;
|
||||
Vector axis;
|
||||
toAxisAngle(axis, angle);
|
||||
return angle * axis;
|
||||
}
|
||||
|
||||
Vector toEuler() const {
|
||||
Vector toEulerZYX() const {
|
||||
// https://github.com/ros/geometry2/blob/589caf083cae9d8fae7effdb910454b4681b9ec1/tf2/include/tf2/impl/utils.h#L87
|
||||
Vector euler;
|
||||
float sqx = x * x;
|
||||
@@ -151,12 +112,21 @@ public:
|
||||
|
||||
void setYaw(float yaw) {
|
||||
// TODO: optimize?
|
||||
Vector euler = toEuler();
|
||||
Vector euler = toEulerZYX();
|
||||
euler.z = yaw;
|
||||
(*this) = Quaternion::fromEuler(euler);
|
||||
(*this) = Quaternion::fromEulerZYX(euler);
|
||||
}
|
||||
|
||||
Quaternion operator * (const Quaternion& q) const {
|
||||
Quaternion& operator *= (const Quaternion& q) {
|
||||
Quaternion ret(
|
||||
w * q.w - x * q.x - y * q.y - z * q.z,
|
||||
w * q.x + x * q.w + y * q.z - z * q.y,
|
||||
w * q.y + y * q.w + z * q.x - x * q.z,
|
||||
w * q.z + z * q.w + x * q.y - y * q.x);
|
||||
return (*this = ret);
|
||||
}
|
||||
|
||||
Quaternion operator * (const Quaternion& q) {
|
||||
return Quaternion(
|
||||
w * q.w - x * q.x - y * q.y - z * q.z,
|
||||
w * q.x + x * q.w + y * q.z - z * q.y,
|
||||
@@ -164,14 +134,6 @@ public:
|
||||
w * q.z + z * q.w + x * q.y - y * q.x);
|
||||
}
|
||||
|
||||
bool operator == (const Quaternion& q) const {
|
||||
return w == q.w && x == q.x && y == q.y && z == q.z;
|
||||
}
|
||||
|
||||
bool operator != (const Quaternion& q) const {
|
||||
return !(*this == q);
|
||||
}
|
||||
|
||||
Quaternion inversed() const {
|
||||
float normSqInv = 1 / (w * w + x * x + y * y + z * z);
|
||||
return Quaternion(
|
||||
@@ -181,39 +143,37 @@ public:
|
||||
-z * normSqInv);
|
||||
}
|
||||
|
||||
Vector conjugate(const Vector& v) const {
|
||||
float norm() const {
|
||||
return sqrt(w * w + x * x + y * y + z * z);
|
||||
}
|
||||
|
||||
void normalize() {
|
||||
float n = norm();
|
||||
w /= n;
|
||||
x /= n;
|
||||
y /= n;
|
||||
z /= n;
|
||||
}
|
||||
|
||||
Vector conjugate(const Vector& v) {
|
||||
Quaternion qv(0, v.x, v.y, v.z);
|
||||
Quaternion res = (*this) * qv * inversed();
|
||||
return Vector(res.x, res.y, res.z);
|
||||
}
|
||||
|
||||
Vector conjugateInversed(const Vector& v) const {
|
||||
Vector conjugateInversed(const Vector& v) {
|
||||
Quaternion qv(0, v.x, v.y, v.z);
|
||||
Quaternion res = inversed() * qv * (*this);
|
||||
return Vector(res.x, res.y, res.z);
|
||||
}
|
||||
|
||||
// Rotate quaternion by quaternion
|
||||
static Quaternion rotate(const Quaternion& a, const Quaternion& b, const bool normalize = true) {
|
||||
Quaternion rotated = a * b;
|
||||
if (normalize) {
|
||||
rotated.normalize();
|
||||
}
|
||||
return rotated;
|
||||
}
|
||||
|
||||
// Rotate vector by quaternion
|
||||
static Vector rotateVector(const Vector& v, const Quaternion& q) {
|
||||
return q.conjugateInversed(v);
|
||||
inline Vector rotate(const Vector& v) {
|
||||
return conjugateInversed(v);
|
||||
}
|
||||
|
||||
// Quaternion between two quaternions a and b
|
||||
static Quaternion between(const Quaternion& a, const Quaternion& b, const bool normalize = true) {
|
||||
Quaternion q = a * b.inversed();
|
||||
if (normalize) {
|
||||
q.normalize();
|
||||
}
|
||||
return q;
|
||||
inline bool finite() const {
|
||||
return isfinite(w) && isfinite(x) && isfinite(y) && isfinite(z);
|
||||
}
|
||||
|
||||
size_t printTo(Print& p) const {
|
||||
|
||||
96
flix/rc.ino
@@ -4,96 +4,52 @@
|
||||
// Work with the RC receiver
|
||||
|
||||
#include <SBUS.h>
|
||||
#include "util.h"
|
||||
|
||||
float channelNeutral[RC_CHANNELS] = {NAN}; // first element NAN means not calibrated
|
||||
float channelMax[RC_CHANNELS];
|
||||
|
||||
SBUS RC(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
|
||||
|
||||
uint16_t channels[16]; // raw rc channels
|
||||
double controlTime; // time of the last controls update
|
||||
float channelZero[16]; // calibration zero values
|
||||
float channelMax[16]; // calibration max values
|
||||
|
||||
// Channels mapping (using float to store in parameters):
|
||||
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, armedChannel = NAN, modeChannel = NAN;
|
||||
|
||||
void setupRC() {
|
||||
print("Setup RC\n");
|
||||
Serial.println("Setup RC");
|
||||
RC.begin();
|
||||
}
|
||||
|
||||
bool readRC() {
|
||||
void readRC() {
|
||||
if (RC.read()) {
|
||||
SBUSData data = RC.data();
|
||||
for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data
|
||||
memcpy(channels, data.ch, sizeof(channels)); // copy channels data
|
||||
normalizeRC();
|
||||
controlTime = t;
|
||||
return true;
|
||||
controlsTime = t;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void normalizeRC() {
|
||||
float controls[16];
|
||||
for (int i = 0; i < 16; i++) {
|
||||
controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1);
|
||||
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);
|
||||
}
|
||||
// Update control values
|
||||
controlRoll = rollChannel >= 0 ? controls[(int)rollChannel] : NAN;
|
||||
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN;
|
||||
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN;
|
||||
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN;
|
||||
controlArmed = armedChannel >= 0 ? controls[(int)armedChannel] : NAN;
|
||||
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN;
|
||||
}
|
||||
|
||||
void calibrateRC() {
|
||||
uint16_t zero[16];
|
||||
uint16_t center[16];
|
||||
uint16_t max[16];
|
||||
print("1/9 Calibrating RC: put all switches to default positions [3 sec]\n");
|
||||
pause(3);
|
||||
calibrateRCChannel(NULL, zero, zero, "2/9 Move sticks [3 sec]\n... ...\n... .o.\n.o. ...\n");
|
||||
calibrateRCChannel(NULL, center, center, "3/9 Move sticks [3 sec]\n... ...\n.o. .o.\n... ...\n");
|
||||
calibrateRCChannel(&throttleChannel, zero, max, "4/9 Move sticks [3 sec]\n.o. ...\n... .o.\n... ...\n");
|
||||
calibrateRCChannel(&yawChannel, center, max, "5/9 Move sticks [3 sec]\n... ...\n..o .o.\n... ...\n");
|
||||
calibrateRCChannel(&pitchChannel, zero, max, "6/9 Move sticks [3 sec]\n... .o.\n... ...\n.o. ...\n");
|
||||
calibrateRCChannel(&rollChannel, zero, max, "7/9 Move sticks [3 sec]\n... ...\n... ..o\n.o. ...\n");
|
||||
calibrateRCChannel(&armedChannel, zero, max, "8/9 Switch to armed [3 sec]\n");
|
||||
calibrateRCChannel(&modeChannel, zero, max, "9/9 Disarm and switch mode to max [3 sec]\n");
|
||||
printRCCalibration();
|
||||
}
|
||||
|
||||
void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const char *str) {
|
||||
print("%s", str);
|
||||
pause(3);
|
||||
for (int i = 0; i < 30; i++) readRC(); // try update 30 times max
|
||||
memcpy(out, channels, sizeof(channels));
|
||||
|
||||
if (channel == NULL) return; // no channel to calibrate
|
||||
|
||||
// Find channel that changed the most between in and out
|
||||
int ch = -1, diff = 0;
|
||||
for (int i = 0; i < 16; i++) {
|
||||
if (abs(out[i] - in[i]) > diff) {
|
||||
ch = i;
|
||||
diff = abs(out[i] - in[i]);
|
||||
}
|
||||
Serial.println("Calibrate RC: move all sticks to maximum positions within 4 seconds");
|
||||
Serial.println("··o ··o\n··· ···\n··· ···");
|
||||
delay(4000);
|
||||
for (int i = 0; i < 30; i++) readRC(); // ensure the values are updated
|
||||
for (int i = 0; i < RC_CHANNELS; i++) {
|
||||
channelMax[i] = channels[i];
|
||||
}
|
||||
if (ch >= 0 && diff > 10) { // difference threshold is 10
|
||||
*channel = ch;
|
||||
channelZero[ch] = in[ch];
|
||||
channelMax[ch] = out[ch];
|
||||
} else {
|
||||
*channel = NAN;
|
||||
Serial.println("Calibrate RC: move all sticks to neutral positions within 4 seconds");
|
||||
Serial.println("··· ···\n··· ·o·\n·o· ···");
|
||||
delay(4000);
|
||||
for (int i = 0; i < 30; i++) readRC(); // ensure the values are updated
|
||||
for (int i = 0; i < RC_CHANNELS; i++) {
|
||||
channelNeutral[i] = channels[i];
|
||||
}
|
||||
printRCCal();
|
||||
}
|
||||
|
||||
void printRCCalibration() {
|
||||
print("Control Ch Zero Max\n");
|
||||
print("Roll %-7g%-7g%-7g\n", rollChannel, rollChannel >= 0 ? channelZero[(int)rollChannel] : NAN, rollChannel >= 0 ? channelMax[(int)rollChannel] : NAN);
|
||||
print("Pitch %-7g%-7g%-7g\n", pitchChannel, pitchChannel >= 0 ? channelZero[(int)pitchChannel] : NAN, pitchChannel >= 0 ? channelMax[(int)pitchChannel] : NAN);
|
||||
print("Yaw %-7g%-7g%-7g\n", yawChannel, yawChannel >= 0 ? channelZero[(int)yawChannel] : NAN, yawChannel >= 0 ? channelMax[(int)yawChannel] : NAN);
|
||||
print("Throttle %-7g%-7g%-7g\n", throttleChannel, throttleChannel >= 0 ? channelZero[(int)throttleChannel] : NAN, throttleChannel >= 0 ? channelMax[(int)throttleChannel] : NAN);
|
||||
print("Armed %-7g%-7g%-7g\n", armedChannel, armedChannel >= 0 ? channelZero[(int)armedChannel] : NAN, armedChannel >= 0 ? channelMax[(int)armedChannel] : NAN);
|
||||
print("Mode %-7g%-7g%-7g\n", modeChannel, modeChannel >= 0 ? channelZero[(int)modeChannel] : NAN, modeChannel >= 0 ? channelMax[(int)modeChannel] : NAN);
|
||||
void printRCCal() {
|
||||
printArray(channelNeutral, RC_CHANNELS);
|
||||
printArray(channelMax, RC_CHANNELS);
|
||||
}
|
||||
|
||||