109 Commits

Author SHA1 Message Date
Oleg Kalachev
f2dec78b16 Fix docker sim build 2025-04-24 19:21:23 +03:00
Oleg Kalachev
31ac562f67 Fix docker sim build again 2025-04-24 19:20:01 +03:00
Oleg Kalachev
feb686727b Fix Docker sim build 2025-04-24 18:47:51 +03:00
Oleg Kalachev
1975ed30b4 Make job using Ubuntu 22.02 2025-04-24 18:45:25 +03:00
Oleg Kalachev
1859fca150 Update APT before installing libsdl2-dev 2025-04-24 18:38:08 +03:00
Oleg Kalachev
42d844287e Fix docker run 2025-04-24 18:23:14 +03:00
Oleg Kalachev
226da71719 Run sim build in docker using container directive 2025-04-24 18:21:58 +03:00
Oleg Kalachev
405777dc46 Use ubuntu-22.04 for sim build, add job with building with docker 2025-04-24 18:20:44 +03:00
Oleg Kalachev
962757f46e Update user builds illustration in readme 2025-04-23 20:10:29 +03:00
Oleg Kalachev
f03dec4fae Update demo video 2025-04-22 11:27:29 +03:00
Oleg Kalachev
fe98a5bf97 Minor code simplifications 2025-04-13 01:42:47 +03:00
Oleg Kalachev
253f2fe3dd Update MAVLink-Arduino to 2.0.16 2025-04-11 07:01:54 +03:00
Oleg Kalachev
94dc566643 Show landed state in imu command output 2025-03-29 16:19:23 +03:00
Oleg Kalachev
547f5087ef Pass landed state to mavlink
Using EXTENDED_SYS_STATE message
2025-03-29 16:14:37 +03:00
Oleg Kalachev
66a43ab246 Continuous gyro bias estimation (#17)
Estimate gyro bias continuously instead of calibrating the gyro at startup.
2025-03-29 12:21:40 +03:00
Oleg Kalachev
117ae42d1b Add Wi-Fi password to build tutorial 2025-03-29 12:02:59 +03:00
Oleg Kalachev
3a61dca102 Simplify and improve acc calibration command output 2025-03-29 01:05:55 +03:00
Oleg Kalachev
a8fe1324c3 Minor readme update 2025-03-28 20:50:23 +03:00
Oleg Kalachev
fc0b805cc2 Add cryptokobans's build to user projects 2025-03-28 18:23:09 +03:00
Oleg Kalachev
d68222953d Simplify user builds article layout: remove tables
Tables make photos squeezed in phones
2025-03-27 18:56:35 +03:00
Oleg Kalachev
bca1312b46 Remove twxs.cmake from the list of recommended extensions 2025-03-14 03:24:30 +03:00
Oleg Kalachev
d5148d12a1 Minor code style fix 2025-03-14 03:03:27 +03:00
Oleg Kalachev
208e50aa15 Encode if the mode in stabilized in heartbeat message 2025-03-14 03:02:43 +03:00
Oleg Kalachev
0a87ccf435 Some minor readme updates 2025-03-01 00:27:55 +03:00
Oleg Kalachev
3fdebf39d8 Fix mavlink disconnection in pauses in cli commands
Implement pause function that proceeds processing mavlink.
Use temporal workaround for simulation, as micros function gives the same result on the same simulation step.
2025-02-28 19:25:41 +03:00
Oleg Kalachev
5bf2e06c5a Use natural order of ino files includes in simulation
In Arduino, ino files are included in alphabetical order.
Cleanup unused function declarations in simulation, add missing.
Rename flu to frd function to match the code style.
2025-02-28 19:06:58 +03:00
Oleg Kalachev
4e3e8c70b0 Update main book illustration 2025-02-28 03:17:09 +03:00
Oleg Kalachev
bda44fca02 Remove dt multiplier from acc correction and increase acc weight
More classical complementary filter implementation
Increase effective accelerometer weight for faster convergence
2025-02-28 00:51:16 +03:00
Oleg Kalachev
e66f6563a5 Add custom Wi-Fi control description by @pavelkabakov #11
Co-authored-by: Pavel Kabakov <110939392+pavelkabakov@users.noreply.github.com>
2025-02-26 01:08:36 +03:00
Oleg Kalachev
95084c167c Add user project by jeka_chex 2025-02-26 00:55:14 +03:00
Oleg Kalachev
931b2066bb Minor book fix 2025-02-26 00:20:50 +03:00
Oleg Kalachev
a2cf318189 Check target system id in mavlink messages
Skip messages addressed to other systems
2025-02-26 00:08:23 +03:00
Oleg Kalachev
83a8dcd63e Cleanup mavlink subsystem code 2025-02-24 13:06:38 +03:00
Oleg Kalachev
c62e536b50 Put last control time in RC control mavlink message instead of send time 2025-02-22 20:07:26 +03:00
Oleg Kalachev
287a4b5a71 Fix accel calibration via mavlink console
Add 5 s timeout as waiting for enter is not implemented for mavlink console yet
2025-02-18 13:01:44 +03:00
Oleg Kalachev
d60628e14d Support MAVLink console
Implement receiving and sending SERIAL_CONTROL message
Use global defined print function instead of Serial.printf
2025-02-18 10:33:01 +03:00
Oleg Kalachev
bfef7bd26a Remove non-nessesary printArray function 2025-02-18 10:26:59 +03:00
Oleg Kalachev
e3c6a0d4df Make some clarifications regarding imu check in troubleshooting 2025-02-18 10:18:27 +03:00
Oleg Kalachev
9566a4a503 Add parameters access method to build article 2025-02-18 10:14:39 +03:00
Oleg Kalachev
e54e0e8c48 Make all the basic functionality work without the imu 2025-02-17 19:44:18 +03:00
Oleg Kalachev
149c62568f Refactor CLI submodule
Move command parsing to doCommand
Parse command with splitString instead of stringToken
Trim commands
Move cliTestMotor to the bottom
Rename parseInput to handleInput, which is more clear
Move motor test function to motors.ino
2025-02-17 15:51:58 +03:00
Oleg Kalachev
641e711e67 Minor fix in joystick support for simulation
Don't use channels variable as it breaks code isolation
2025-02-15 03:29:09 +03:00
Oleg Kalachev
f2171f2db4 Minor clarification in RC receiver connection table 2025-02-12 11:10:04 +03:00
Oleg Kalachev
6ed6ef3e8c Assume armed is true if armed channel is not defined 2025-02-12 10:15:42 +03:00
Oleg Kalachev
083db659c6 Improve RC reading in calibration process 2025-02-12 10:15:13 +03:00
Oleg Kalachev
ce1223e82d Allow CI simulator build under macOS if manually triggered 2025-02-12 06:24:51 +03:00
Peter A. Ukhov
437ce81a68 Add video for flix2 by Peter Ukhov (#10)
Co-authored-by: Oleg Kalachev <okalachev@gmail.com>
2025-02-12 05:01:56 +03:00
Oleg Kalachev
42f318c6df Another update of hall of fame page 2025-02-11 14:02:15 +03:00
Oleg Kalachev
1450c793b7 Update hall of fame page 2025-02-11 12:11:22 +03:00
Oleg Kalachev
3ed4143ba0 Simplify WIFI_ENABLED macro test 2025-02-08 02:41:09 +03:00
Oleg Kalachev
33adf33f0e Add proper command to install arduino-cli on Linux in instructions 2025-02-01 22:56:09 +03:00
Oleg Kalachev
373c0f117a Update user builds page 2025-01-31 11:15:57 +03:00
Oleg Kalachev
0cb2eb5fac Update upload-artifact action to fix build 2025-01-31 03:32:09 +03:00
Oleg Kalachev
70f63bfbe9 Add hall of fame page 2025-01-31 03:19:49 +03:00
Oleg Kalachev
15fbe34d19 Add failsafe to prevent arming without prior zero throttle 2025-01-24 16:23:59 +03:00
Zatupitel
7d2d54a94d Fix working on ESP32-S3 (#8)
Disable brown-out detector in a more correct way: clear only enable bit instead of clearing the whole register.

---------

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

View File

@@ -5,6 +5,7 @@ on:
branches: [ '*' ]
pull_request:
branches: [ master ]
workflow_dispatch:
jobs:
build_linux:
@@ -15,6 +16,8 @@ jobs:
run: curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=/usr/local/bin sh
- name: Build firmware
run: make
- name: Build firmware without Wi-Fi
run: sed -i 's/^#define WIFI_ENABLED 1$/#define WIFI_ENABLED 0/' flix/flix.ino && make
- name: Check c_cpp_properties.json
run: tools/check_c_cpp_properties.py
@@ -43,7 +46,7 @@ jobs:
run: python3 tools/check_c_cpp_properties.py
build_simulator:
runs-on: ubuntu-latest
runs-on: ubuntu-22.04
steps:
- name: Install Arduino CLI
uses: arduino/setup-arduino-cli@v1.1.1
@@ -54,28 +57,49 @@ jobs:
run: sudo apt-get install libsdl2-dev
- name: Build simulator
run: make build_simulator
- uses: actions/upload-artifact@v3
- uses: actions/upload-artifact@v4
with:
name: gazebo-plugin-binary
path: gazebo/build/*.so
retention-days: 1
# build_simulator_macos:
# runs-on: macos-latest
# steps:
# - name: Install Arduino CLI
# run: brew install arduino-cli
# - uses: actions/checkout@v4
# - name: Clean up python binaries # Workaround for https://github.com/actions/setup-python/issues/577
# run: |
# rm -f /usr/local/bin/2to3*
# rm -f /usr/local/bin/idle3*
# rm -f /usr/local/bin/pydoc3*
# rm -f /usr/local/bin/python3*
# rm -f /usr/local/bin/python3*-config
# - name: Install Gazebo
# run: brew update && brew tap osrf/simulation && brew install gazebo11
# - name: Install SDL2
# run: brew install sdl2
# - name: Build simulator
# run: make build_simulator
build_simulator_docker:
runs-on: ubuntu-latest
container:
image: ubuntu:20.04
steps:
- name: Install Arduino CLI
uses: arduino/setup-arduino-cli@v1.1.1
- uses: actions/checkout@v4
- name: Install Gazebo
run: curl -sSL http://get.gazebosim.org | sh
- name: Install SDL2
run: apt-get update && DEBIAN_FRONTEND=noninteractive apt-get install build-essential libsdl2-dev -y
- name: Build simulator
run: make build_simulator
- uses: actions/upload-artifact@v4
with:
name: gazebo-plugin-binary
path: gazebo/build/*.so
retention-days: 1
build_simulator_macos:
runs-on: macos-latest
if: github.event_name == 'workflow_dispatch'
steps:
- name: Install Arduino CLI
run: brew install arduino-cli
- uses: actions/checkout@v4
- name: Clean up python binaries # Workaround for https://github.com/actions/setup-python/issues/577
run: |
rm -f /usr/local/bin/2to3*
rm -f /usr/local/bin/idle3*
rm -f /usr/local/bin/pydoc3*
rm -f /usr/local/bin/python3*
rm -f /usr/local/bin/python3*-config
- name: Install Gazebo
run: brew update && brew tap osrf/simulation && brew install gazebo11
- name: Install SDL2
run: brew install sdl2
- name: Build simulator
run: make build_simulator

View File

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

View File

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

View File

@@ -4,11 +4,11 @@
<table>
<tr>
<td align=center><strong>Version 1</strong> (3D-printed frame)</td>
<td align=center><strong>Version 1.1</strong> (3D-printed frame)</td>
<td align=center><strong>Version 0</strong></td>
</tr>
<tr>
<td><img src="docs/img/flix1.jpg" width=500 alt="Flix quadcopter"></td>
<td><img src="docs/img/flix1.1.jpg" width=500 alt="Flix quadcopter"></td>
<td><img src="docs/img/flix.jpg" width=500 alt="Flix quadcopter"></td>
</tr>
</table>
@@ -32,13 +32,17 @@
## It actually flies
See detailed demo video (for version 0): https://youtu.be/8GzzIQ3C6DQ.
See detailed demo video: https://youtu.be/hT46CZ1CgC4.
<a href="https://youtu.be/hT46CZ1CgC4"><img width=500 src="https://i3.ytimg.com/vi/hT46CZ1CgC4/maxresdefault.jpg"></a>
Version 0 demo video: https://youtu.be/8GzzIQ3C6DQ.
<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.
See the [user builds gallery](docs/user.md).
<a href="https://t.me/opensourcequadcopter/42"><img width=500 src="docs/img/flight-video.jpg"></a>
<a href="docs/user.md"><img src="docs/img/user/user.jpg" width=400></a>
## Simulation
@@ -53,19 +57,20 @@ See [instructions on running the simulation](docs/build.md).
|Type|Part|Image|Quantity|
|-|-|:-:|:-:|
|Microcontroller board|ESP32 Mini|<img src="docs/img/esp32.jpg" width=100>|1|
|IMU (and barometer²) board|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|
|IMU (and barometer²) board|GY91, MPU-9265 (or other MPU9250/MPU6500 board), ICM20948³|<img src="docs/img/gy-91.jpg" width=90 align=center><img src="docs/img/icm-20948.jpg" width=100>|1|
|Motor|8520 3.7V brushed motor (shaft 0.8mm).<br>Motor with exact 3.7V voltage is needed, not ranged working voltage (3.7V — 6V).|<img src="docs/img/motor.jpeg" width=100>|4|
|Propeller|Hubsan 55 mm|<img src="docs/img/prop.jpg" width=100>|4|
|MOSFET (transistor)|100N03A or [analog](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4|
|Pull-down resistor|10 kΩ|<img src="docs/img/resistor10k.jpg" width=100>|4|
|3.7V Li-Po battery|LW 952540 (or any compatible by the size)|<img src="docs/img/battery.jpg" width=100>|1|
|Battery connector cable|MX2.0 2P female|<img src="docs/img/mx.png" width=100>|1|
|Li-Po Battery charger|Any|<img src="docs/img/charger.jpg" width=100>|1|
|Screws for IMU board mounting|M3x5|<img src="docs/img/screw-m3.jpg" width=100>|2|
|Screws for frame assembly|M1.4x5|<img src="docs/img/screw-m1.4.jpg" height=30 align=center>|4|
|Frame bottom part|3D printed⁴:<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 bottom part|3D printed⁴:<br>[`flix-frame-1.1.stl`](docs/assets/flix-frame-1.1.stl) [`flix-frame-1.1.step`](docs/assets/flix-frame-1.1.step)|<img src="docs/img/frame1.jpg" width=100>|1|
|Frame top part|3D printed:<br>[`esp32-holder.stl`](docs/assets/esp32-holder.stl) [`esp32-holder.step`](docs/assets/esp32-holder.step)|<img src="docs/img/esp32-holder.jpg" width=100>|1|
|Washer for IMU board mounting|3D printed:<br>[`washer-m3.stl`](docs/assets/washer-m3.stl) [`washer-m3.step`](docs/assets/washer-m3.step)|<img src="docs/img/washer-m3.jpg" width=100>|1|
|*RC transmitter (optional)*|*KINGKONG TINY X8 or other⁵*|<img src="docs/img/tx.jpg" width=100>|1|
|Washer for IMU board mounting|3D printed:<br>[`washer-m3.stl`](docs/assets/washer-m3.stl) [`washer-m3.step`](docs/assets/washer-m3.step)|<img src="docs/img/washer-m3.jpg" width=100>|2|
|*RC transmitter (optional)*|*KINGKONG TINY X8 (warning: lacks USB support) 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||||
@@ -95,7 +100,9 @@ Motor connection scheme:
<img src="docs/img/mosfet-connection.png" height=400 alt="MOSFET connection scheme">
Complete diagram is Work-in-Progress.
You can see a user-contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612338222067&cot=14) of the drone.
See [assembly guide](docs/assembly.md) for instructions on assembling the drone.
### Notes
@@ -116,10 +123,10 @@ Complete diagram is Work-in-Progress.
|Motor|Position|Direction|Wires|GPIO|
|-|-|-|-|-|
|Motor 0|Rear left|Counter-clockwise|Black & White|GPIO12|
|Motor 1|Rear right|Clockwise|Blue & Red|GPIO13|
|Motor 2|Front right|Counter-clockwise|Black & White|GPIO14|
|Motor 3|Front left|Clockwise|Blue & Red|GPIO15|
|Motor 0|Rear left|Counter-clockwise|Black & White|GPIO12 (*TDI*)|
|Motor 1|Rear right|Clockwise|Blue & Red|GPIO13 (*TCK*)|
|Motor 2|Front right|Counter-clockwise|Black & White|GPIO14 (*TMS*)|
|Motor 3|Front left|Clockwise|Blue & Red|GPIO15 (*TD0*)|
Counter-clockwise motors have black and white wires and clockwise motors have blue and red wires.
@@ -128,8 +135,8 @@ Complete diagram is Work-in-Progress.
|Receiver pin|ESP32 pin|
|-|-|
|GND|GND|
|VIN|VC (or 3.3V depending on the receiver)|
|Signal|GPIO4⁶|
|VIN|VCC (or 3.3V depending on the receiver)|
|Signal (TX)|GPIO4⁶|
*⁶ — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.*

29
docs/assembly.md Normal file
View File

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

File diff suppressed because it is too large Load Diff

Binary file not shown.

View File

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

View File

@@ -12,7 +12,7 @@
* [Моторы]()
* [Радиоуправление]()
* [Гироскоп](gyro.md)
* [Акселерометр]()s
* [Акселерометр]()
* [Оценка состояния]()
* [PID-регулятор]()
* [Режим ACRO]()

View File

@@ -139,7 +139,7 @@ void loop() {
### Частота сэмплов
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер. В Flix используется частота сэмплов 1 кГц.
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер.
Частота сэмплов устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:

View File

@@ -84,7 +84,7 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 20.04. If you h
#### Control with smartphone
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone.
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone. For **iOS**, use [QGroundControl build from TAJISOFT](https://apps.apple.com/ru/app/qgc-from-tajisoft/id1618653051).
2. Connect your smartphone to the same Wi-Fi network as the machine running the simulator.
3. If you're using a virtual machine, make sure that its network is set to the **bridged** mode with Wi-Fi adapter selected.
4. Run the simulation.
@@ -105,17 +105,26 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 20.04. If you h
### Arduino IDE (Windows, Linux, macOS)
1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended).
2. Install ESP32 core, version 3.0.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):
2. Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).
3. Install ESP32 core, version 3.1.0 (version 2.x is not supported). See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
* `FlixPeriph`, the latest version.
* `MAVLink`, version 2.0.12.
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.
* `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.
### Command line (Windows, Linux, macOS)
1. [Install Arduino CLI](https://arduino.github.io/arduino-cli/installation/).
On Linux, use:
```bash
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
```
2. Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).
3. Compile the firmware using `make`. Arduino dependencies will be installed automatically:
@@ -137,18 +146,21 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 20.04. If you h
See other available Make commands in the [Makefile](../Makefile).
> [!TIP]
> You can test the firmware on a bare ESP32 board without connecting IMU and other peripherals. The Wi-Fi network `flix` should appear and all the basic functionality including CLI and QGroundControl connection should work.
### Setup and flight
Before flight you need to calibrate the accelerometer:
1. Open Serial Monitor in Arduino IDE (use use `make monitor` command in the command line).
1. Open Serial Monitor in Arduino IDE (or use `make monitor` command in the command line).
2. Type `ca` command there and follow the instructions.
#### Control with smartphone
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone.
2. Power the drone using the battery.
3. Connect your smartphone to the appeared `flix` Wi-Fi network.
3. Connect your smartphone to the appeared `flix` Wi-Fi network (password: `flixwifi`).
4. Open QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
5. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
6. Use the virtual joystick to fly the drone!
@@ -157,10 +169,33 @@ 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).
1. Open Serial Monitor in Arduino IDE (or use `make monitor` command in the command line).
2. Type `cr` command there and follow the instructions.
3. Use the remote control to fly the drone!
Then you can use your remote control to fly the drone!
#### Control with USB remote control
If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it.
1. Install [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html) app on your computer.
2. Connect your USB remote control to the computer.
3. Power up the drone.
4. Connect your computer to the appeared `flix` Wi-Fi network (password: `flixwifi`).
5. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
6. Go the the QGroundControl menu ⇒ *Vehicle Setup**Joystick*. Calibrate you USB remote control there.
7. Use the USB remote control to fly the drone!
#### Adjusting parameters
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl app. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup**Parameters*.
<img src="img/parameters.png" width="400">
#### CLI access
In addition to accessing the drone's command line interface (CLI) using the serial port, you can also access it with QGroundControl using Wi-Fi connection. To do that, go to the QGroundControl menu ⇒ *Vehicle Setup**Analyze Tools**MAVLink Console*.
<img src="img/cli.png" width="400">
> [!NOTE]
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.

View File

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

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 157 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 79 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 115 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 169 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 147 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 99 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 152 KiB

BIN
docs/img/cli.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 123 KiB

BIN
docs/img/mx.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 16 KiB

BIN
docs/img/parameters.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 27 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 68 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 40 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 45 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 51 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 52 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 44 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 35 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 36 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 43 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 24 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 45 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 54 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 30 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 43 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 70 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 18 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 33 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 40 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 83 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 58 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 74 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 56 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 28 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 57 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 49 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 78 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 20 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 73 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 58 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 66 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 9.8 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 87 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 58 KiB

View File

@@ -14,14 +14,16 @@ 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.
* **Check if the CLI is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the CLI using QGroundControl (*Vehicle Setup* ⇒ *Analyze Tools**MAVLink Console*).
* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
* **Make sure you're not moving the drone several seconds after the power on**. The drone calibrates its gyroscope on the start so it should stay still for a while.
* **Check the IMU 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.
* **Check the IMU is working**. Perform `imu` command and check its output:
* The `status` field should be `OK`.
* The `rate` field should be about 1000 (Hz).
* The `accel` and `gyro` fields should change as you move the drone.
* **Calibrate the accelerometer.** if is wasn't done before. Type `ca` command in Serial Monitor and follow the instructions.
* **Check the attitude estimation**. Connect to the drone using QGroundControl. Rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct.
* **Check the IMU orientation is set correctly**. If the attitude estimation is rotated, make sure `rotateIMU` function is defined correctly in `imu.ino` file.
* **Check the motors type**. Motors with exact 3.7V voltage are needed, not ranged working voltage (3.7V — 6V).
* **Check the motors**. Perform the following commands using Serial Monitor:
* `mfr` — should rotate front right motor (counter-clockwise).
* `mfl` — should rotate front left motor (clockwise).

97
docs/user.md Normal file
View File

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

View File

@@ -27,4 +27,4 @@ Flix version 0 (obsolete):
<img src="img/schematics.svg" width=800 alt="Flix schematics">
You can also check a user contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/) of the drone.
You can also check a user contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764574482511443&cot=14) of the drone.

View File

@@ -5,9 +5,12 @@
#include "pid.h"
#include "vector.h"
#include "util.h"
extern PID rollRatePID, pitchRatePID, yawRatePID, rollPID, pitchPID;
extern LowPassFilter<Vector> ratesFilter;
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern float loopRate, dt;
extern double t;
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
const char* motd =
"\nWelcome to\n"
@@ -23,6 +26,7 @@ const char* motd =
"p <name> - show parameter\n"
"p <name> <value> - set parameter\n"
"preset - reset parameters\n"
"time - show time info\n"
"ps - show pitch/roll/yaw\n"
"psq - show attitude quaternion\n"
"imu - show IMU data\n"
@@ -30,66 +34,106 @@ const char* motd =
"mot - show motor output\n"
"log - dump in-RAM log\n"
"cr - calibrate RC\n"
"cg - calibrate gyro\n"
"ca - calibrate accel\n"
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
"reset - reset drone's state\n"
"reboot - reboot the drone\n";
void doCommand(String& command, String& arg0, String& arg1) {
void print(const char* format, ...) {
char buf[1000];
va_list args;
va_start(args, format);
vsnprintf(buf, sizeof(buf), format, args);
va_end(args);
Serial.print(buf);
#if WIFI_ENABLED
mavlinkPrint(buf);
#endif
}
void pause(float duration) {
#if ARDUINO
double start = t;
while (t - start < duration) {
step();
handleInput();
#if WIFI_ENABLED
processMavlink();
#endif
}
#else
// Code above won't work in the simulation
delay(duration * 1000);
#endif
}
void doCommand(String str, bool echo = false) {
// parse command
String command, arg0, arg1;
splitString(str, command, arg0, arg1);
// echo command
if (echo && !command.isEmpty()) {
print("> %s\n", str.c_str());
}
// execute command
if (command == "help" || command == "motd") {
Serial.println(motd);
print("%s\n", 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()));
print("%s = %g\n", arg0.c_str(), getParameter(arg0.c_str()));
} else if (command == "p") {
bool success = setParameter(arg0.c_str(), arg1.toFloat());
if (success) {
Serial.printf("%s = %g\n", arg0.c_str(), arg1.toFloat());
print("%s = %g\n", arg0.c_str(), arg1.toFloat());
} else {
Serial.printf("Parameter not found: %s\n", arg0.c_str());
print("Parameter not found: %s\n", arg0.c_str());
}
} else if (command == "preset") {
resetParameters();
} else if (command == "time") {
print("Time: %f\n", t);
print("Loop rate: %f\n", loopRate);
print("dt: %f\n", dt);
} else if (command == "ps") {
Vector a = attitude.toEulerZYX();
Serial.printf("roll: %f pitch: %f yaw: %f\n", a.x * RAD_TO_DEG, a.y * RAD_TO_DEG, a.z * RAD_TO_DEG);
print("roll: %f pitch: %f yaw: %f\n", degrees(a.x), degrees(a.y), degrees(a.z));
} else if (command == "psq") {
Serial.printf("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
print("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
} else if (command == "imu") {
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);
print("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
print("acc: %f %f %f\n", acc.x, acc.y, acc.z);
printIMUCal();
Serial.printf("rate: %f\n", loopRate);
print("rate: %f\n", loopRate);
print("landed: %d\n", landed);
} else if (command == "rc") {
Serial.printf("Raw: throttle %d yaw %d pitch %d roll %d armed %d mode %d\n",
channels[RC_CHANNEL_THROTTLE], channels[RC_CHANNEL_YAW], channels[RC_CHANNEL_PITCH],
channels[RC_CHANNEL_ROLL], channels[RC_CHANNEL_ARMED], channels[RC_CHANNEL_MODE]);
Serial.printf("Control: throttle %f yaw %f pitch %f roll %f armed %f mode %f\n",
controls[RC_CHANNEL_THROTTLE], controls[RC_CHANNEL_YAW], controls[RC_CHANNEL_PITCH],
controls[RC_CHANNEL_ROLL], controls[RC_CHANNEL_ARMED], controls[RC_CHANNEL_MODE]);
Serial.printf("Mode: %s\n", getModeName());
print("Raw: throttle %d yaw %d pitch %d roll %d armed %d mode %d\n",
channels[throttleChannel], channels[yawChannel], channels[pitchChannel],
channels[rollChannel], channels[armedChannel], channels[modeChannel]);
print("Control: throttle %g yaw %g pitch %g roll %g armed %g mode %g\n",
controls[throttleChannel], controls[yawChannel], controls[pitchChannel],
controls[rollChannel], controls[armedChannel], controls[modeChannel]);
print("Mode: %s\n", getModeName());
} else if (command == "mot") {
Serial.printf("MOTOR front-right %f front-left %f rear-right %f rear-left %f\n",
print("Motors: front-right %g front-left %g rear-right %g rear-left %g\n",
motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]);
} else if (command == "log") {
dumpLog();
} else if (command == "cr") {
calibrateRC();
} else if (command == "cg") {
calibrateGyro();
} else if (command == "ca") {
calibrateAccel();
} else if (command == "mfr") {
cliTestMotor(MOTOR_FRONT_RIGHT);
testMotor(MOTOR_FRONT_RIGHT);
} else if (command == "mfl") {
cliTestMotor(MOTOR_FRONT_LEFT);
testMotor(MOTOR_FRONT_LEFT);
} else if (command == "mrr") {
cliTestMotor(MOTOR_REAR_RIGHT);
testMotor(MOTOR_REAR_RIGHT);
} else if (command == "mrl") {
cliTestMotor(MOTOR_REAR_LEFT);
testMotor(MOTOR_REAR_LEFT);
} else if (command == "reset") {
attitude = Quaternion();
} else if (command == "reboot") {
@@ -97,48 +141,26 @@ void doCommand(String& command, String& arg0, String& arg1) {
} else if (command == "") {
// do nothing
} else {
Serial.println("Invalid command: " + command);
print("Invalid command: %s\n", command.c_str());
}
}
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() {
void handleInput() {
static bool showMotd = true;
static String input;
if (showMotd) {
Serial.println(motd);
print("%s\n", motd);
showMotd = false;
}
while (Serial.available()) {
char c = Serial.read();
if (c == '\n') {
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);
doCommand(input);
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,6 +7,7 @@
#include "quaternion.h"
#include "pid.h"
#include "lpf.h"
#include "util.h"
#define PITCHRATE_P 0.05
#define PITCHRATE_I 0.2
@@ -29,8 +30,8 @@
#define YAW_P 3
#define PITCHRATE_MAX radians(360)
#define ROLLRATE_MAX radians(360)
#define YAWRATE_MAX radians(360)
#define MAX_TILT radians(30)
#define YAWRATE_MAX radians(300)
#define TILT_MAX radians(30)
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
@@ -44,12 +45,17 @@ PID yawRatePID(YAWRATE_P, YAWRATE_I, YAWRATE_D);
PID rollPID(ROLL_P, ROLL_I, ROLL_D);
PID pitchPID(PITCH_P, PITCH_I, PITCH_D);
PID yawPID(YAW_P, 0, 0);
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
float tiltMax = TILT_MAX;
Quaternion attitudeTarget;
Vector ratesTarget;
Vector torqueTarget;
float thrustTarget;
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
void control() {
interpretRC();
failsafe();
@@ -66,38 +72,39 @@ void control() {
}
void interpretRC() {
armed = controls[RC_CHANNEL_THROTTLE] >= 0.05 && controls[RC_CHANNEL_ARMED] >= 0.5;
armed = controls[throttleChannel] >= 0.05 &&
(controls[armedChannel] >= 0.5 || isnan(controls[armedChannel])); // assume armed if armed channel is not defined
// NOTE: put ACRO or MANUAL modes there if you want to use them
if (controls[RC_CHANNEL_MODE] < 0.25) {
if (controls[modeChannel] < 0.25) {
mode = STAB;
} else if (controls[RC_CHANNEL_MODE] < 0.75) {
} else if (controls[modeChannel] < 0.75) {
mode = STAB;
} else {
mode = STAB;
}
thrustTarget = controls[RC_CHANNEL_THROTTLE];
thrustTarget = controls[throttleChannel];
if (mode == ACRO) {
yawMode = YAW_RATE;
ratesTarget.x = controls[RC_CHANNEL_ROLL] * ROLLRATE_MAX;
ratesTarget.y = controls[RC_CHANNEL_PITCH] * PITCHRATE_MAX;
ratesTarget.z = -controls[RC_CHANNEL_YAW] * YAWRATE_MAX; // positive yaw stick means clockwise rotation in FLU
ratesTarget.x = controls[rollChannel] * maxRate.x;
ratesTarget.y = controls[pitchChannel] * maxRate.y;
ratesTarget.z = -controls[yawChannel] * maxRate.z; // positive yaw stick means clockwise rotation in FLU
} else if (mode == STAB) {
yawMode = controls[RC_CHANNEL_YAW] == 0 ? YAW : YAW_RATE;
yawMode = controls[yawChannel] == 0 ? YAW : YAW_RATE;
attitudeTarget = Quaternion::fromEulerZYX(Vector(
controls[RC_CHANNEL_ROLL] * MAX_TILT,
controls[RC_CHANNEL_PITCH] * MAX_TILT,
controls[rollChannel] * tiltMax,
controls[pitchChannel] * tiltMax,
attitudeTarget.getYaw()));
ratesTarget.z = -controls[RC_CHANNEL_YAW] * YAWRATE_MAX; // positive yaw stick means clockwise rotation in FLU
ratesTarget.z = -controls[yawChannel] * maxRate.z; // positive yaw stick means clockwise rotation in FLU
} else if (mode == MANUAL) {
// passthrough mode
yawMode = YAW_RATE;
torqueTarget = Vector(controls[RC_CHANNEL_ROLL], controls[RC_CHANNEL_PITCH], -controls[RC_CHANNEL_YAW]) * 0.01;
torqueTarget = Vector(controls[rollChannel], controls[pitchChannel], -controls[yawChannel]) * 0.01;
}
if (yawMode == YAW_RATE || !motorsActive()) {
@@ -115,8 +122,8 @@ void controlAttitude() {
}
const Vector up(0, 0, 1);
Vector upActual = attitude.rotate(up);
Vector upTarget = attitudeTarget.rotate(up);
Vector upActual = attitude.rotateVector(up);
Vector upTarget = attitudeTarget.rotateVector(up);
Vector error = Vector::angularRatesBetweenVectors(upTarget, upActual);
@@ -162,10 +169,6 @@ void controlTorque() {
motors[3] = constrain(motors[3], 0, 1);
}
bool motorsActive() {
return motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0;
}
const char* getModeName() {
switch (mode) {
case MANUAL: return "MANUAL";

View File

@@ -6,8 +6,9 @@
#include "quaternion.h"
#include "vector.h"
#include "lpf.h"
#include "util.h"
#define WEIGHT_ACC 0.5f
#define WEIGHT_ACC 0.003
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
@@ -22,23 +23,20 @@ void applyGyro() {
rates = ratesFilter.update(gyro);
// apply rates to attitude
attitude *= Quaternion::fromAngularRates(rates * dt);
attitude.normalize();
attitude = attitude.rotate(Quaternion::fromAngularRates(rates * dt));
}
void applyAcc() {
// test should we apply accelerometer gravity correction
float accNorm = acc.norm();
bool landed = !motorsActive() && abs(accNorm - ONE_G) < ONE_G * 0.1f;
landed = !motorsActive() && abs(accNorm - ONE_G) < ONE_G * 0.1f;
setLED(landed);
if (!landed) return;
// calculate accelerometer correction
Vector up = attitude.rotate(Vector(0, 0, 1));
Vector correction = Vector::angularRatesBetweenVectors(acc, up) * dt * WEIGHT_ACC;
Vector up = attitude.rotateVector(Vector(0, 0, 1));
Vector correction = Vector::angularRatesBetweenVectors(acc, up) * WEIGHT_ACC;
// apply correction
attitude *= Quaternion::fromAngularRates(correction);
attitude.normalize();
attitude = attitude.rotate(Quaternion::fromAngularRates(correction));
}

View File

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

View File

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

View File

@@ -5,6 +5,8 @@
#include <SPI.h>
#include <MPU9250.h>
#include "lpf.h"
#include "util.h"
MPU9250 IMU(SPI);
@@ -13,16 +15,9 @@ Vector gyroBias;
Vector accScale(1, 1, 1);
void setupIMU() {
Serial.println("Setup IMU");
bool status = IMU.begin();
if (!status) {
while (true) {
Serial.println("IMU begin error");
delay(1000);
}
}
print("Setup IMU\n");
IMU.begin();
configureIMU();
// calibrateGyro();
}
void configureIMU() {
@@ -53,48 +48,39 @@ void rotateIMU(Vector& data) {
}
void calibrateGyroOnce() {
if (!landed) return;
static float samples = 0; // overflows after 49 days at 1000 Hz
samples++;
gyroBias = gyroBias + (gyro - gyroBias) / samples; // running average
}
static float landedTime = 0;
landedTime = landed ? landedTime + dt : 0;
if (landedTime < 2) return; // calibrate only if definitely stationary
void calibrateGyro() {
const int samples = 1000;
Serial.println("Calibrating gyro, stand still");
IMU.setGyroRange(IMU.GYRO_RANGE_250DPS); // the most sensitive mode
gyroBias = Vector(0, 0, 0);
for (int i = 0; i < samples; i++) {
IMU.waitForData();
IMU.getGyro(gyro.x, gyro.y, gyro.z);
gyroBias = gyroBias + gyro;
}
gyroBias = gyroBias / samples;
printIMUCal();
configureIMU();
static LowPassFilter<Vector> gyroCalibrationFilter(0.001);
gyroBias = gyroCalibrationFilter.update(gyro);
}
void calibrateAccel() {
Serial.println("Calibrating accelerometer");
print("Calibrating accelerometer\n");
IMU.setAccelRange(IMU.ACCEL_RANGE_2G); // the most sensitive mode
Serial.setTimeout(60000);
Serial.print("Place level [enter] "); Serial.readStringUntil('\n');
print("Place level [8 sec]\n");
pause(8);
calibrateAccelOnce();
Serial.print("Place nose up [enter] "); Serial.readStringUntil('\n');
print("Place nose up [8 sec]\n");
pause(8);
calibrateAccelOnce();
Serial.print("Place nose down [enter] "); Serial.readStringUntil('\n');
print("Place nose down [8 sec]\n");
pause(8);
calibrateAccelOnce();
Serial.print("Place on right side [enter] "); Serial.readStringUntil('\n');
print("Place on right side [8 sec]\n");
pause(8);
calibrateAccelOnce();
Serial.print("Place on left side [enter] "); Serial.readStringUntil('\n');
print("Place on left side [8 sec]\n");
pause(8);
calibrateAccelOnce();
Serial.print("Place upside down [enter] "); Serial.readStringUntil('\n');
print("Place upside down [8 sec]\n");
pause(8);
calibrateAccelOnce();
printIMUCal();
print("✓ Calibration done!\n");
configureIMU();
}
@@ -120,21 +106,19 @@ 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 printIMUCal() {
Serial.printf("gyro bias: %f, %f, %f\n", gyroBias.x, gyroBias.y, gyroBias.z);
Serial.printf("accel bias: %f, %f, %f\n", accBias.x, accBias.y, accBias.z);
Serial.printf("accel scale: %f, %f, %f\n", accScale.x, accScale.y, accScale.z);
print("gyro bias: %f %f %f\n", gyroBias.x, gyroBias.y, gyroBias.z);
print("accel bias: %f %f %f\n", accBias.x, accBias.y, accBias.z);
print("accel scale: %f %f %f\n", accScale.x, accScale.y, accScale.z);
}
void printIMUInfo() {
Serial.printf("model: %s\n", IMU.getModel());
Serial.printf("who am I: 0x%02X\n", IMU.whoAmI());
IMU.status() ? print("status: ERROR %d\n", IMU.status()) : print("status: OK\n");
print("model: %s\n", IMU.getModel());
print("who am I: 0x%02X\n", IMU.whoAmI());
}

View File

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

View File

@@ -3,7 +3,7 @@
// MAVLink communication
#if WIFI_ENABLED == 1
#if WIFI_ENABLED
#include <MAVLink.h>
@@ -13,14 +13,19 @@
#define MAVLINK_CONTROL_SCALE 0.7f
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
float mavlinkControlScale = 0.7;
extern double controlsTime;
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
void processMavlink() {
sendMavlink();
receiveMavlink();
}
void sendMavlink() {
static float lastSlow = 0;
static float lastFast = 0;
static double lastSlow = 0;
static double lastFast = 0;
mavlink_message_t msg;
uint32_t time = t * 1000;
@@ -28,22 +33,26 @@ 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 : 0),
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),
0, MAV_STATE_STANDBY);
sendMessage(&msg);
mavlink_msg_extended_sys_state_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
MAV_VTOL_STATE_UNDEFINED, landed ? MAV_LANDED_STATE_ON_GROUND : MAV_LANDED_STATE_IN_AIR);
sendMessage(&msg);
}
if (t - lastFast >= PERIOD_FAST) {
lastFast = t;
const float zeroQuat[] = {0, 0, 0, 0};
Quaternion attitudeFRD = FLU2FRD(attitude); // MAVLink uses FRD coordinate system
Quaternion att = fluToFrd(attitude); // MAVLink uses FRD coordinate system
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
time, attitudeFRD.w, attitudeFRD.x, attitudeFRD.y, attitudeFRD.z, rates.x, rates.y, rates.z, zeroQuat);
time, att.w, att.x, att.y, att.z, rates.x, rates.y, rates.z, zeroQuat);
sendMessage(&msg);
mavlink_msg_rc_channels_scaled_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0,
mavlink_msg_rc_channels_scaled_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, controlsTime * 1000, 0,
controls[0] * 10000, controls[1] * 10000, controls[2] * 10000,
controls[3] * 10000, controls[4] * 10000, controls[5] * 10000,
INT16_MAX, INT16_MAX, UINT8_MAX);
@@ -83,23 +92,29 @@ void receiveMavlink() {
}
void handleMavlink(const void *_msg) {
mavlink_message_t *msg = (mavlink_message_t *)_msg;
const mavlink_message_t& msg = *(mavlink_message_t *)_msg;
if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
mavlink_manual_control_t manualControl;
mavlink_msg_manual_control_decode(msg, &manualControl);
controls[RC_CHANNEL_THROTTLE] = manualControl.z / 1000.0f;
controls[RC_CHANNEL_PITCH] = manualControl.x / 1000.0f * MAVLINK_CONTROL_SCALE;
controls[RC_CHANNEL_ROLL] = manualControl.y / 1000.0f * MAVLINK_CONTROL_SCALE;
controls[RC_CHANNEL_YAW] = manualControl.r / 1000.0f * MAVLINK_CONTROL_SCALE;
controls[RC_CHANNEL_MODE] = 1; // STAB mode
controls[RC_CHANNEL_ARMED] = 1; // armed
if (msg.msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
mavlink_manual_control_t m;
mavlink_msg_manual_control_decode(&msg, &m);
if (m.target && m.target != SYSTEM_ID) return; // 0 is broadcast
controls[throttleChannel] = m.z / 1000.0f;
controls[pitchChannel] = m.x / 1000.0f * mavlinkControlScale;
controls[rollChannel] = m.y / 1000.0f * mavlinkControlScale;
controls[yawChannel] = m.r / 1000.0f * mavlinkControlScale;
controls[modeChannel] = 1; // STAB mode
controls[armedChannel] = 1; // armed
controlsTime = t;
if (abs(controls[RC_CHANNEL_YAW]) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controls[RC_CHANNEL_YAW] = 0;
if (abs(controls[yawChannel]) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controls[yawChannel] = 0;
}
if (msg->msgid == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
mavlink_param_request_list_t m;
mavlink_msg_param_request_list_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
mavlink_message_t msg;
for (int i = 0; i < parametersCount(); i++) {
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
@@ -108,62 +123,94 @@ void handleMavlink(const void *_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);
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_READ) {
mavlink_param_request_read_t m;
mavlink_msg_param_request_read_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
char name[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
float value = strlen(name) == 0 ? getParameter(m.param_index) : getParameter(name);
if (m.param_index != -1) {
memcpy(name, getParameterName(m.param_index), 16);
}
mavlink_message_t msg;
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
name, value, MAV_PARAM_TYPE_REAL32, parametersCount(), paramRequestRead.param_index);
name, value, MAV_PARAM_TYPE_REAL32, parametersCount(), m.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);
if (msg.msgid == MAVLINK_MSG_ID_PARAM_SET) {
mavlink_param_set_t m;
mavlink_msg_param_set_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
char name[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN + 1];
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
setParameter(name, m.param_value);
// send ack
mavlink_message_t msg;
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
paramSet.param_id, paramSet.param_value, MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
m.param_id, m.param_value, MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
sendMessage(&msg);
}
if (msg->msgid == MAVLINK_MSG_ID_MISSION_REQUEST_LIST) { // handle to make qgc happy
if (msg.msgid == MAVLINK_MSG_ID_MISSION_REQUEST_LIST) { // handle to make qgc happy
mavlink_mission_request_list_t m;
mavlink_msg_mission_request_list_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
mavlink_message_t msg;
mavlink_msg_mission_count_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, 0, 0, 0, MAV_MISSION_TYPE_MISSION, 0);
sendMessage(&msg);
}
if (msg.msgid == MAVLINK_MSG_ID_SERIAL_CONTROL) {
mavlink_serial_control_t m;
mavlink_msg_serial_control_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
strlcpy(data, (const char *)m.data, m.count); // data might be not null-terminated
doCommand(data, true);
}
// Handle commands
if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
mavlink_command_long_t commandLong;
mavlink_msg_command_long_decode(msg, &commandLong);
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
mavlink_command_long_t m;
mavlink_msg_command_long_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
mavlink_message_t ack;
mavlink_message_t response;
if (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);
if (m.command == MAV_CMD_REQUEST_MESSAGE && m.param1 == MAVLINK_MSG_ID_AUTOPILOT_VERSION) {
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
sendMessage(&ack);
mavlink_msg_autopilot_version_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &response,
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MAVLINK2, 1, 0, 1, 1, 0, 0, 0, 0, 0, 0, 0);
sendMessage(&response);
} else {
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, commandLong.command, MAV_RESULT_UNSUPPORTED, UINT8_MAX, 0, msg->sysid, msg->compid);
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_UNSUPPORTED, UINT8_MAX, 0, msg.sysid, msg.compid);
sendMessage(&ack);
}
}
}
// Send shell output to GCS
void mavlinkPrint(const char* str) {
// Send data in chunks
for (int i = 0; i < strlen(str); i += MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN) {
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
strlcpy(data, str + i, sizeof(data));
mavlink_message_t msg;
mavlink_msg_serial_control_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
SERIAL_CONTROL_DEV_SHELL, 0, 0, 0, strlen(data), (uint8_t *)data, 0, 0);
sendMessage(&msg);
}
}
// Convert Forward-Left-Up to Forward-Right-Down quaternion
inline Quaternion FLU2FRD(const Quaternion &q) {
inline Quaternion fluToFrd(const Quaternion &q) {
return Quaternion(q.w, q.x, -q.y, -q.z);
}

View File

@@ -2,19 +2,29 @@
// Repository: https://github.com/okalachev/flix
// Motors output control using MOSFETs
// In case of using ESC, use this version of the code: https://gist.github.com/okalachev/8871d3a94b6b6c0a298f41a4edd34c61.
// Motor: 8520 3.7V
// In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400)
#include "util.h"
#define MOTOR_0_PIN 12 // rear left
#define MOTOR_1_PIN 13 // rear right
#define MOTOR_2_PIN 14 // front right
#define MOTOR_3_PIN 15 // front left
#define PWM_FREQUENCY 200
#define PWM_RESOLUTION 8
#define PWM_FREQUENCY 1000
#define PWM_RESOLUTION 12
#define PWM_STOP 0
#define PWM_MIN 0
#define PWM_MAX 1000000 / PWM_FREQUENCY
// Motors array indexes:
const int MOTOR_REAR_LEFT = 0;
const int MOTOR_REAR_RIGHT = 1;
const int MOTOR_FRONT_RIGHT = 2;
const int MOTOR_FRONT_LEFT = 3;
void setupMotors() {
Serial.println("Setup Motors");
print("Setup Motors\n");
// configure pins
ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
@@ -23,17 +33,35 @@ void setupMotors() {
ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
sendMotors();
Serial.println("Motors initialized");
print("Motors initialized\n");
}
uint8_t signalToDutyCycle(float control) {
float duty = mapff(control, 0, 1, 0, (1 << PWM_RESOLUTION) - 1);
return round(constrain(duty, 0, (1 << PWM_RESOLUTION) - 1));
int getDutyCycle(float value) {
value = constrain(value, 0, 1);
float pwm = mapff(value, 0, 1, PWM_MIN, PWM_MAX);
if (value == 0) pwm = PWM_STOP;
float duty = mapff(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
return round(duty);
}
void sendMotors() {
ledcWrite(MOTOR_0_PIN, signalToDutyCycle(motors[0]));
ledcWrite(MOTOR_1_PIN, signalToDutyCycle(motors[1]));
ledcWrite(MOTOR_2_PIN, signalToDutyCycle(motors[2]));
ledcWrite(MOTOR_3_PIN, signalToDutyCycle(motors[3]));
ledcWrite(MOTOR_0_PIN, getDutyCycle(motors[0]));
ledcWrite(MOTOR_1_PIN, getDutyCycle(motors[1]));
ledcWrite(MOTOR_2_PIN, getDutyCycle(motors[2]));
ledcWrite(MOTOR_3_PIN, getDutyCycle(motors[3]));
}
bool motorsActive() {
return motors[0] != 0 || motors[1] != 0 || motors[2] != 0 || motors[3] != 0;
}
void testMotor(uint8_t n) {
print("Testing motor %d\n", n);
motors[n] = 1;
delay(50); // ESP32 may need to wait until the end of the current cycle to change duty https://github.com/espressif/arduino-esp32/issues/5306
sendMotors();
pause(3);
motors[n] = 0;
sendMotors();
print("Done\n");
}

View File

@@ -1,10 +1,13 @@
#pragma once
// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Parameters storage in flash memory
#include <Preferences.h>
#include <vector>
extern float channelNeutral[RC_CHANNELS];
extern float channelMax[RC_CHANNELS];
extern float channelNeutral[16];
extern float channelMax[16];
extern float mavlinkControlScale;
Preferences storage;
@@ -34,6 +37,10 @@ Parameter parameters[] = {
{"PITCH_I", &pitchPID.i},
{"PITCH_D", &pitchPID.d},
{"YAW_P", &yawPID.p},
{"PITCHRATE_MAX", &maxRate.y},
{"ROLLRATE_MAX", &maxRate.x},
{"YAWRATE_MAX", &maxRate.z},
{"TILT_MAX", &tiltMax},
// imu
{"ACC_BIAS_X", &accBias.x},
{"ACC_BIAS_Y", &accBias.y},
@@ -41,9 +48,6 @@ Parameter parameters[] = {
{"ACC_SCALE_X", &accScale.x},
{"ACC_SCALE_Y", &accScale.y},
{"ACC_SCALE_Z", &accScale.z},
// {"GYRO_BIAS_X", &gyroBias.x},
// {"GYRO_BIAS_Y", &gyroBias.y},
// {"GYRO_BIAS_Z", &gyroBias.z},
// rc
{"RC_NEUTRAL_0", &channelNeutral[0]},
{"RC_NEUTRAL_1", &channelNeutral[1]},
@@ -60,7 +64,11 @@ Parameter parameters[] = {
{"RC_MAX_4", &channelMax[4]},
{"RC_MAX_5", &channelMax[5]},
{"RC_MAX_6", &channelMax[6]},
{"RC_MAX_7", &channelMax[7]}
{"RC_MAX_7", &channelMax[7]},
#if WIFI_ENABLED
// MAVLink
{"MAV_CTRL_SCALE", &mavlinkControlScale},
#endif
};
void setupParameters() {
@@ -68,7 +76,6 @@ void setupParameters() {
// 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);
@@ -81,10 +88,12 @@ int parametersCount() {
}
const char *getParameterName(int index) {
if (index < 0 || index >= parametersCount()) return "";
return parameters[index].name;
}
float getParameter(int index) {
if (index < 0 || index >= parametersCount()) return NAN;
return *parameters[index].variable;
}
@@ -107,11 +116,11 @@ bool setParameter(const char *name, const float value) {
return false;
}
void flushParameters() {
static float lastFlush = 0;
if (t - lastFlush < 1) return; // flush once per second
void syncParameters() {
static double lastSync = 0;
if (t - lastSync < 1) return; // sync once per second
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
lastFlush = t;
lastSync = t;
for (auto &parameter : parameters) {
if (parameter.value == *parameter.variable) continue;
@@ -123,7 +132,7 @@ void flushParameters() {
void printParameters() {
for (auto &parameter : parameters) {
Serial.printf("%s = %g\n", parameter.name, *parameter.variable);
print("%s = %g\n", parameter.name, *parameter.variable);
}
}

View File

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

View File

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

View File

@@ -3,8 +3,10 @@
// Time related functions
float loopRate; // Hz
void step() {
float now = micros() / 1000000.0;
double now = micros() / 1000000.0;
dt = now - t;
t = now;
@@ -16,7 +18,7 @@ void step() {
}
void computeLoopRate() {
static float windowStart = 0;
static double windowStart = 0;
static uint32_t rate = 0;
rate++;
if (t - windowStart >= 1) { // 1 second window

View File

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

View File

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

View File

@@ -3,7 +3,7 @@
// Wi-Fi support
#if WIFI_ENABLED == 1
#if WIFI_ENABLED
#include <WiFi.h>
#include <WiFiAP.h>
@@ -17,13 +17,13 @@
WiFiUDP udp;
void setupWiFi() {
Serial.println("Setup Wi-Fi");
print("Setup Wi-Fi\n");
WiFi.softAP(WIFI_SSID, WIFI_PASSWORD);
IPAddress myIP = WiFi.softAPIP();
udp.begin(WIFI_UDP_PORT);
}
void sendWiFi(const uint8_t *buf, int len) {
if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return;
udp.beginPacket(WIFI_UDP_IP, WIFI_UDP_PORT);
udp.write(buf, len);
udp.endPacket();

View File

@@ -41,13 +41,17 @@ class __FlashStringHelper;
// https://www.arduino.cc/reference/en/language/variables/data-types/stringobject/
class String: public std::string {
public:
String(const char *str = "") : std::string(str) {}
String(const char *str = "") : std::string(str ? 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);
}
void trim() {
this->erase(0, this->find_first_not_of(" \t\n\r"));
this->erase(this->find_last_not_of(" \t\n\r") + 1);
}
};
class Print;
@@ -111,7 +115,7 @@ public:
class HardwareSerial: public Print {
public:
void begin(unsigned long baud) {
// server is running in background by default, so doesn't have access to stdin
// server is running in background by default, so it 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
@@ -150,6 +154,9 @@ 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;

View File

@@ -36,8 +36,6 @@ public:
return true;
}
void end();
bool isKey(const char *key) {
return storage.find(key) != storage.end();
}

View File

@@ -14,7 +14,7 @@ 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 joystickInitialized; };
bool read() { return joystickInit(); };
SBUSData data() {
SBUSData data;
joystickGet(data.ch);

View File

@@ -10,30 +10,21 @@
#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;
double t = NAN;
float dt;
float loopRate;
float motors[4];
int16_t channels[16]; // raw rc channels
float controls[RC_CHANNELS];
float controlsTime;
float controls[16];
Vector acc;
Vector gyro;
Vector rates;
Quaternion attitude;
bool landed;
// declarations
void step();
void computeLoopRate();
void applyGyro();
void applyAcc();
@@ -42,26 +33,41 @@ void interpretRC();
void controlAttitude();
void controlRate();
void controlTorque();
void showTable();
const char* getModeName();
void sendMotors();
bool motorsActive();
void cliTestMotor(uint8_t n);
String stringToken(char* str, const char* delim);
void testMotor(uint8_t n);
void print(const char* format, ...);
void pause(float duration);
void doCommand(String str, bool echo);
void handleInput();
void calibrateRC();
void normalizeRC();
void printRCCal();
void dumpLog();
void processMavlink();
void sendMavlink();
void sendMessage(const void *msg);
void receiveMavlink();
void handleMavlink(const void *_msg);
void mavlinkPrint(const char* str);
inline Quaternion fluToFrd(const Quaternion &q);
void failsafe();
void armingFailsafe();
void rcLossFailsafe();
void descend();
inline Quaternion FLU2FRD(const Quaternion &q);
int parametersCount();
const char *getParameterName(int index);
float getParameter(int index);
float getParameter(const char *name);
bool setParameter(const char *name, const float value);
void printParameters();
void resetParameters();
// mocks
void setLED(bool on) {};
void calibrateGyro() { printf("Skip gyro calibrating\n"); };
void calibrateAccel() { printf("Skip accel calibrating\n"); };
void sendMotors() {};
void printIMUCal() { printf("cal: N/A\n"); };
void calibrateGyro() { print("Skip gyro calibrating\n"); };
void calibrateAccel() { print("Skip accel calibrating\n"); };
void printIMUCal() { print("cal: N/A\n"); };
void printIMUInfo() {};
Vector accBias, gyroBias, accScale(1, 1, 1);

View File

@@ -7,17 +7,13 @@
#include <gazebo/gazebo.hh>
#include <iostream>
#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 joystickInit() {
bool joystickInit() {
static bool joystickInitialized = false;
static bool warnShown = false;
if (joystickInitialized) return true;
SDL_Init(SDL_INIT_JOYSTICK);
joystick = SDL_JoystickOpen(0);
if (joystick != NULL) {
@@ -27,17 +23,13 @@ void joystickInit() {
gzwarn << "Joystick not found, begin waiting for joystick..." << std::endl;
warnShown = true;
}
return joystickInitialized;
}
bool joystickGet(int16_t ch[16]) {
if (!joystickInitialized) {
joystickInit();
return false;
}
SDL_JoystickUpdate();
for (uint8_t i = 0; i < sizeof(channels) / sizeof(channels[0]); i++) {
for (uint8_t i = 0; i < 16; i++) {
ch[i] = SDL_JoystickGetAxis(joystick, i);
}
return true;

View File

@@ -1,6 +1,7 @@
<?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>
@@ -23,38 +24,14 @@
<update_rate>1000</update_rate>
<imu>
<angular_velocity>
<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>
<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>
</angular_velocity>
<linear_acceleration>
<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>
<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>
</linear_acceleration>
</imu>
</sensor>
@@ -90,6 +67,5 @@
<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,17 +17,18 @@
#include "Arduino.h"
#include "flix.h"
#include "util.ino"
#include "cli.ino"
#include "control.ino"
#include "estimate.ino"
#include "failsafe.ino"
#include "log.ino"
#include "lpf.h"
#include "mavlink.ino"
#include "motors.ino"
#include "parameters.ino"
#include "rc.ino"
#include "time.ino"
#include "estimate.ino"
#include "control.ino"
#include "log.ino"
#include "parameters.ino"
#include "cli.ino"
#include "mavlink.ino"
#include "failsafe.ino"
#include "lpf.h"
using ignition::math::Vector3d;
using namespace gazebo;
@@ -72,8 +73,8 @@ public:
// read rc
readRC();
controls[RC_CHANNEL_MODE] = 1; // 0 acro, 1 stab
controls[RC_CHANNEL_ARMED] = 1; // armed
controls[modeChannel] = 1; // 0 acro, 1 stab
controls[armedChannel] = 1; // armed
estimate();
@@ -81,13 +82,13 @@ public:
attitude.setYaw(this->model->WorldPose().Yaw());
control();
parseInput();
handleInput();
processMavlink();
applyMotorForces();
publishTopics();
logData();
flushParameters();
syncParameters();
}
void applyMotorForces() {

View File

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

View File

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

View File

@@ -22,7 +22,10 @@ void setupWiFi() {
addr.sin_family = AF_INET;
addr.sin_addr.s_addr = INADDR_ANY;
addr.sin_port = htons(WIFI_UDP_PORT_LOCAL);
bind(wifiSocket, (sockaddr *)&addr, sizeof(addr));
if (bind(wifiSocket, (sockaddr *)&addr, sizeof(addr))) {
gzerr << "Failed to bind WiFi UDP socket on port " << WIFI_UDP_PORT_LOCAL << std::endl;
return;
}
int broadcast = 1;
setsockopt(wifiSocket, SOL_SOCKET, SO_BROADCAST, &broadcast, sizeof(broadcast)); // enable broadcast
gzmsg << "WiFi UDP socket initialized on port " << WIFI_UDP_PORT_LOCAL << " (remote port " << WIFI_UDP_PORT_REMOTE << ")" << std::endl;