20 Commits

Author SHA1 Message Date
Oleg Kalachev
073c860b90 Calibrate gyro continuously when landed and stationary 2024-12-24 22:19:54 +03:00
Oleg Kalachev
fd30027ea4 Support AUTOPILOT_VERSION message request to make qgc connection faster
Don't have to wait until the request is timed out.
2024-12-23 17:59:35 +03:00
Oleg Kalachev
6f190295cf Fix building article regarding new parameters subsystem 2024-12-23 13:59:44 +03:00
Oleg Kalachev
ae349fb73c Implement parameters subsystem
* Unified parameters storage.
* Store parameters in flash on the hardware.
* Store parameters in text file in simulation.
* Work with parameters in command line.
* Support parameters in MAVLink for working with parameters in QGC.
2024-12-23 13:00:02 +03:00
Oleg Kalachev
28f6cfff60 Fix SBUS simulation logic
Don't consider zero values from not connected joystick
2024-12-23 04:04:00 +03:00
Oleg Kalachev
7533a9cbfa Move ONE_G definition to flix.ino 2024-12-23 02:37:03 +03:00
Oleg Kalachev
3cc3014ca0 Improve logic of passing channels data in simulated SBUS
Return the data the same way as on the real drone without touching channels global vairable
2024-12-23 02:04:22 +03:00
Oleg Kalachev
b6286a50b2 Minor change 2024-12-23 02:01:55 +03:00
Oleg Kalachev
4f2cf0c0b1 Don't let throttle be less than 0 in failsafe 2024-12-23 01:32:25 +03:00
Oleg Kalachev
f06a9301df Add notice on removing props in motor test commands in help 2024-12-23 01:14:05 +03:00
Oleg Kalachev
41cde3261a Minor troubleshooting article fix 2024-12-21 13:53:04 +03:00
Oleg Kalachev
f54da5bf42 Add CLI command for rebooting the drone 2024-12-20 20:59:59 +03:00
Oleg Kalachev
d01d5b7ecb Improve Markdown linting
* Move .markdownlint to the root so it applies to the main readme.
* Improve .markdownlint, enable proper names checks.
* Use markdownlint-cli2 instead of markdownlint-cli as it's more compatible with VSCode extension.
2024-12-17 17:16:19 +03:00
Oleg Kalachev
0608765347 Add link to textbook website to readme 2024-12-17 11:27:14 +03:00
Oleg Kalachev
b70d16c1f7 Update deploy-pages version to fix website deploy 2024-12-16 12:13:36 +03:00
Oleg Kalachev
f7253bed70 Temporarily disable macOS simulation build 2024-12-16 11:59:49 +03:00
Oleg Kalachev
9957205d8f Fix website deploy 2024-12-16 11:58:35 +03:00
Oleg Kalachev
8440ddd3ee Create book and deploy it to the website (#6)
* Create book structure.
* Add workflow for linting the markdown using markdownlint.
* Add workflow for building the book with mdBook and deploying to the website.
* Restyle mdBook and support GitHub-style alerts.
* Add images zooming.
* Add index, firmware structure and gyroscope articles.
2024-12-16 11:53:43 +03:00
Oleg Kalachev
66ba9518ae Minor readme fix 2024-12-16 11:30:53 +03:00
Oleg Kalachev
d273b77ce2 Bring back macOS simulation build in Actions 2024-12-12 09:07:09 +03:00
61 changed files with 2321 additions and 429 deletions

View File

@@ -15,8 +15,6 @@ jobs:
run: curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=/usr/local/bin sh
- name: Build firmware
run: make
- name: Build firmware without Wi-Fi
run: sed -i 's/^#define WIFI_ENABLED 1$/#define WIFI_ENABLED 0/' flix/flix.ino && make
- name: Check c_cpp_properties.json
run: tools/check_c_cpp_properties.py
@@ -45,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
@@ -56,7 +54,7 @@ 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

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

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

67
.markdownlint.json Normal file
View File

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

View File

@@ -5,18 +5,18 @@
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"~/.arduino15/packages/esp32/hardware/esp32/3.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,9 +28,11 @@
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.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": [
@@ -50,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",
@@ -74,9 +76,11 @@
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.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": [
@@ -98,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",
@@ -120,9 +124,11 @@
"${workspaceFolder}/flix/motors.ino",
"${workspaceFolder}/flix/rc.ino",
"${workspaceFolder}/flix/time.ino",
"${workspaceFolder}/flix/wifi.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": [

View File

@@ -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"
],

View File

@@ -13,10 +13,10 @@ monitor:
dependencies .dependencies:
arduino-cli core update-index --config-file arduino-cli.yaml
arduino-cli core install esp32:esp32@3.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

155
README.md
View File

@@ -1,7 +1,156 @@
# Flix
Minimal **Flix** quadcopter firmware implementation for the [book](https://quadcopter.dev).
**Flix** (*flight + X*) — making an open source ESP32-based quadcopter from scratch.
See the full code and documentation in the main branch: https://github.com/okalachev/flix.
<table>
<tr>
<td align=center><strong>Version 1</strong> (3D-printed frame)</td>
<td align=center><strong>Version 0</strong></td>
</tr>
<tr>
<td><img src="docs/img/flix1.jpg" width=500 alt="Flix quadcopter"></td>
<td><img src="docs/img/flix.jpg" width=500 alt="Flix quadcopter"></td>
</tr>
</table>
<img src="docs/img/flix1.jpg" width=500 alt="Flix quadcopter">
## Features
* 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 (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>
Version 1 test flight: https://t.me/opensourcequadcopter/42.
<a href="https://t.me/opensourcequadcopter/42"><img width=500 src="docs/img/flight-video.jpg"></a>
## Simulation
The simulator is implemented using Gazebo and runs the original Arduino code:
<img src="docs/img/simulator.png" width=500 alt="Flix simulator">
See [instructions on running the simulation](docs/build.md).
## Components (version 1)
|Type|Part|Image|Quantity|
|-|-|:-:|:-:|
|Microcontroller board|ESP32 Mini|<img src="docs/img/esp32.jpg" width=100>|1|
|IMU (and barometer²) board|GY91 (or other MPU9250/MPU6500 board), ICM20948³|<img src="docs/img/gy-91.jpg" width=90 align=center><img src="docs/img/icm-20948.jpg" width=100>|1|
|Motor|8520 3.7V brushed motor (**shaft 0.8mm!**)|<img src="docs/img/motor.jpeg" width=100>|4|
|Propeller|Hubsan 55 mm|<img src="docs/img/prop.jpg" width=100>|4|
|MOSFET (transistor)|100N03A or [analog](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4|
|Pull-down resistor|10 kΩ|<img src="docs/img/resistor10k.jpg" width=100>|4|
|3.7V Li-Po battery|LW 952540 (or any compatible by the size)|<img src="docs/img/battery.jpg" width=100>|1|
|Li-Po Battery charger|Any|<img src="docs/img/charger.jpg" width=100>|1|
|Screws for IMU board mounting|M3x5|<img src="docs/img/screw-m3.jpg" width=100>|2|
|Screws for frame assembly|M1.4x5|<img src="docs/img/screw-m1.4.jpg" height=30 align=center>|4|
|Frame bottom part|3D printed⁴:<br>[`flix-frame.stl`](docs/assets/flix-frame.stl) [`flix-frame.step`](docs/assets/flix-frame.step)|<img src="docs/img/frame1.jpg" width=100>|1|
|Frame top part|3D printed:<br>[`esp32-holder.stl`](docs/assets/esp32-holder.stl) [`esp32-holder.step`](docs/assets/esp32-holder.step)|<img src="docs/img/esp32-holder.jpg" width=100>|1|
|Washer for IMU board mounting|3D printed:<br>[`washer-m3.stl`](docs/assets/washer-m3.stl) [`washer-m3.step`](docs/assets/washer-m3.step)|<img src="docs/img/washer-m3.jpg" width=100>|1|
|*RC transmitter (optional)*|*KINGKONG TINY X8 or other⁵*|<img src="docs/img/tx.jpg" width=100>|1|
|*RC receiver (optional)*|*DF500 or other⁵*|<img src="docs/img/rx.jpg" width=100>|1|
|Wires|28 AWG recommended|<img src="docs/img/wire-28awg.jpg" width=100>||
|Tape, double-sided tape||||
*² — barometer is not used for now.*<br>
*³ — change `MPU9250` to `ICM20948` in `imu.ino` file if using ICM-20948 board.*<br>
*⁴ — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*<br>
*⁵ — you may use any transmitter-receiver pair with SBUS interface.*
Tools required for assembly:
* 3D printer.
* Soldering iron.
* Solder wire (with flux).
* Screwdrivers.
* Multimeter.
Feel free to modify the design and or code, and create your own improved versions of Flix! Send your results to the [official Telegram chat](https://t.me/opensourcequadcopterchat), or directly to the author ([E-mail](mailto:okalachev@gmail.com), [Telegram](https://t.me/okalachev)).
## Schematics (version 1)
### Simplified connection diagram
<img src="docs/img/schematics1.svg" width=800 alt="Flix version 1 schematics">
Motor connection scheme:
<img src="docs/img/mosfet-connection.png" height=400 alt="MOSFET connection scheme">
Complete diagram is Work-in-Progress.
### Notes
* Power ESP32 Mini with Li-Po battery using VCC (+) and GND (-) pins.
* Connect the IMU board to the ESP32 Mini using VSPI, power it using 3.3V and GND pins:
|IMU pin|ESP32 pin|
|-|-|
|GND|GND|
|3.3V|3.3V|
|SCL *(SCK)*|SVP (GPIO18)|
|SDA *(MOSI)*|GPIO23|
|SAO *(MISO)*|GPIO19|
|NCS|GPIO5|
* Solder pull-down resistors to the MOSFETs.
* Connect the motors to the ESP32 Mini using MOSFETs, by following scheme:
|Motor|Position|Direction|Wires|GPIO|
|-|-|-|-|-|
|Motor 0|Rear left|Counter-clockwise|Black & White|GPIO12|
|Motor 1|Rear right|Clockwise|Blue & Red|GPIO13|
|Motor 2|Front right|Counter-clockwise|Black & White|GPIO14|
|Motor 3|Front left|Clockwise|Blue & Red|GPIO15|
Counter-clockwise motors have black and white wires and clockwise motors have blue and red wires.
* Optionally connect the RC receiver to the ESP32's UART2:
|Receiver pin|ESP32 pin|
|-|-|
|GND|GND|
|VIN|VC (or 3.3V depending on the receiver)|
|Signal|GPIO4⁶|
*⁶ — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.*
### IMU placement
Default IMU orientation in the code is **LFD** (Left-Forward-Down):
<img src="docs/img/gy91-lfd.svg" width=400 alt="GY-91 axes">
In case of using other IMU orientation, modify the `rotateIMU` function in the `imu.ino` file.
See [FlixPeriph documentation](https://github.com/okalachev/flixperiph?tab=readme-ov-file#imu-axes-orientation) to learn axis orientation of other IMU boards.
## Version 0
See the information on the obsolete version 0 in the [corresponding article](docs/version0.md).
## Materials
Subscribe to the Telegram channel on developing the drone and the flight controller (in Russian): https://t.me/opensourcequadcopter.
Join the official Telegram chat: https://t.me/opensourcequadcopterchat.
Detailed article on Habr.com about the development of the drone (in Russian): https://habr.com/ru/articles/814127/.

10
docs/Makefile Normal file
View File

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

31
docs/alerts.py Normal file
View File

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

110
docs/book.css Normal file
View File

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

22
docs/book.toml Normal file
View File

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

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

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

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

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

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

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

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

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

1
docs/book/img Symbolic link
View File

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

View File

@@ -9,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:
@@ -96,25 +96,22 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you h
1. Connect your USB remote control to the machine running the simulator.
2. Run the simulation.
3. Calibrate the RC using `cr` command in the command line interface and stop the simulation.
4. Copy the calibration results to the source code (`gazebo/joystick.h`).
5. Run the simulation again.
6. Use the USB remote control to fly the drone!
3. Calibrate the RC using `cr` command in the command line interface.
4. Run the simulation again.
5. Use the USB remote control to fly the drone!
## Firmware
### Arduino IDE (Windows, Linux, macOS)
1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended).
2. 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)
@@ -145,8 +142,7 @@ See other available Make commands in the [Makefile](../Makefile).
Before flight you need to calibrate the accelerometer:
1. Open Serial Monitor in Arduino IDE (use use `make monitor` command in the command line).
2. Type `ca` command there.
3. Copy calibration results to the source code (`flix/imu.ino`).
2. Type `ca` command there and follow the instructions.
#### Control with smartphone
@@ -162,8 +158,7 @@ Before flight you need to calibrate the accelerometer:
Before flight using remote control, you need to calibrate it:
1. Open Serial Monitor in Arduino IDE (use use `make monitor` command in the command line).
2. Type `cr` command there.
3. Copy calibration results to the source code (`flix/rc.ino`).
2. Type `cr` command there and follow the instructions.
Then you can use your remote control to fly the drone!

View File

@@ -12,8 +12,8 @@ The main loop is running at 1000 Hz. All the dataflow is happening through globa
* `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, normalized to [0, 1] range; reverse rotation is possible.
* `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

BIN
docs/img/flixperiph.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 115 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 114 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 105 KiB

BIN
docs/img/gyroscope.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 36 KiB

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

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

After

Width:  |  Height:  |  Size: 2.8 KiB

BIN
docs/img/mpu9250.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 16 KiB

7
docs/js.js Normal file
View File

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

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

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

33
docs/troubleshooting.md Normal file
View File

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

30
docs/version0.md Normal file
View File

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

31
docs/zoom.css Normal file
View File

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

281
docs/zoom.js Normal file
View File

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

View File

@@ -6,9 +6,8 @@
#include "pid.h"
#include "vector.h"
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern float loopRate;
extern uint16_t channels[16];
extern PID rollRatePID, pitchRatePID, yawRatePID, rollPID, pitchPID;
extern LowPassFilter<Vector> ratesFilter;
const char* motd =
"\nWelcome to\n"
@@ -20,6 +19,10 @@ const char* motd =
"|__| |_______||__| /__/ \\__\\\n\n"
"Commands:\n\n"
"help - show help\n"
"p - show all parameters\n"
"p <name> - show parameter\n"
"p <name> <value> - set parameter\n"
"preset - reset parameters\n"
"ps - show pitch/roll/yaw\n"
"psq - show attitude quaternion\n"
"imu - show IMU data\n"
@@ -30,13 +33,27 @@ const char* motd =
"cg - calibrate gyro\n"
"ca - calibrate accel\n"
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
"reset - reset drone's state\n";
"reset - reset drone's state\n"
"reboot - reboot the drone\n";
void doCommand(const String& command) {
void doCommand(String& command, String& arg0, String& arg1) {
if (command == "help" || command == "motd") {
Serial.println(motd);
} else if (command == "p" && arg0 == "") {
printParameters();
} else if (command == "p" && arg0 != "" && arg1 == "") {
Serial.printf("%s = %g\n", arg0.c_str(), getParameter(arg0.c_str()));
} else if (command == "p") {
bool success = setParameter(arg0.c_str(), arg1.toFloat());
if (success) {
Serial.printf("%s = %g\n", arg0.c_str(), arg1.toFloat());
} else {
Serial.printf("Parameter not found: %s\n", arg0.c_str());
}
} else if (command == "preset") {
resetParameters();
} else if (command == "ps") {
Vector a = attitude.toEuler();
Vector a = attitude.toEulerZYX();
Serial.printf("roll: %f pitch: %f yaw: %f\n", a.x * RAD_TO_DEG, a.y * RAD_TO_DEG, a.z * RAD_TO_DEG);
} else if (command == "psq") {
Serial.printf("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
@@ -44,18 +61,18 @@ void doCommand(const String& command) {
printIMUInfo();
Serial.printf("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
Serial.printf("acc: %f %f %f\n", acc.x, acc.y, acc.z);
printIMUCalibration();
printIMUCal();
Serial.printf("rate: %f\n", loopRate);
} else if (command == "rc") {
Serial.printf("channels: ");
for (int i = 0; i < 16; i++) {
Serial.printf("%u ", channels[i]);
}
Serial.printf("\nroll: %g pitch: %g yaw: %g throttle: %g armed: %g mode: %g\n",
controlRoll, controlPitch, controlYaw, controlThrottle, controlArmed, controlMode);
Serial.printf("mode: %s\n", getModeName());
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") {
Serial.printf("front-right %f front-left %f rear-right %f rear-left %f\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();
@@ -66,15 +83,17 @@ void doCommand(const String& command) {
} 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);
cliTestMotor(MOTOR_REAR_LEFT);
} else if (command == "reset") {
attitude = Quaternion();
} else if (command == "reboot") {
ESP.restart();
} else if (command == "") {
// do nothing
} else {
@@ -82,22 +101,44 @@ void doCommand(const String& 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) {
Serial.printf("%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;
}

View File

@@ -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
@@ -30,8 +29,8 @@
#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
@@ -51,8 +50,6 @@ Vector ratesTarget;
Vector torqueTarget;
float thrustTarget;
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
void control() {
interpretRC();
failsafe();
@@ -69,39 +66,38 @@ void control() {
}
void interpretRC() {
armed = controlThrottle >= 0.05 && controlArmed >= 0.5;
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) {
if (controls[RC_CHANNEL_MODE] < 0.25) {
mode = STAB;
} else if (controlMode < 0.75) {
} else if (controls[RC_CHANNEL_MODE] < 0.75) {
mode = STAB;
} else {
mode = STAB;
}
thrustTarget = controlThrottle;
thrustTarget = controls[RC_CHANNEL_THROTTLE];
if (mode == ACRO) {
yawMode = YAW_RATE;
ratesTarget.x = controlRoll * ROLLRATE_MAX;
ratesTarget.y = controlPitch * PITCHRATE_MAX;
ratesTarget.z = -controlYaw * YAWRATE_MAX; // positive yaw stick means clockwise rotation in FLU
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 = controlYaw == 0 ? YAW : YAW_RATE;
yawMode = controls[RC_CHANNEL_YAW] == 0 ? YAW : YAW_RATE;
attitudeTarget = Quaternion::fromEuler(Vector(
controlRoll * TILT_MAX,
controlPitch * TILT_MAX,
attitudeTarget = Quaternion::fromEulerZYX(Vector(
controls[RC_CHANNEL_ROLL] * MAX_TILT,
controls[RC_CHANNEL_PITCH] * MAX_TILT,
attitudeTarget.getYaw()));
ratesTarget.z = -controlYaw * YAWRATE_MAX; // positive yaw stick means clockwise rotation in FLU
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(controlRoll, controlPitch, -controlYaw) * 0.01;
torqueTarget = Vector(controls[RC_CHANNEL_ROLL], controls[RC_CHANNEL_PITCH], -controls[RC_CHANNEL_YAW]) * 0.01;
}
if (yawMode == YAW_RATE || !motorsActive()) {
@@ -119,10 +115,10 @@ 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);
ratesTarget.y = pitchPID.update(error.y, dt);
@@ -166,6 +162,10 @@ void controlTorque() {
motors[3] = constrain(motors[3], 0, 1);
}
bool motorsActive() {
return motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0;
}
const char* getModeName() {
switch (mode) {
case MANUAL: return "MANUAL";

View File

@@ -6,9 +6,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,7 +22,8 @@ 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() {
@@ -31,12 +31,14 @@ void applyAcc() {
float accNorm = acc.norm();
bool landed = !motorsActive() && abs(accNorm - ONE_G) < ONE_G * 0.1f;
setLED(landed);
if (!landed) return;
// calculate accelerometer correction
Vector up = 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();
}

View File

@@ -6,21 +6,18 @@
#define RC_LOSS_TIMEOUT 0.2
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
extern float controlTime;
// RC loss failsafe
void failsafe() {
if (t - controlTime > RC_LOSS_TIMEOUT) {
if (t - controlsTime > RC_LOSS_TIMEOUT) {
descend();
}
}
// Smooth descend on RC lost
void descend() {
// Smooth descend on RC lost
mode = STAB;
controlRoll = 0;
controlPitch = 0;
controlYaw = 0;
controlThrottle -= dt / DESCEND_TIME;
if (controlThrottle < 0) controlThrottle = 0;
controls[RC_CHANNEL_ROLL] = 0;
controls[RC_CHANNEL_PITCH] = 0;
controls[RC_CHANNEL_YAW] = 0;
controls[RC_CHANNEL_THROTTLE] -= dt / DESCEND_TIME;
if (controls[RC_CHANNEL_THROTTLE] < 0) controls[RC_CHANNEL_THROTTLE] = 0;
}

View File

@@ -5,34 +5,55 @@
#include "vector.h"
#include "quaternion.h"
#include "util.h"
#define SERIAL_BAUDRATE 115200
#define WIFI_ENABLED 1
#define RC_CHANNELS 16
#define RC_CHANNEL_ROLL 0
#define RC_CHANNEL_PITCH 1
#define RC_CHANNEL_THROTTLE 2
#define RC_CHANNEL_YAW 3
#define RC_CHANNEL_ARMED 4
#define RC_CHANNEL_MODE 5
#define MOTOR_REAR_LEFT 0
#define MOTOR_REAR_RIGHT 1
#define MOTOR_FRONT_RIGHT 2
#define MOTOR_FRONT_LEFT 3
#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, controlArmed, controlMode; // pilot's inputs, range [-1, 1]
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
float motors[4]; // normalized motors thrust in range [0..1]
bool landed; // are we landed and stationary
float motors[4]; // normalized motors thrust in range [-1..1]
void setup() {
Serial.begin(SERIAL_BAUDRATE);
Serial.println("Initializing flix\n");
Serial.println("Initializing flix");
disableBrownOut();
setupParameters();
setupLED();
setupMotors();
setLED(true);
#if WIFI_ENABLED
#if WIFI_ENABLED == 1
setupWiFi();
#endif
setupIMU();
setupRC();
setLED(false);
Serial.println("Initializing complete\n");
Serial.println("Initializing complete");
}
void loop() {
@@ -42,9 +63,10 @@ void loop() {
estimate();
control();
sendMotors();
handleInput();
#if WIFI_ENABLED
parseInput();
#if WIFI_ENABLED == 1
processMavlink();
#endif
logData();
flushParameters();
}

View File

@@ -5,14 +5,12 @@
#include <SPI.h>
#include <MPU9250.h>
#include "util.h"
MPU9250 IMU(SPI);
// NOTE: use 'ca' command to calibrate the accelerometer and put the values here
Vector accBias;
Vector accScale(1, 1, 1);
Vector gyroBias;
Vector accScale(1, 1, 1);
void setupIMU() {
Serial.println("Setup IMU");
@@ -24,7 +22,7 @@ void setupIMU() {
}
}
configureIMU();
calibrateGyro();
// calibrateGyro();
}
void configureIMU() {
@@ -38,6 +36,7 @@ void readIMU() {
IMU.waitForData();
IMU.getGyro(gyro.x, gyro.y, gyro.z);
IMU.getAccel(acc.x, acc.y, acc.z);
calibrateGyroOnce();
// apply scale and bias
acc = (acc - accBias) / accScale;
gyro = gyro - gyroBias;
@@ -53,6 +52,13 @@ void rotateIMU(Vector& data) {
// Axes orientation for various boards: https://github.com/okalachev/flixperiph#imu-axes-orientation
}
void calibrateGyroOnce() {
if (!landed) return;
static float samples = 0; // overflows after 49 days at 1000 Hz
samples++;
gyroBias = gyroBias + (gyro - gyroBias) / samples; // running average
}
void calibrateGyro() {
const int samples = 1000;
Serial.println("Calibrating gyro, stand still");
@@ -66,7 +72,7 @@ void calibrateGyro() {
}
gyroBias = gyroBias / samples;
printIMUCalibration();
printIMUCal();
configureIMU();
}
@@ -75,27 +81,20 @@ void calibrateAccel() {
IMU.setAccelRange(IMU.ACCEL_RANGE_2G); // the most sensitive mode
Serial.setTimeout(60000);
Serial.print("1/6 Place level [enter] ");
Serial.readStringUntil('\n');
Serial.print("Place level [enter] "); Serial.readStringUntil('\n');
calibrateAccelOnce();
Serial.print("2/6 Place nose up [enter] ");
Serial.readStringUntil('\n');
Serial.print("Place nose up [enter] "); Serial.readStringUntil('\n');
calibrateAccelOnce();
Serial.print("3/6 Place nose down [enter] ");
Serial.readStringUntil('\n');
Serial.print("Place nose down [enter] "); Serial.readStringUntil('\n');
calibrateAccelOnce();
Serial.print("4/6 Place on right side [enter] ");
Serial.readStringUntil('\n');
Serial.print("Place on right side [enter] "); Serial.readStringUntil('\n');
calibrateAccelOnce();
Serial.print("5/6 Place on left side [enter] ");
Serial.readStringUntil('\n');
Serial.print("Place on left side [enter] "); Serial.readStringUntil('\n');
calibrateAccelOnce();
Serial.print("6/6 Place upside down [enter] ");
Serial.readStringUntil('\n');
Serial.print("Place upside down [enter] "); Serial.readStringUntil('\n');
calibrateAccelOnce();
printIMUCalibration();
Serial.print("✓ Calibration done!\n");
printIMUCal();
configureIMU();
}
@@ -121,15 +120,18 @@ 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() {
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 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() {

View File

@@ -21,3 +21,7 @@ void setLED(bool on) {
digitalWrite(LED_BUILTIN, on ? HIGH : LOW);
state = on;
}
void blinkLED() {
setLED(micros() / BLINK_PERIOD % 2);
}

View File

@@ -26,12 +26,12 @@ void logData() {
logBuffer[logPointer][4] = ratesTarget.x;
logBuffer[logPointer][5] = ratesTarget.y;
logBuffer[logPointer][6] = ratesTarget.z;
logBuffer[logPointer][7] = attitude.toEuler().x;
logBuffer[logPointer][8] = attitude.toEuler().y;
logBuffer[logPointer][9] = attitude.toEuler().z;
logBuffer[logPointer][10] = attitudeTarget.toEuler().x;
logBuffer[logPointer][11] = attitudeTarget.toEuler().y;
logBuffer[logPointer][12] = attitudeTarget.toEuler().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++;

View File

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

View File

@@ -3,7 +3,7 @@
// MAVLink communication
#if WIFI_ENABLED
#if WIFI_ENABLED == 1
#include <MAVLink.h>
@@ -13,8 +13,6 @@
#define MAVLINK_CONTROL_SCALE 0.7f
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
extern float controlTime;
void processMavlink() {
sendMavlink();
receiveMavlink();
@@ -30,8 +28,8 @@ 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,
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (armed * MAV_MODE_FLAG_SAFETY_ARMED) | ((mode == STAB) * MAV_MODE_FLAG_STABILIZE_ENABLED),
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);
}
@@ -40,12 +38,15 @@ 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);
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 actuator[32];
@@ -54,8 +55,8 @@ void sendMavlink() {
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);
}
@@ -82,21 +83,88 @@ 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);
controlThrottle = m.z / 1000.0f;
controlPitch = m.x / 1000.0f * MAVLINK_CONTROL_SCALE;
controlRoll = m.y / 1000.0f * MAVLINK_CONTROL_SCALE;
controlYaw = m.r / 1000.0f * MAVLINK_CONTROL_SCALE;
controlMode = 1; // STAB mode
controlArmed = 1; // armed
controlTime = t;
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;
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_message_t msg;
for (int i = 0; i < parametersCount(); i++) {
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
getParameterName(i), getParameter(i), MAV_PARAM_TYPE_REAL32, parametersCount(), i);
sendMessage(&msg);
}
}
if (msg->msgid == MAVLINK_MSG_ID_PARAM_REQUEST_READ) {
mavlink_param_request_read_t paramRequestRead;
mavlink_msg_param_request_read_decode(msg, &paramRequestRead);
char name[16 + 1];
strlcpy(name, paramRequestRead.param_id, sizeof(name)); // param_id might be not null-terminated
float value = strlen(name) == 0 ? getParameter(paramRequestRead.param_index) : getParameter(name);
if (paramRequestRead.param_index != -1) {
memcpy(name, getParameterName(paramRequestRead.param_index), 16);
}
mavlink_message_t msg;
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
name, value, MAV_PARAM_TYPE_REAL32, parametersCount(), paramRequestRead.param_index);
sendMessage(&msg);
}
if (msg->msgid == MAVLINK_MSG_ID_PARAM_SET) {
mavlink_param_set_t paramSet;
mavlink_msg_param_set_decode(msg, &paramSet);
char name[16 + 1];
strlcpy(name, paramSet.param_id, sizeof(name)); // param_id might be not null-terminated
setParameter(name, paramSet.param_value);
// send ack
mavlink_message_t msg;
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
paramSet.param_id, paramSet.param_value, MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
sendMessage(&msg);
}
if (msg->msgid == MAVLINK_MSG_ID_MISSION_REQUEST_LIST) { // handle to make qgc happy
mavlink_message_t msg;
mavlink_msg_mission_count_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, 0, 0, 0, MAV_MISSION_TYPE_MISSION, 0);
sendMessage(&msg);
}
// Handle commands
if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
mavlink_command_long_t commandLong;
mavlink_msg_command_long_decode(msg, &commandLong);
mavlink_message_t ack;
mavlink_message_t response;
if (commandLong.command == MAV_CMD_REQUEST_MESSAGE && commandLong.param1 == MAVLINK_MSG_ID_AUTOPILOT_VERSION) {
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, commandLong.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg->sysid, msg->compid);
sendMessage(&ack);
mavlink_msg_autopilot_version_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &response,
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MAVLINK2, 1, 0, 1, 1, 0, 0, 0, 0, 0, 0, 0);
sendMessage(&response);
} else {
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, commandLong.command, MAV_RESULT_UNSUPPORTED, UINT8_MAX, 0, msg->sysid, msg->compid);
sendMessage(&ack);
}
}
}
// Convert Forward-Left-Up to Forward-Right-Down quaternion
inline Quaternion FLU2FRD(const Quaternion &q) {
return Quaternion(q.w, q.x, -q.y, -q.z);
}
#endif

View File

@@ -2,22 +2,16 @@
// Repository: https://github.com/okalachev/flix
// Motors output control using MOSFETs
#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
// 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() {
Serial.println("Setup Motors");
@@ -32,30 +26,14 @@ void setupMotors() {
Serial.println("Motors initialized");
}
int getDutyCycle(float value) {
value = constrain(value, 0, 1);
float duty = mapff(value, 0, 1, 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) {
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.printf("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]));
}

133
flix/parameters.ino Normal file
View File

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

View File

@@ -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,38 +60,14 @@ public:
return ret;
}
bool finite() const {
return isfinite(w) && isfinite(x) && isfinite(y) && isfinite(z);
}
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;
@@ -136,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,
@@ -149,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(
@@ -166,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 {

View File

@@ -4,77 +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
float controlTime; // time of the last controls update
// NOTE: use 'cr' command to calibrate the RC and put the values here
int channelZero[] = {992, 992, 172, 992, 172, 172, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
int channelMax[] = {1811, 1811, 1811, 1811, 1811, 1811, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
// Channels mapping:
int rollChannel = 0;
int pitchChannel = 1;
int throttleChannel = 2;
int yawChannel = 3;
int armedChannel = 4;
int modeChannel = 5;
void setupRC() {
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 = controls[rollChannel];
controlPitch = controls[pitchChannel];
controlYaw = controls[yawChannel];
controlThrottle = controls[throttleChannel];
controlArmed = controls[armedChannel];
controlMode = controls[modeChannel];
}
void calibrateRC() {
Serial.println("Calibrate RC: move all sticks to maximum positions [4 sec]");
Serial.println("Calibrate RC: move all sticks to maximum positions within 4 seconds");
Serial.println("··o ··o\n··· ···\n··· ···");
delay(4000);
while (!readRC());
for (int i = 0; i < 16; i++) {
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];
}
Serial.println("Calibrate RC: move all sticks to neutral positions [4 sec]");
Serial.println("Calibrate RC: move all sticks to neutral positions within 4 seconds");
Serial.println("··· ···\n··· ·o·\n·o· ···");
delay(4000);
while (!readRC());
for (int i = 0; i < 16; i++) {
channelZero[i] = channels[i];
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];
}
printRCCalibration();
printRCCal();
}
void printRCCalibration() {
for (int i = 0; i < sizeof(channelZero) / sizeof(channelZero[0]); i++) Serial.printf("%d ", channelZero[i]);
Serial.printf("\n");
for (int i = 0; i < sizeof(channelMax) / sizeof(channelMax[0]); i++) Serial.printf("%d ", channelMax[i]);
Serial.printf("\n");
void printRCCal() {
printArray(channelNeutral, RC_CHANNELS);
printArray(channelMax, RC_CHANNELS);
}

View File

@@ -3,8 +3,6 @@
// Time related functions
float loopRate; // Hz
void step() {
float now = micros() / 1000000.0;
dt = now - t;

View File

@@ -3,14 +3,10 @@
// Utility functions
#pragma once
#include <math.h>
#include <soc/soc.h>
#include <soc/rtc_cntl_reg.h>
const float ONE_G = 9.80665;
float mapf(long x, long in_min, long in_max, float out_min, float out_max) {
return (float)(x - in_min) * (out_max - out_min) / (float)(in_max - in_min) + out_min;
}
@@ -30,7 +26,17 @@ float wrapAngle(float angle) {
return angle;
}
template <typename T>
void printArray(T arr[], int size) {
Serial.print("{");
for (uint8_t i = 0; i < size; i++) {
Serial.print(arr[i]);
if (i < size - 1) Serial.print(", ");
}
Serial.println("}");
}
// Disable reset on low voltage
void disableBrownOut() {
REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA);
WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
}

View File

@@ -13,18 +13,14 @@ public:
Vector(float x, float y, float z): x(x), y(y), z(z) {};
bool zero() const {
return x == 0 && y == 0 && z == 0;
}
bool finite() const {
return isfinite(x) && isfinite(y) && isfinite(z);
}
float norm() const {
return sqrt(x * x + y * y + z * z);
}
bool zero() const {
return x == 0 && y == 0 && z == 0;
}
void normalize() {
float n = norm();
x /= n;
@@ -32,10 +28,6 @@ public:
z /= n;
}
Vector operator + (const float b) const {
return Vector(x + b, y + b, z + b);
}
Vector operator * (const float b) const {
return Vector(x * b, y * b, z * b);
}
@@ -52,14 +44,6 @@ public:
return Vector(x - b.x, y - b.y, z - b.z);
}
Vector& operator += (const Vector& b) {
return *this = *this + b;
}
Vector& operator -= (const Vector& b) {
return *this = *this - b;
}
// Element-wise multiplication
Vector operator * (const Vector& b) const {
return Vector(x * b.x, y * b.y, z * b.z);
@@ -70,14 +54,18 @@ public:
return Vector(x / b.x, y / b.y, z / b.z);
}
bool operator == (const Vector& b) const {
inline bool operator == (const Vector& b) const {
return x == b.x && y == b.y && z == b.z;
}
bool operator != (const Vector& b) const {
inline bool operator != (const Vector& b) const {
return !(*this == b);
}
inline bool finite() const {
return isfinite(x) && isfinite(y) && isfinite(z);
}
static float dot(const Vector& a, const Vector& b) {
return a.x * b.x + a.y * b.y + a.z * b.z;
}
@@ -86,18 +74,18 @@ public:
return Vector(a.y * b.z - a.z * b.y, a.z * b.x - a.x * b.z, a.x * b.y - a.y * b.x);
}
static float angleBetween(const Vector& a, const Vector& b) {
static float angleBetweenVectors(const Vector& a, const Vector& b) {
return acos(constrain(dot(a, b) / (a.norm() * b.norm()), -1, 1));
}
static Vector rotationVectorBetween(const Vector& a, const Vector& b) {
static Vector angularRatesBetweenVectors(const Vector& a, const Vector& b) {
Vector direction = cross(a, b);
if (direction.zero()) {
// vectors are opposite, return any perpendicular vector
return cross(a, Vector(1, 0, 0));
}
direction.normalize();
float angle = angleBetween(a, b);
float angle = angleBetweenVectors(a, b);
return direction * angle;
}
@@ -108,6 +96,3 @@ public:
p.print(z, 15);
}
};
Vector operator * (const float a, const Vector& b) { return b * a; }
Vector operator + (const float a, const Vector& b) { return b + a; }

View File

@@ -3,7 +3,7 @@
// Wi-Fi support
#if WIFI_ENABLED
#if WIFI_ENABLED == 1
#include <WiFi.h>
#include <WiFiAP.h>
@@ -11,19 +11,20 @@
#define WIFI_SSID "flix"
#define WIFI_PASSWORD "flixwifi"
#define WIFI_UDP_IP "255.255.255.255"
#define WIFI_UDP_PORT 14550
#define WIFI_UDP_REMOTE_PORT 14550
WiFiUDP udp;
void setupWiFi() {
Serial.println("Setup Wi-Fi");
WiFi.softAP(WIFI_SSID, WIFI_PASSWORD);
IPAddress myIP = WiFi.softAPIP();
udp.begin(WIFI_UDP_PORT);
}
void sendWiFi(const uint8_t *buf, int len) {
udp.beginPacket(WiFi.softAPBroadcastIP(), WIFI_UDP_REMOTE_PORT);
udp.beginPacket(WIFI_UDP_IP, WIFI_UDP_PORT);
udp.write(buf, len);
udp.endPacket();
}

View File

@@ -27,15 +27,27 @@ long map(long x, long in_min, long in_max, long out_min, long out_max) {
return (delta * rise) / run + out_min;
}
size_t strlcpy(char* dst, const char* src, size_t len) {
size_t l = strlen(src);
size_t i = 0;
while (i < len - 1 && *src != '\0') { *dst++ = *src++; i++; }
*dst = '\0';
return l;
}
class __FlashStringHelper;
// Arduino String partial implementation
// https://www.arduino.cc/reference/en/language/variables/data-types/stringobject/
class String: public std::string {
public:
String(const char *str = "") : std::string(str) {}
long toInt() const { return atol(this->c_str()); }
float toFloat() const { return atof(this->c_str()); }
bool isEmpty() const { return this->empty(); }
void toCharArray(char *buf, unsigned int bufsize, unsigned int index = 0) const {
strlcpy(buf, this->c_str() + index, bufsize);
}
};
class Print;
@@ -99,7 +111,7 @@ public:
class HardwareSerial: public Print {
public:
void begin(unsigned long baud) {
// server is running in background by default, so it doesn't have access to stdin
// server is running in background by default, so doesn't have access to stdin
// https://github.com/gazebosim/gazebo-classic/blob/d45feeb51f773e63960616880b0544770b8d1ad7/gazebo/gazebo_main.cc#L216
// set foreground process group to current process group to allow reading from stdin
// https://stackoverflow.com/questions/58918188/why-is-stdin-not-propagated-to-child-process-of-different-process-group
@@ -129,13 +141,15 @@ public:
HardwareSerial Serial, Serial2;
class EspClass {
public:
void restart() { Serial.println("Ignore reboot in simulation"); }
} ESP;
void delay(uint32_t ms) {
std::this_thread::sleep_for(std::chrono::milliseconds(ms));
}
bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { return true; }
bool ledcWrite(uint8_t pin, uint32_t duty) { return true; }
unsigned long __micros;
unsigned long __resetTime = 0;

63
gazebo/Preferences.h Normal file
View File

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

View File

@@ -14,13 +14,10 @@ public:
SBUS(HardwareSerial& bus, const bool inv = true) {};
SBUS(HardwareSerial& bus, const int8_t rxpin, const int8_t txpin, const bool inv = true) {};
void begin() {};
bool read() { return joystickInit(); };
bool read() { return joystickInitialized; };
SBUSData data() {
SBUSData data;
joystickGet(data.ch);
for (int i = 0; i < 16; i++) {
data.ch[i] = map(data.ch[i], -32768, 32767, 1000, 2000); // convert to pulse width style
}
return data;
};
};

View File

@@ -10,12 +10,24 @@
#include "Arduino.h"
#include "wifi.h"
#define RC_CHANNELS 16
#define MOTOR_REAR_LEFT 0
#define MOTOR_FRONT_LEFT 3
#define MOTOR_FRONT_RIGHT 2
#define MOTOR_REAR_RIGHT 1
#define WIFI_ENABLED 1
#define ONE_G 9.80665
float t = NAN;
float dt;
float loopRate;
float motors[4];
float controlRoll, controlPitch, controlYaw, controlThrottle, controlArmed, controlMode;
int16_t channels[16]; // raw rc channels
float controls[RC_CHANNELS];
float controlsTime;
Vector acc;
Vector gyro;
Vector rates;
@@ -31,11 +43,11 @@ void controlAttitude();
void controlRate();
void controlTorque();
void showTable();
void sendMotors();
bool motorsActive();
void doCommand(const String& command);
void cliTestMotor(uint8_t n);
String stringToken(char* str, const char* delim);
void normalizeRC();
void printRCCalibration();
void printRCCal();
void processMavlink();
void sendMavlink();
void sendMessage(const void *msg);
@@ -43,11 +55,13 @@ void receiveMavlink();
void handleMavlink(const void *_msg);
void failsafe();
void descend();
inline Quaternion fluToFrd(const Quaternion &q);
inline Quaternion FLU2FRD(const Quaternion &q);
// mocks
void setLED(bool on) {};
void calibrateGyro() { printf("Skip gyro calibrating\n"); };
void calibrateAccel() { printf("Skip accel calibrating\n"); };
void printIMUCalibration() { printf("cal: N/A\n"); };
void sendMotors() {};
void printIMUCal() { printf("cal: N/A\n"); };
void printIMUInfo() {};
Vector accBias, gyroBias, accScale(1, 1, 1);

View File

@@ -7,27 +7,17 @@
#include <gazebo/gazebo.hh>
#include <iostream>
// simulation calibration overrides, NOTE: use `cr` command and replace with the actual values
const int channelZeroOverride[] = {1500, 0, 1000, 1500, 1500, 1000};
const int channelMaxOverride[] = {2000, 2000, 2000, 2000, 2000, 2000};
// channels mapping overrides
const int rollChannelOverride = 3;
const int pitchChannelOverride = 4;
const int throttleChannelOverride = 5;
const int yawChannelOverride = 0;
const int armedChannelOverride = 2;
const int modeChannelOverride = 1;
#define RC_CHANNEL_ROLL 0
#define RC_CHANNEL_PITCH 1
#define RC_CHANNEL_THROTTLE 2
#define RC_CHANNEL_YAW 3
#define RC_CHANNEL_ARMED 5
#define RC_CHANNEL_MODE 4
SDL_Joystick *joystick;
bool joystickInitialized = false, warnShown = false;
void normalizeRC();
bool joystickInit() {
static bool joystickInitialized = false;
static bool warnShown = false;
if (joystickInitialized) return true;
void joystickInit() {
SDL_Init(SDL_INIT_JOYSTICK);
joystick = SDL_JoystickOpen(0);
if (joystick != NULL) {
@@ -37,28 +27,17 @@ bool joystickInit() {
gzwarn << "Joystick not found, begin waiting for joystick..." << std::endl;
warnShown = true;
}
// apply overrides
extern int channelZero[16];
extern int channelMax[16];
memcpy(channelZero, channelZeroOverride, sizeof(channelZeroOverride));
memcpy(channelMax, channelMaxOverride, sizeof(channelMaxOverride));
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
rollChannel = rollChannelOverride;
pitchChannel = pitchChannelOverride;
throttleChannel = throttleChannelOverride;
yawChannel = yawChannelOverride;
armedChannel = armedChannelOverride;
modeChannel = modeChannelOverride;
return joystickInitialized;
}
bool joystickGet(int16_t ch[16]) {
if (!joystickInitialized) {
joystickInit();
return false;
}
SDL_JoystickUpdate();
for (uint8_t i = 0; i < 16; i++) {
for (uint8_t i = 0; i < sizeof(channels) / sizeof(channels[0]); i++) {
ch[i] = SDL_JoystickGetAxis(joystick, i);
}
return true;

View File

@@ -1,7 +1,6 @@
<?xml version="1.0"?>
<sdf version="1.5">
<model name="flix">
<plugin name="flix" filename="libflix.so"/>
<link name="body">
<inertial>
<mass>0.065</mass>
@@ -24,14 +23,38 @@
<update_rate>1000</update_rate>
<imu>
<angular_velocity>
<x><noise type="gaussian"><stddev>0.00174533</stddev></noise></x><!-- 0.1 degrees per second -->
<y><noise type="gaussian"><stddev>0.00174533</stddev></noise></y>
<z><noise type="gaussian"><stddev>0.00174533</stddev></noise></z>
<x>
<noise type="gaussian">
<stddev>0.00174533</stddev><!-- 0.1 degrees per second -->
</noise>
</x>
<y>
<noise type="gaussian">
<stddev>0.00174533</stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<stddev>0.00174533</stddev>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x><noise type="gaussian"><stddev>0.0784</stddev></noise></x><!-- 8 mg -->
<y><noise type="gaussian"><stddev>0.0784</stddev></noise></y>
<z><noise type="gaussian"><stddev>0.0784</stddev></noise></z>
<x>
<noise type="gaussian">
<stddev>0.0784</stddev><!-- 8 mg -->
</noise>
</x>
<y>
<noise type="gaussian">
<stddev>0.0784</stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<stddev>0.0784</stddev>
</noise>
</z>
</linear_acceleration>
</imu>
</sensor>
@@ -67,5 +90,6 @@
<material><ambient>1 1 1 0.5</ambient><diffuse>1 1 1 0.5</diffuse></material>
</visual>
</link>
<plugin name="flix" filename="libflix.so"/>
</model>
</sdf>

View File

@@ -17,12 +17,13 @@
#include "Arduino.h"
#include "flix.h"
#include "util.ino"
#include "rc.ino"
#include "time.ino"
#include "motors.ino"
#include "estimate.ino"
#include "control.ino"
#include "log.ino"
#include "parameters.ino"
#include "cli.ino"
#include "mavlink.ino"
#include "failsafe.ino"
@@ -51,6 +52,7 @@ public:
this->resetConnection = event::Events::ConnectWorldReset(std::bind(&ModelFlix::OnReset, this));
initNode();
Serial.begin(0);
setupParameters();
gzmsg << "Flix plugin loaded" << endl;
}
@@ -70,8 +72,8 @@ public:
// read rc
readRC();
controlMode = 1; // 0 acro, 1 stab
controlArmed = 1; // armed
controls[RC_CHANNEL_MODE] = 1; // 0 acro, 1 stab
controls[RC_CHANNEL_ARMED] = 1; // armed
estimate();
@@ -79,12 +81,13 @@ public:
attitude.setYaw(this->model->WorldPose().Yaw());
control();
handleInput();
parseInput();
processMavlink();
applyMotorForces();
publishTopics();
logData();
flushParameters();
}
void applyMotorForces() {

View File

@@ -1 +1 @@
// Dummy file to make it possible to compile simulator with Flix' util.h
// Dummy file to make it possible to compile simulator with util.ino

View File

@@ -1,4 +1,3 @@
// Dummy file to make it possible to compile simulator with Flix' util.h
// Dummy file to make it possible to compile simulator with util.ino
#define WRITE_PERI_REG(addr, val) {}
#define REG_CLR_BIT(_r, _b) {}

9
gazebo/util.h Normal file
View File

@@ -0,0 +1,9 @@
#include <filesystem>
std::filesystem::path getPluginPath() {
Dl_info dl_info;
if (dladdr((void*)&getPluginPath, &dl_info) == 0) {
throw std::runtime_error("Unable to determine plugin path using dladdr.");
}
return std::filesystem::path(dl_info.dli_fname);
}

View File

@@ -11,8 +11,8 @@
#include <sys/poll.h>
#include <gazebo/gazebo.hh>
#define WIFI_UDP_PORT 14580
#define WIFI_UDP_REMOTE_PORT 14550
#define WIFI_UDP_PORT_LOCAL 14580
#define WIFI_UDP_PORT_REMOTE 14550
int wifiSocket;
@@ -21,11 +21,11 @@ void setupWiFi() {
sockaddr_in addr; // local address
addr.sin_family = AF_INET;
addr.sin_addr.s_addr = INADDR_ANY;
addr.sin_port = htons(WIFI_UDP_PORT);
addr.sin_port = htons(WIFI_UDP_PORT_LOCAL);
bind(wifiSocket, (sockaddr *)&addr, sizeof(addr));
int broadcast = 1;
setsockopt(wifiSocket, SOL_SOCKET, SO_BROADCAST, &broadcast, sizeof(broadcast)); // enable broadcast
gzmsg << "WiFi UDP socket initialized on port " << WIFI_UDP_PORT << " (remote port " << WIFI_UDP_REMOTE_PORT << ")" << std::endl;
gzmsg << "WiFi UDP socket initialized on port " << WIFI_UDP_PORT_LOCAL << " (remote port " << WIFI_UDP_PORT_REMOTE << ")" << std::endl;
}
void sendWiFi(const uint8_t *buf, int len) {
@@ -33,7 +33,7 @@ void sendWiFi(const uint8_t *buf, int len) {
sockaddr_in addr; // remote address
addr.sin_family = AF_INET;
addr.sin_addr.s_addr = INADDR_BROADCAST; // send UDP broadcast
addr.sin_port = htons(WIFI_UDP_REMOTE_PORT);
addr.sin_port = htons(WIFI_UDP_PORT_REMOTE);
sendto(wifiSocket, buf, len, 0, (sockaddr *)&addr, sizeof(addr));
}