Compare commits
30 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
99c891e1cd | ||
|
|
378db51de9 | ||
|
|
8a83d70bb6 | ||
|
|
ba5ac30136 | ||
|
|
baf724ed6e | ||
|
|
af58d56138 | ||
|
|
13341602f0 | ||
|
|
84368738b4 | ||
|
|
0397b3a736 | ||
|
|
c41c96a96d | ||
|
|
a94687bd56 | ||
|
|
abcc9b96de | ||
|
|
f46460e53d | ||
|
|
23f3295439 | ||
|
|
b0b6eb9a97 | ||
|
|
84a329cca7 | ||
|
|
5613028678 | ||
|
|
a0cca80980 | ||
|
|
bed5d79db8 | ||
|
|
da51ebab38 | ||
|
|
0b977aee28 | ||
|
|
6ef8820770 | ||
|
|
e993dde355 | ||
|
|
627233f862 | ||
|
|
ce87234a51 | ||
|
|
e40fbd0ce2 | ||
|
|
0938609dc7 | ||
|
|
1a22350775 | ||
|
|
72b2cf49d5 | ||
|
|
63d602dd7a |
@@ -4,7 +4,7 @@ root = true
|
|||||||
end_of_line = lf
|
end_of_line = lf
|
||||||
insert_final_newline = true
|
insert_final_newline = true
|
||||||
|
|
||||||
[*.{ino,cpp,c,h,hpp,sdf,world}]
|
[*.{ino,cpp,c,h,hpp,sdf,world,json}]
|
||||||
charset = utf-8
|
charset = utf-8
|
||||||
indent_style = tab
|
indent_style = tab
|
||||||
tab_width = 4
|
tab_width = 4
|
||||||
|
|||||||
24
.github/workflows/build.yml
vendored
@@ -7,49 +7,53 @@ on:
|
|||||||
branches: [ master ]
|
branches: [ master ]
|
||||||
|
|
||||||
jobs:
|
jobs:
|
||||||
build:
|
build_linux:
|
||||||
runs-on: ubuntu-latest
|
runs-on: ubuntu-latest
|
||||||
steps:
|
steps:
|
||||||
- uses: actions/checkout@v3
|
- uses: actions/checkout@v4
|
||||||
- name: Install Arduino CLI
|
- name: Install Arduino CLI
|
||||||
run: curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=/usr/local/bin sh
|
run: curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=/usr/local/bin sh
|
||||||
- name: Build firmware
|
- name: Build firmware
|
||||||
run: make
|
run: make
|
||||||
|
- name: Check c_cpp_properties.json
|
||||||
|
run: tools/check_c_cpp_properties.py
|
||||||
|
|
||||||
build_macos:
|
build_macos:
|
||||||
runs-on: macos-latest
|
runs-on: macos-latest
|
||||||
steps:
|
steps:
|
||||||
- uses: actions/checkout@v3
|
- uses: actions/checkout@v4
|
||||||
- name: Install Arduino CLI
|
- name: Install Arduino CLI
|
||||||
run: brew install arduino-cli
|
run: brew install arduino-cli
|
||||||
- name: Build firmware
|
- name: Build firmware
|
||||||
run: make
|
run: make
|
||||||
|
- name: Check c_cpp_properties.json
|
||||||
|
run: tools/check_c_cpp_properties.py
|
||||||
|
|
||||||
build_windows:
|
build_windows:
|
||||||
runs-on: windows-latest
|
runs-on: windows-latest
|
||||||
steps:
|
steps:
|
||||||
- uses: actions/checkout@v3
|
- uses: actions/checkout@v4
|
||||||
- name: Install Arduino CLI
|
- name: Install Arduino CLI
|
||||||
run: choco install arduino-cli
|
run: choco install arduino-cli
|
||||||
- name: Install Make
|
- name: Install Make
|
||||||
run: choco install make
|
run: choco install make
|
||||||
- name: Build firmware
|
- name: Build firmware
|
||||||
run: make
|
run: make
|
||||||
|
- name: Check c_cpp_properties.json
|
||||||
|
run: python3 tools/check_c_cpp_properties.py
|
||||||
|
|
||||||
build_simulator:
|
build_simulator:
|
||||||
runs-on: ubuntu-latest
|
runs-on: ubuntu-latest
|
||||||
steps:
|
steps:
|
||||||
- name: Install Arduino CLI
|
- name: Install Arduino CLI
|
||||||
uses: arduino/setup-arduino-cli@v1.1.1
|
uses: arduino/setup-arduino-cli@v1.1.1
|
||||||
- uses: actions/checkout@v3
|
- uses: actions/checkout@v4
|
||||||
- name: Install Gazebo
|
- name: Install Gazebo
|
||||||
run: curl -sSL http://get.gazebosim.org | sh
|
run: curl -sSL http://get.gazebosim.org | sh
|
||||||
- name: Install SDL2
|
- name: Install SDL2
|
||||||
run: sudo apt-get install libsdl2-dev
|
run: sudo apt-get install libsdl2-dev
|
||||||
- name: Build simulator
|
- name: Build simulator
|
||||||
run: make build_simulator
|
run: make build_simulator
|
||||||
- name: Run simulator
|
|
||||||
run: timeout --preserve-status 30 make simulator GAZEBO=gzserver || [ $? -eq 143 ]
|
|
||||||
- uses: actions/upload-artifact@v3
|
- uses: actions/upload-artifact@v3
|
||||||
with:
|
with:
|
||||||
name: gazebo-plugin-binary
|
name: gazebo-plugin-binary
|
||||||
@@ -61,7 +65,7 @@ jobs:
|
|||||||
steps:
|
steps:
|
||||||
- name: Install Arduino CLI
|
- name: Install Arduino CLI
|
||||||
run: brew install arduino-cli
|
run: brew install arduino-cli
|
||||||
- uses: actions/checkout@v3
|
- uses: actions/checkout@v4
|
||||||
- name: Clean up python binaries # Workaround for https://github.com/actions/setup-python/issues/577
|
- name: Clean up python binaries # Workaround for https://github.com/actions/setup-python/issues/577
|
||||||
run: |
|
run: |
|
||||||
rm -f /usr/local/bin/2to3*
|
rm -f /usr/local/bin/2to3*
|
||||||
@@ -75,7 +79,3 @@ jobs:
|
|||||||
run: brew install sdl2
|
run: brew install sdl2
|
||||||
- name: Build simulator
|
- name: Build simulator
|
||||||
run: make build_simulator
|
run: make build_simulator
|
||||||
- name: Run simulator
|
|
||||||
run: |
|
|
||||||
brew install coreutils
|
|
||||||
timeout --preserve-status 30 make simulator GAZEBO=gzserver || [ $? -eq 143 ]
|
|
||||||
|
|||||||
33
.github/workflows/tools.yml
vendored
Normal file
@@ -0,0 +1,33 @@
|
|||||||
|
name: Build tools
|
||||||
|
|
||||||
|
on:
|
||||||
|
push:
|
||||||
|
branches: [ '*' ]
|
||||||
|
pull_request:
|
||||||
|
branches: [ master ]
|
||||||
|
|
||||||
|
jobs:
|
||||||
|
csv_to_ulog:
|
||||||
|
runs-on: ubuntu-latest
|
||||||
|
steps:
|
||||||
|
- uses: actions/checkout@v4
|
||||||
|
- name: Build csv_to_ulog
|
||||||
|
run: cd tools/csv_to_ulog && mkdir build && cd build && cmake .. && make
|
||||||
|
- name: Test csv_to_ulog
|
||||||
|
run: |
|
||||||
|
cd tools/csv_to_ulog/build
|
||||||
|
echo -e "t,x,y,z\n0,1,2,3\n1,4,5,6" > log.csv
|
||||||
|
./csv_to_ulog log.csv
|
||||||
|
test $(stat -c %s log.ulg) -eq 196
|
||||||
|
python_tools:
|
||||||
|
runs-on: ubuntu-latest
|
||||||
|
steps:
|
||||||
|
- uses: actions/checkout@v4
|
||||||
|
- name: Install Python dependencies
|
||||||
|
run: pip install -r tools/requirements.txt
|
||||||
|
- name: Test csv_to_mcap tool
|
||||||
|
run: |
|
||||||
|
cd tools
|
||||||
|
echo -e "t,x,y,z\n0,1,2,3\n1,4,5,6" > log.csv
|
||||||
|
./csv_to_mcap.py log.csv
|
||||||
|
test $(stat -c %s log.mcap) -eq 883
|
||||||
7
.gitignore
vendored
@@ -3,3 +3,10 @@
|
|||||||
build/
|
build/
|
||||||
tools/log/
|
tools/log/
|
||||||
.dependencies
|
.dependencies
|
||||||
|
.vscode/*
|
||||||
|
!.vscode/settings.json
|
||||||
|
!.vscode/c_cpp_properties.json
|
||||||
|
!.vscode/tasks.json
|
||||||
|
!.vscode/launch.json
|
||||||
|
!.vscode/extensions.json
|
||||||
|
!.vscode/intellisense.h
|
||||||
|
|||||||
147
.vscode/c_cpp_properties.json
vendored
Normal file
@@ -0,0 +1,147 @@
|
|||||||
|
{
|
||||||
|
"configurations": [
|
||||||
|
{
|
||||||
|
"name": "Linux",
|
||||||
|
"includePath": [
|
||||||
|
"${workspaceFolder}/flix",
|
||||||
|
"${workspaceFolder}/gazebo",
|
||||||
|
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32",
|
||||||
|
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/libraries/**",
|
||||||
|
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32",
|
||||||
|
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/**",
|
||||||
|
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/dio_qspi/include",
|
||||||
|
"~/Arduino/libraries/**",
|
||||||
|
"/usr/include/**"
|
||||||
|
],
|
||||||
|
"forcedInclude": [
|
||||||
|
"${workspaceFolder}/.vscode/intellisense.h",
|
||||||
|
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32/Arduino.h",
|
||||||
|
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32/pins_arduino.h",
|
||||||
|
"${workspaceFolder}/flix/cli.ino",
|
||||||
|
"${workspaceFolder}/flix/control.ino",
|
||||||
|
"${workspaceFolder}/flix/estimate.ino",
|
||||||
|
"${workspaceFolder}/flix/flix.ino",
|
||||||
|
"${workspaceFolder}/flix/imu.ino",
|
||||||
|
"${workspaceFolder}/flix/led.ino",
|
||||||
|
"${workspaceFolder}/flix/log.ino",
|
||||||
|
"${workspaceFolder}/flix/mavlink.ino",
|
||||||
|
"${workspaceFolder}/flix/motors.ino",
|
||||||
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
|
"${workspaceFolder}/flix/time.ino",
|
||||||
|
"${workspaceFolder}/flix/util.ino",
|
||||||
|
"${workspaceFolder}/flix/wifi.ino"
|
||||||
|
],
|
||||||
|
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2302/bin/xtensa-esp32-elf-g++",
|
||||||
|
"cStandard": "c11",
|
||||||
|
"cppStandard": "c++17",
|
||||||
|
"defines": [
|
||||||
|
"F_CPU=240000000L",
|
||||||
|
"ARDUINO=10607",
|
||||||
|
"ARDUINO_D1_MINI32",
|
||||||
|
"ARDUINO_ARCH_ESP32",
|
||||||
|
"ARDUINO_BOARD=D1_MINI32",
|
||||||
|
"ARDUINO_VARIANT=d1_mini32",
|
||||||
|
"ARDUINO_PARTITION_default",
|
||||||
|
"ESP32",
|
||||||
|
"CORE_DEBUG_LEVEL=0",
|
||||||
|
"ARDUINO_USB_CDC_ON_BOOT="
|
||||||
|
]
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "Mac",
|
||||||
|
"includePath": [
|
||||||
|
"${workspaceFolder}/flix",
|
||||||
|
"${workspaceFolder}/gazebo",
|
||||||
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32",
|
||||||
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/libraries/**",
|
||||||
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32",
|
||||||
|
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/include/**",
|
||||||
|
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/dio_qspi/include",
|
||||||
|
"~/Documents/Arduino/libraries/**",
|
||||||
|
"/opt/homebrew/include/**"
|
||||||
|
],
|
||||||
|
"forcedInclude": [
|
||||||
|
"${workspaceFolder}/.vscode/intellisense.h",
|
||||||
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32/Arduino.h",
|
||||||
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32/pins_arduino.h",
|
||||||
|
"${workspaceFolder}/flix/flix.ino",
|
||||||
|
"${workspaceFolder}/flix/cli.ino",
|
||||||
|
"${workspaceFolder}/flix/control.ino",
|
||||||
|
"${workspaceFolder}/flix/estimate.ino",
|
||||||
|
"${workspaceFolder}/flix/imu.ino",
|
||||||
|
"${workspaceFolder}/flix/led.ino",
|
||||||
|
"${workspaceFolder}/flix/log.ino",
|
||||||
|
"${workspaceFolder}/flix/mavlink.ino",
|
||||||
|
"${workspaceFolder}/flix/motors.ino",
|
||||||
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
|
"${workspaceFolder}/flix/time.ino",
|
||||||
|
"${workspaceFolder}/flix/util.ino",
|
||||||
|
"${workspaceFolder}/flix/wifi.ino"
|
||||||
|
],
|
||||||
|
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2302/bin/xtensa-esp32-elf-g++",
|
||||||
|
"cStandard": "c11",
|
||||||
|
"cppStandard": "c++17",
|
||||||
|
"defines": [
|
||||||
|
"F_CPU=240000000L",
|
||||||
|
"ARDUINO=10607",
|
||||||
|
"ARDUINO_D1_MINI32",
|
||||||
|
"ARDUINO_ARCH_ESP32",
|
||||||
|
"ARDUINO_BOARD=D1_MINI32",
|
||||||
|
"ARDUINO_VARIANT=d1_mini32",
|
||||||
|
"ARDUINO_PARTITION_default",
|
||||||
|
"ARDUINO_FQBN=esp32:esp32:d1_mini32",
|
||||||
|
"ESP32",
|
||||||
|
"CORE_DEBUG_LEVEL=0",
|
||||||
|
"ARDUINO_USB_CDC_ON_BOOT="
|
||||||
|
]
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "Win32",
|
||||||
|
"includePath": [
|
||||||
|
"${workspaceFolder}/flix",
|
||||||
|
"${workspaceFolder}/gazebo",
|
||||||
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32",
|
||||||
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/libraries/**",
|
||||||
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32",
|
||||||
|
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/**",
|
||||||
|
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/dio_qspi/include",
|
||||||
|
"~/Documents/Arduino/libraries/**"
|
||||||
|
],
|
||||||
|
"forcedInclude": [
|
||||||
|
"${workspaceFolder}/.vscode/intellisense.h",
|
||||||
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32/Arduino.h",
|
||||||
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32/pins_arduino.h",
|
||||||
|
"${workspaceFolder}/flix/cli.ino",
|
||||||
|
"${workspaceFolder}/flix/control.ino",
|
||||||
|
"${workspaceFolder}/flix/estimate.ino",
|
||||||
|
"${workspaceFolder}/flix/flix.ino",
|
||||||
|
"${workspaceFolder}/flix/imu.ino",
|
||||||
|
"${workspaceFolder}/flix/led.ino",
|
||||||
|
"${workspaceFolder}/flix/log.ino",
|
||||||
|
"${workspaceFolder}/flix/mavlink.ino",
|
||||||
|
"${workspaceFolder}/flix/motors.ino",
|
||||||
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
|
"${workspaceFolder}/flix/time.ino",
|
||||||
|
"${workspaceFolder}/flix/util.ino",
|
||||||
|
"${workspaceFolder}/flix/wifi.ino"
|
||||||
|
],
|
||||||
|
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2302/bin/xtensa-esp32-elf-g++.exe",
|
||||||
|
"cStandard": "c11",
|
||||||
|
"cppStandard": "c++17",
|
||||||
|
"defines": [
|
||||||
|
"F_CPU=240000000L",
|
||||||
|
"ARDUINO=10607",
|
||||||
|
"ARDUINO_D1_MINI32",
|
||||||
|
"ARDUINO_ARCH_ESP32",
|
||||||
|
"ARDUINO_BOARD=D1_MINI32",
|
||||||
|
"ARDUINO_VARIANT=d1_mini32",
|
||||||
|
"ARDUINO_PARTITION_default",
|
||||||
|
"ARDUINO_FQBN=esp32:esp32:d1_mini32",
|
||||||
|
"ESP32",
|
||||||
|
"CORE_DEBUG_LEVEL=0",
|
||||||
|
"ARDUINO_USB_CDC_ON_BOOT="
|
||||||
|
]
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"version": 4
|
||||||
|
}
|
||||||
10
.vscode/extensions.json
vendored
Normal file
@@ -0,0 +1,10 @@
|
|||||||
|
{
|
||||||
|
// 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"
|
||||||
|
],
|
||||||
|
"unwantedRecommendations": []
|
||||||
|
}
|
||||||
5
.vscode/intellisense.h
vendored
Normal file
@@ -0,0 +1,5 @@
|
|||||||
|
#ifdef __INTELLISENSE__
|
||||||
|
#pragma diag_suppress 144, 513
|
||||||
|
// diag 144: a value of type "enum <unnamed>" cannot be used to initialize an entity of type "enum <unnamed>"C/C++
|
||||||
|
// diag 513: a value of type "enum <unnamed>" cannot be assigned to an entity of type "enum <unnamed>"C/C++
|
||||||
|
#endif
|
||||||
25
.vscode/launch.json
vendored
Normal file
@@ -0,0 +1,25 @@
|
|||||||
|
{
|
||||||
|
"version": "0.2.0",
|
||||||
|
"configurations": [
|
||||||
|
{
|
||||||
|
"name": "Debug simulation",
|
||||||
|
"type": "cppdbg",
|
||||||
|
"request": "launch",
|
||||||
|
"program": "/usr/bin/gzserver",
|
||||||
|
"osx": {
|
||||||
|
"program": "/opt/homebrew/bin/gzserver",
|
||||||
|
"MIMode": "lldb",
|
||||||
|
},
|
||||||
|
"args": ["--verbose", "${workspaceFolder}/gazebo/flix.world"],
|
||||||
|
"stopAtEntry": false,
|
||||||
|
"cwd": "${fileDirname}",
|
||||||
|
"environment": [
|
||||||
|
{"name": "GAZEBO_MODEL_PATH", "value": "${workspaceFolder}/gazebo/models"},
|
||||||
|
{"name": "GAZEBO_PLUGIN_PATH", "value": "${workspaceFolder}/gazebo/build"}
|
||||||
|
],
|
||||||
|
"MIMode": "gdb",
|
||||||
|
"preLaunchTask": "Build simulator",
|
||||||
|
"externalConsole": true,
|
||||||
|
},
|
||||||
|
]
|
||||||
|
}
|
||||||
13
.vscode/settings.json
vendored
Normal file
@@ -0,0 +1,13 @@
|
|||||||
|
{
|
||||||
|
"C_Cpp.intelliSenseEngineFallback": "enabled",
|
||||||
|
"files.associations": {
|
||||||
|
"*.sdf": "xml",
|
||||||
|
"*.ino": "cpp",
|
||||||
|
"*.h": "cpp"
|
||||||
|
},
|
||||||
|
"C_Cpp.vcFormat.newLine.beforeOpenBrace.function": "newLine",
|
||||||
|
"C_Cpp.vcFormat.newLine.beforeOpenBrace.block": "sameLine",
|
||||||
|
"C_Cpp.vcFormat.newLine.beforeOpenBrace.lambda": "sameLine",
|
||||||
|
"C_Cpp.vcFormat.newLine.beforeOpenBrace.namespace": "sameLine",
|
||||||
|
"C_Cpp.vcFormat.newLine.beforeOpenBrace.type": "sameLine"
|
||||||
|
}
|
||||||
31
.vscode/tasks.json
vendored
Normal file
@@ -0,0 +1,31 @@
|
|||||||
|
{
|
||||||
|
"tasks": [
|
||||||
|
{
|
||||||
|
"label": "Build firmware",
|
||||||
|
"type": "shell",
|
||||||
|
"command": "make",
|
||||||
|
"problemMatcher": [ "$gcc" ],
|
||||||
|
"presentation": { "clear": true, "showReuseMessage": false },
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"label": "Upload firmware",
|
||||||
|
"type": "shell",
|
||||||
|
"command": "make upload",
|
||||||
|
"problemMatcher": [ "$gcc" ],
|
||||||
|
"presentation": { "clear": true, "showReuseMessage": false }
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"label": "Build simulator",
|
||||||
|
"type": "shell",
|
||||||
|
"command": "make build_simulator",
|
||||||
|
"problemMatcher": [ "$gcc" ],
|
||||||
|
"presentation": { "clear": true, "showReuseMessage": false }
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"label": "Clean",
|
||||||
|
"type": "shell",
|
||||||
|
"command": "make clean",
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"version": "2.0.0"
|
||||||
|
}
|
||||||
7
Makefile
@@ -13,10 +13,10 @@ monitor:
|
|||||||
|
|
||||||
dependencies .dependencies:
|
dependencies .dependencies:
|
||||||
arduino-cli core update-index --config-file arduino-cli.yaml
|
arduino-cli core update-index --config-file arduino-cli.yaml
|
||||||
arduino-cli core install esp32:esp32@2.0.11 --config-file arduino-cli.yaml
|
arduino-cli core install esp32:esp32@3.0.3 --config-file arduino-cli.yaml
|
||||||
arduino-cli lib update-index
|
arduino-cli lib update-index
|
||||||
arduino-cli lib install "FlixPeriph"
|
arduino-cli lib install "FlixPeriph"
|
||||||
arduino-cli lib install "MAVLink"@2.0.1
|
arduino-cli lib install "MAVLink"@2.0.10
|
||||||
touch .dependencies
|
touch .dependencies
|
||||||
|
|
||||||
gazebo/build cmake: gazebo/CMakeLists.txt
|
gazebo/build cmake: gazebo/CMakeLists.txt
|
||||||
@@ -26,11 +26,10 @@ gazebo/build cmake: gazebo/CMakeLists.txt
|
|||||||
build_simulator: .dependencies gazebo/build
|
build_simulator: .dependencies gazebo/build
|
||||||
make -C gazebo/build
|
make -C gazebo/build
|
||||||
|
|
||||||
GAZEBO ?= gazebo
|
|
||||||
simulator: build_simulator
|
simulator: build_simulator
|
||||||
GAZEBO_MODEL_PATH=$$GAZEBO_MODEL_PATH:${CURDIR}/gazebo/models \
|
GAZEBO_MODEL_PATH=$$GAZEBO_MODEL_PATH:${CURDIR}/gazebo/models \
|
||||||
GAZEBO_PLUGIN_PATH=$$GAZEBO_PLUGIN_PATH:${CURDIR}/gazebo/build \
|
GAZEBO_PLUGIN_PATH=$$GAZEBO_PLUGIN_PATH:${CURDIR}/gazebo/build \
|
||||||
$(GAZEBO) --verbose ${CURDIR}/gazebo/flix.world
|
gazebo --verbose ${CURDIR}/gazebo/flix.world
|
||||||
|
|
||||||
log:
|
log:
|
||||||
PORT=$(PORT) tools/grab_log.py
|
PORT=$(PORT) tools/grab_log.py
|
||||||
|
|||||||
141
README.md
@@ -1,69 +1,144 @@
|
|||||||
# flix
|
# Flix
|
||||||
|
|
||||||
**flix** (*flight + X*) — making an open source ESP32-based quadcopter from scratch.
|
**Flix** (*flight + X*) — making an open source ESP32-based quadcopter from scratch.
|
||||||
|
|
||||||
<img src="docs/img/flix.jpg" width=500 alt="Flix quadcopter">
|
<table>
|
||||||
|
<tr>
|
||||||
|
<td align=center><strong>Version 1</strong> (3D-printed frame)</td>
|
||||||
|
<td align=center><strong>Version 0</strong></td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td><img src="docs/img/flix1.jpg" width=500 alt="Flix quadcopter"></td>
|
||||||
|
<td><img src="docs/img/flix.jpg" width=500 alt="Flix quadcopter"></td>
|
||||||
|
</tr>
|
||||||
|
</table>
|
||||||
|
|
||||||
## Features
|
## Features
|
||||||
|
|
||||||
* Simple and clean Arduino based source code.
|
* Simple and clean Arduino based source code.
|
||||||
* Acro and Stabilized flight using remote control.
|
* Acro and Stabilized flight using remote control.
|
||||||
* Precise simulation using Gazebo.
|
* Precise simulation using Gazebo.
|
||||||
* In-RAM logging.
|
* [In-RAM logging](docs/log.md).
|
||||||
* Command line interface through USB port.
|
* Command line interface through USB port.
|
||||||
* Wi-Fi support.
|
* Wi-Fi support.
|
||||||
* MAVLink support.
|
* MAVLink support.
|
||||||
* Control using mobile phone (with QGroundControl app).
|
* Control using mobile phone (with QGroundControl app).
|
||||||
* ESCs with reverse mode support.
|
* Completely 3D-printed frame.
|
||||||
* *Textbook and videos for students on writing a flight controller\*.*
|
* *Textbook and videos for students on writing a flight controller¹.*
|
||||||
* *Completely 3D-printed frame*.*
|
* *Position control and autonomous flights using external camera¹*.
|
||||||
* *Position control and autonomous flights using external camera\**.
|
|
||||||
* [Building and running instructions](docs/build.md).
|
* [Building and running instructions](docs/build.md).
|
||||||
|
|
||||||
*\* — planned.*
|
*¹ — planned.*
|
||||||
|
|
||||||
## It actually flies
|
## It actually flies
|
||||||
|
|
||||||
|
See detailed demo video (for version 0): https://youtu.be/8GzzIQ3C6DQ.
|
||||||
|
|
||||||
<a href="https://youtu.be/8GzzIQ3C6DQ"><img width=500 src="https://i3.ytimg.com/vi/8GzzIQ3C6DQ/maxresdefault.jpg"></a>
|
<a href="https://youtu.be/8GzzIQ3C6DQ"><img width=500 src="https://i3.ytimg.com/vi/8GzzIQ3C6DQ/maxresdefault.jpg"></a>
|
||||||
|
|
||||||
See YouTube demo video: https://youtu.be/8GzzIQ3C6DQ.
|
Version 1 test flight: https://t.me/opensourcequadcopter/42.
|
||||||
|
|
||||||
|
<a href="https://t.me/opensourcequadcopter/42"><img width=500 src="docs/img/flight-video.jpg"></a>
|
||||||
|
|
||||||
## Simulation
|
## Simulation
|
||||||
|
|
||||||
Simulation in Gazebo using a plugin that runs original Arduino code is implemented:
|
The simulator is implemented using Gazebo and runs the original Arduino code:
|
||||||
|
|
||||||
<img src="docs/img/simulator.png" width=500 alt="Flix simulator">
|
<img src="docs/img/simulator.png" width=500 alt="Flix simulator">
|
||||||
|
|
||||||
## Schematics
|
See [instructions on running the simulation](docs/build.md).
|
||||||
|
|
||||||
<img src="docs/img/schematics.svg" width=800 alt="Flix schematics">
|
## Components (version 1)
|
||||||
|
|
||||||
You can also check a user contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/) of the drone.
|
|Type|Part|Image|Quantity|
|
||||||
|
|-|-|:-:|:-:|
|
||||||
|
|Microcontroller board|ESP32 Mini|<img src="docs/img/esp32.jpg" width=100>|1|
|
||||||
|
|IMU and barometer² board|GY-91 (or other MPU-9250 board)|<img src="docs/img/gy-91.jpg" width=100>|1|
|
||||||
|
|Motor|8520 3.7V brushed motor (**shaft 0.8mm!**)|<img src="docs/img/motor.jpeg" width=100>|4|
|
||||||
|
|Propeller|Hubsan 55 mm|<img src="docs/img/prop.jpg" width=100>|4|
|
||||||
|
|MOSFET (transistor)|100N03A or [compatible](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4|
|
||||||
|
|Pull-down resistor|10 kΩ|<img src="docs/img/resistor10k.jpg" width=100>|4|
|
||||||
|
|3.7V Li-Po battery|LW 952540 (or any compatible by the size)|<img src="docs/img/battery.jpg" width=100>|1|
|
||||||
|
|Li-Po Battery charger|Any|<img src="docs/img/charger.jpg" width=100>|1|
|
||||||
|
|Screws for IMU board mounting|M3x5|<img src="docs/img/screw-m3.jpg" width=100>|2|
|
||||||
|
|Screws for frame assembly|M1.4x5|<img src="docs/img/screw-m1.4.jpg" height=30 align=center>|4|
|
||||||
|
|Frame bottom part|3D printed: [`flix-frame.stl`](docs/assets/flix-frame.stl)|<img src="docs/img/frame1.jpg" width=100>|1|
|
||||||
|
|Frame top part|3D printed: [`esp32-holder.stl`](docs/assets/esp32-holder.stl)|<img src="docs/img/esp32-holder.jpg" width=100>|1|
|
||||||
|
|Washer for IMU board mounting|3D printed: [`washer-m3.stl`](docs/assets/washer-m3.stl)|<img src="docs/img/washer-m3.jpg" width=100>|1|
|
||||||
|
|*RC transmitter (optional)*|*KINGKONG TINY X8 or other³*|<img src="docs/img/tx.jpg" width=100>|1|
|
||||||
|
|*RC receiver (optional)*|*DF500 or other³*|<img src="docs/img/rx.jpg" width=100>|1|
|
||||||
|
|Wires|28 AWG recommended|<img src="docs/img/wire-28awg.jpg" width=100>||
|
||||||
|
|Tape, double-sided tape||||
|
||||||
|
|
||||||
*\* — SBUS inverter is not needed as ESP32 supports [software pin inversion](https://github.com/bolderflight/sbus#inverted-serial).*
|
*² — barometer is not used for now.*<br>
|
||||||
|
*³ — you may use any transmitter-receiver pair with SBUS interface.*
|
||||||
|
|
||||||
## Components (version 0)
|
Tools required for assembly:
|
||||||
|
|
||||||
|Component|Type|Image|Quantity|
|
* 3D printer.
|
||||||
|-|-|-|-|
|
* Soldering iron.
|
||||||
|ESP32 Mini|Microcontroller board|<img src="docs/img/esp32.jpg" width=100>|1|
|
* Solder wire (with flux).
|
||||||
|GY-91|IMU+LDO+barometer board|<img src="docs/img/gy-91.jpg" width=100>|1|
|
* Screwdrivers.
|
||||||
|K100|Quadcopter frame|<img src="docs/img/frame.jpg" width=100>|1|
|
* Multimeter.
|
||||||
|8520 3.7V brushed motor (**shaft 0.8mm!**)|Motor|<img src="docs/img/motor.jpeg" width=100>|4|
|
|
||||||
|Hubsan 55 mm| Propeller|<img src="docs/img/prop.jpg" width=100>|4|
|
|
||||||
|2.7A 1S Dual Way Micro Brush ESC|Motor ESC|<img src="docs/img/esc.jpg" width=100>|4|
|
|
||||||
|KINGKONG TINY X8|RC transmitter|<img src="docs/img/tx.jpg" width=100>|1|
|
|
||||||
|DF500 (SBUS)|RC receiver|<img src="docs/img/rx.jpg" width=100>|1|
|
|
||||||
||~~SBUS inverter~~*|<img src="docs/img/inv.jpg" width=100>|~~1~~|
|
|
||||||
|3.7 Li-Po 850 MaH 60C|Battery|||
|
|
||||||
||Battery charger|<img src="docs/img/charger.jpg" width=100>|1|
|
|
||||||
||Wires, connectors, tape, ...|||
|
|
||||||
||3D-printed frame parts|||
|
|
||||||
|
|
||||||
*\* — not needed as ESP32 supports [software pin inversion](https://github.com/bolderflight/sbus#inverted-serial).*
|
Feel free to modify the design and or code, and create your own improved versions of Flix! Send your results to the [official Telegram chat](https://t.me/opensourcequadcopterchat), or directly to the author ([E-mail](mailto:okalachev@gmail.com), [Telegram](https://t.me/okalachev)).
|
||||||
|
|
||||||
|
## Schematics (version 1)
|
||||||
|
|
||||||
|
### Simplified connection diagram
|
||||||
|
|
||||||
|
<img src="docs/img/schematics1.svg" width=800 alt="Flix version 1 schematics">
|
||||||
|
|
||||||
|
Motor connection scheme:
|
||||||
|
|
||||||
|
<img src="docs/img/mosfet-connection.png" height=400 alt="MOSFET connection scheme">
|
||||||
|
|
||||||
|
Complete diagram is Work-in-Progress.
|
||||||
|
|
||||||
|
### Notes
|
||||||
|
|
||||||
|
* Power ESP32 Mini with Li-Po battery using VCC (+) and GND (-) pins.
|
||||||
|
* Connect the GY-91 board to the ESP32 Mini using VSPI, power it using 3.3V and GND pins:
|
||||||
|
|
||||||
|
|GY-91 pin|ESP32 pin|
|
||||||
|
|-|-|
|
||||||
|
|GND|GND|
|
||||||
|
|3.3V|3.3V|
|
||||||
|
|SCK|SVP (GPIO18)|
|
||||||
|
|MOSI|GPIO23|
|
||||||
|
|MISO|GPIO19|
|
||||||
|
|NCS|GPIO5|
|
||||||
|
|
||||||
|
* Solder pull-down resistors to the MOSFETs.
|
||||||
|
* Connect the motors to the ESP32 Mini using MOSFETs, by following scheme:
|
||||||
|
|
||||||
|
|Motor|Position|Direction|Wires|GPIO|
|
||||||
|
|-|-|-|-|-|
|
||||||
|
|Motor 0|Rear left|Counter-clockwise|Black & White|GPIO12|
|
||||||
|
|Motor 1|Rear right|Clockwise|Blue & Red|GPIO13|
|
||||||
|
|Motor 2|Front right|Counter-clockwise|Black & White|GPIO14|
|
||||||
|
|Motor 3|Front left|Clockwise|Blue & Red|GPIO15|
|
||||||
|
|
||||||
|
Counter-clockwise motors have black and white wires and clockwise motors have blue and red wires.
|
||||||
|
|
||||||
|
* Optionally connect the RC receiver to the ESP32's UART2:
|
||||||
|
|
||||||
|
|Receiver pin|ESP32 pin|
|
||||||
|
|-|-|
|
||||||
|
|GND|GND|
|
||||||
|
|VIN|VC (or 3.3V depending on the receiver)|
|
||||||
|
|Signal|GPIO4⁴|
|
||||||
|
|
||||||
|
*⁴ — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.*
|
||||||
|
|
||||||
|
## Version 0
|
||||||
|
|
||||||
|
See the information on the obsolete version 0 in the [corresponding article](docs/version0.md).
|
||||||
|
|
||||||
## Materials
|
## Materials
|
||||||
|
|
||||||
Subscribe to Telegram-channel on developing the drone and the flight controller (in Russian): https://t.me/opensourcequadcopter.
|
Subscribe to the Telegram channel on developing the drone and the flight controller (in Russian): https://t.me/opensourcequadcopter.
|
||||||
|
|
||||||
|
Join the official Telegram chat: https://t.me/opensourcequadcopterchat.
|
||||||
|
|
||||||
Detailed article on Habr.com about the development of the drone (in Russian): https://habr.com/ru/articles/814127/.
|
Detailed article on Habr.com about the development of the drone (in Russian): https://habr.com/ru/articles/814127/.
|
||||||
|
|||||||
BIN
docs/assets/esp32-holder.stl
Normal file
BIN
docs/assets/flix-frame.stl
Normal file
BIN
docs/assets/washer-m3.stl
Normal file
@@ -14,7 +14,7 @@ cd flix
|
|||||||
1. Install Arduino CLI:
|
1. Install Arduino CLI:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=/usr/local/bin sh
|
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
|
||||||
```
|
```
|
||||||
|
|
||||||
2. Install Gazebo 11:
|
2. Install Gazebo 11:
|
||||||
@@ -78,19 +78,36 @@ cd flix
|
|||||||
make simulator
|
make simulator
|
||||||
```
|
```
|
||||||
|
|
||||||
### Flight
|
### Setup and flight
|
||||||
|
|
||||||
Use USB remote control or QGroundControl mobile app (with *Virtual Joystick* setting enabled) to control the drone. *Auto-Center Throttle* setting **should be disabled**.
|
#### 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. 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.
|
||||||
|
5. Open QGroundControl app. It should connect and begin showing the virtual drone's telemetry automatically.
|
||||||
|
6. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
|
||||||
|
7. Use the virtual joystick to fly the drone!
|
||||||
|
|
||||||
|
#### Control with USB remote control
|
||||||
|
|
||||||
|
1. Connect your USB remote control to the machine running the simulator.
|
||||||
|
2. Run the simulation.
|
||||||
|
3. Calibrate the RC using `cr` command in the command line interface and stop the simulation.
|
||||||
|
4. Copy the calibration results to the source code (`gazebo/joystick.h`).
|
||||||
|
5. Run the simulation again.
|
||||||
|
6. Use the USB remote control to fly the drone!
|
||||||
|
|
||||||
## Firmware
|
## Firmware
|
||||||
|
|
||||||
### Arduino IDE (Windows, Linux, macOS)
|
### Arduino IDE (Windows, Linux, macOS)
|
||||||
|
|
||||||
1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended).
|
1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended).
|
||||||
2. Install ESP32 core using [Boards Manager](https://docs.arduino.cc/learn/starting-guide/cores).
|
2. Install ESP32 core, version 3.0.3 (version 2.x is not supported). See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
|
||||||
3. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
|
3. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
|
||||||
* `FlixPeriph`.
|
* `FlixPeriph`.
|
||||||
* `MAVLink`, version 2.0.1.
|
* `MAVLink`, version 2.0.10.
|
||||||
4. Clone the project using git or [download the source code as a ZIP archive](https://codeload.github.com/okalachev/flix/zip/refs/heads/master).
|
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.
|
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.
|
6. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
|
||||||
@@ -119,12 +136,33 @@ Use USB remote control or QGroundControl mobile app (with *Virtual Joystick* set
|
|||||||
|
|
||||||
See other available Make commands in the [Makefile](../Makefile).
|
See other available Make commands in the [Makefile](../Makefile).
|
||||||
|
|
||||||
|
### Setup and flight
|
||||||
|
|
||||||
|
Before flight you need to calibrate the accelerometer:
|
||||||
|
|
||||||
|
1. Open Serial Monitor in Arduino IDE (use use `make monitor` command in the command line).
|
||||||
|
2. Type `ca` command there.
|
||||||
|
3. Copy calibration results to the source code (`flix/imu.ino`).
|
||||||
|
|
||||||
|
#### 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.
|
||||||
|
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!
|
||||||
|
|
||||||
|
#### Control with remote control
|
||||||
|
|
||||||
|
Before flight using remote control, you need to calibrate it:
|
||||||
|
|
||||||
|
1. Open Serial Monitor in Arduino IDE (use use `make monitor` command in the command line).
|
||||||
|
2. Type `cr` command there.
|
||||||
|
3. Copy calibration results to the source code (`flix/rc.ino`).
|
||||||
|
|
||||||
|
Then you can use your remote control to fly the drone!
|
||||||
|
|
||||||
### Firmware code structure
|
### Firmware code structure
|
||||||
|
|
||||||
See [firmware overview](firmware.md) for more details.
|
See [firmware overview](firmware.md) for more details.
|
||||||
|
|
||||||
## Setup
|
|
||||||
|
|
||||||
Before flight in simulation and on the real drone, you need to calibrate your remote control. Use drone's command line interface (`make monitor` on the real drone) and type `cr` command. Copy calibration results to the source code (`flix/rc.ino` and/or `gazebo/joystick.h`).
|
|
||||||
|
|
||||||
On the real drone, you also need to calibrate the accelerometer and the gyroscope. Use `ca` and `cg` commands for that. Copy calibration results to the source code (`flix/imu.ino`).
|
|
||||||
|
|||||||
BIN
docs/img/100n03a.jpg
Normal file
|
After Width: | Height: | Size: 27 KiB |
BIN
docs/img/battery.jpg
Normal file
|
After Width: | Height: | Size: 32 KiB |
BIN
docs/img/esp32-holder.jpg
Normal file
|
After Width: | Height: | Size: 9.3 KiB |
BIN
docs/img/flight-video.jpg
Normal file
|
After Width: | Height: | Size: 79 KiB |
BIN
docs/img/flightplot.png
Normal file
|
After Width: | Height: | Size: 56 KiB |
BIN
docs/img/flix1.jpg
Normal file
|
After Width: | Height: | Size: 89 KiB |
BIN
docs/img/foxglove.png
Normal file
|
After Width: | Height: | Size: 61 KiB |
BIN
docs/img/frame1.jpg
Normal file
|
After Width: | Height: | Size: 11 KiB |
BIN
docs/img/mosfet-connection.png
Normal file
|
After Width: | Height: | Size: 38 KiB |
BIN
docs/img/plotjuggler.png
Normal file
|
After Width: | Height: | Size: 53 KiB |
BIN
docs/img/resistor10k.jpg
Normal file
|
After Width: | Height: | Size: 12 KiB |
256
docs/img/schematics1.svg
Normal file
@@ -0,0 +1,256 @@
|
|||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
|
||||||
|
viewBox="0 0 1920 1080" style="enable-background:new 0 0 1920 1080;" xml:space="preserve">
|
||||||
|
<style type="text/css">
|
||||||
|
.st0{clip-path:url(#SVGID_00000116955662310502408250000008996271717606231736_);fill:#FFFFFF;}
|
||||||
|
.st1{clip-path:url(#SVGID_00000116955662310502408250000008996271717606231736_);fill:#0076BA;}
|
||||||
|
.st2{clip-path:url(#SVGID_00000116955662310502408250000008996271717606231736_);fill:none;stroke:#0076BA;stroke-width:6;}
|
||||||
|
.st3{clip-path:url(#SVGID_00000055674346191406539380000013421132283630177205_);}
|
||||||
|
.st4{fill:#FFFFFF;}
|
||||||
|
.st5{font-family:'Tahoma';}
|
||||||
|
.st6{font-size:60px;}
|
||||||
|
.st7{clip-path:url(#SVGID_00000057846011469822040540000011754501750068092081_);fill:none;stroke:#0076BA;stroke-width:6;}
|
||||||
|
|
||||||
|
.st8{clip-path:url(#SVGID_00000057846011469822040540000011754501750068092081_);fill:none;stroke:#0076BA;stroke-width:6;stroke-dasharray:12,12;}
|
||||||
|
.st9{clip-path:url(#SVGID_00000031912132892401345140000018376817810309323944_);}
|
||||||
|
.st10{letter-spacing:-1;}
|
||||||
|
.st11{clip-path:url(#SVGID_00000096022444481931167570000018189382621257791423_);fill:none;stroke:#D5D5D5;stroke-width:6;}
|
||||||
|
.st12{clip-path:url(#SVGID_00000096022444481931167570000018189382621257791423_);fill:#D5D5D5;}
|
||||||
|
.st13{clip-path:url(#SVGID_00000096022444481931167570000018189382621257791423_);}
|
||||||
|
.st14{font-size:40px;}
|
||||||
|
|
||||||
|
.st15{clip-path:url(#SVGID_00000096022444481931167570000018189382621257791423_);fill:none;stroke:#D5D5D5;stroke-width:6;stroke-dasharray:12,12;}
|
||||||
|
.st16{letter-spacing:-3;}
|
||||||
|
.st17{clip-path:url(#SVGID_00000096022444481931167570000018189382621257791423_);fill:none;stroke:#0076BA;stroke-width:6;}
|
||||||
|
.st18{clip-path:url(#SVGID_00000178923025368094801390000008109591059568692644_);}
|
||||||
|
.st19{clip-path:url(#SVGID_00000170245726615134129150000014803823133490835355_);fill:none;stroke:#D5D5D5;stroke-width:6;}
|
||||||
|
.st20{clip-path:url(#SVGID_00000170245726615134129150000014803823133490835355_);fill:#D5D5D5;}
|
||||||
|
.st21{clip-path:url(#SVGID_00000170245726615134129150000014803823133490835355_);}
|
||||||
|
.st22{clip-path:url(#SVGID_00000170245726615134129150000014803823133490835355_);fill:none;stroke:#FF9300;stroke-width:6;}
|
||||||
|
.st23{clip-path:url(#SVGID_00000137829079020238483810000004945639728221863820_);}
|
||||||
|
.st24{clip-path:url(#SVGID_00000127742992435002359440000017943924755103710901_);fill:none;stroke:#0076BA;stroke-width:6;}
|
||||||
|
.st25{clip-path:url(#SVGID_00000172413095142863711730000006643673940354901182_);}
|
||||||
|
.st26{fill:#333333;}
|
||||||
|
.st27{clip-path:url(#SVGID_00000057841300642942441540000015331613196773382808_);fill:none;stroke:#0076BA;stroke-width:3;}
|
||||||
|
.st28{clip-path:url(#SVGID_00000015346235126698654330000007941041458912523396_);}
|
||||||
|
.st29{font-size:30px;}
|
||||||
|
</style>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_1_" width="1920" height="1080"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000171677823290121104880000004951624621648774806_">
|
||||||
|
<use xlink:href="#SVGID_1_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
|
||||||
|
<rect style="clip-path:url(#SVGID_00000171677823290121104880000004951624621648774806_);fill:#FFFFFF;" width="1920" height="1080"/>
|
||||||
|
<path style="clip-path:url(#SVGID_00000171677823290121104880000004951624621648774806_);fill:#0076BA;" d="M781,353.4h358
|
||||||
|
c8.4,0,13.4,0,16.7,1.4c4.8,1.8,8.6,5.6,10.4,10.4c1.4,3.3,1.4,8.4,1.4,16.7v268.8c0,8.4,0,13.4-1.4,16.7
|
||||||
|
c-1.8,4.8-5.6,8.6-10.4,10.4c-3.3,1.4-8.4,1.4-16.7,1.4H781c-8.4,0-13.4,0-16.7-1.4c-4.8-1.8-8.6-5.6-10.4-10.4
|
||||||
|
c-1.4-3.3-1.4-8.4-1.4-16.7V381.9c0-8.4,0-13.4,1.4-16.7c1.8-4.8,5.6-8.6,10.4-10.4C767.6,353.4,772.6,353.4,781,353.4z"/>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000171677823290121104880000004951624621648774806_);fill:none;stroke:#0076BA;stroke-width:6;" d="
|
||||||
|
M781,353.4h358c8.4,0,13.4,0,16.7,1.4c4.8,1.8,8.6,5.6,10.4,10.4c1.4,3.3,1.4,8.4,1.4,16.7v268.8c0,8.4,0,13.4-1.4,16.7
|
||||||
|
c-1.8,4.8-5.6,8.6-10.4,10.4c-3.3,1.4-8.4,1.4-16.7,1.4H781c-8.4,0-13.4,0-16.7-1.4c-4.8-1.8-8.6-5.6-10.4-10.4
|
||||||
|
c-1.4-3.3-1.4-8.4-1.4-16.7V381.9c0-8.4,0-13.4,1.4-16.7c1.8-4.8,5.6-8.6,10.4-10.4C767.6,353.4,772.6,353.4,781,353.4z"/>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_00000039115730048533150280000004801426134829330596_" x="737.4" y="353.4" width="445.2" height="325.8"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000016774010820287457580000002865762276517841055_">
|
||||||
|
<use xlink:href="#SVGID_00000039115730048533150280000004801426134829330596_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
<g style="clip-path:url(#SVGID_00000016774010820287457580000002865762276517841055_);">
|
||||||
|
<text transform="matrix(1 0 0 1 877.1631 540.0012)" class="st4 st5 st6">ESP32</text>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_00000075151113810300876960000013536007874996673433_" width="1920" height="1080"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000107586269070498659130000000925674275700912771_">
|
||||||
|
<use xlink:href="#SVGID_00000075151113810300876960000013536007874996673433_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000107586269070498659130000000925674275700912771_);fill:none;stroke:#0076BA;stroke-width:6;" d="
|
||||||
|
M107.1,424.9h369.6c6.7,0,10.7,0,13.4,1.1c3.9,1.4,6.9,4.4,8.3,8.3c1.1,2.7,1.1,6.7,1.1,13.4v153.2c0,6.7,0,10.7-1.1,13.4
|
||||||
|
c-1.4,3.9-4.4,6.9-8.3,8.3c-2.7,1.1-6.7,1.1-13.4,1.1H107.1c-6.7,0-10.7,0-13.4-1.1c-3.9-1.4-6.9-4.4-8.3-8.3
|
||||||
|
c-1.1-2.7-1.1-6.7-1.1-13.4V447.6c0-6.7,0-10.7,1.1-13.4c1.4-3.9,4.4-6.9,8.3-8.3C96.4,424.9,100.4,424.9,107.1,424.9z"/>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000107586269070498659130000000925674275700912771_);fill:none;stroke:#0076BA;stroke-width:6;stroke-dasharray:12,12;" d="
|
||||||
|
M777.9,846.9h364.3c7.5,0,11.9,0,14.9,1.2c4.3,1.6,7.7,5,9.3,9.3c1.2,3,1.2,7.5,1.2,14.9V974c0,7.5,0,11.9-1.2,14.9
|
||||||
|
c-1.6,4.3-5,7.7-9.3,9.3c-3,1.2-7.5,1.2-14.9,1.2H777.9c-7.5,0-11.9,0-14.9-1.2c-4.3-1.6-7.7-5-9.3-9.3c-1.2-3-1.2-7.5-1.2-14.9
|
||||||
|
V872.4c0-7.5,0-11.9,1.2-14.9c1.6-4.3,5-7.7,9.3-9.3C765.9,846.9,770.4,846.9,777.9,846.9z"/>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_00000128454988870213717900000008065144461254055839_" x="737.3" y="846.9" width="445.4" height="152.5"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000124119398570885020400000016506660910002275730_">
|
||||||
|
<use xlink:href="#SVGID_00000128454988870213717900000008065144461254055839_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
<g style="clip-path:url(#SVGID_00000124119398570885020400000016506660910002275730_);">
|
||||||
|
<text transform="matrix(1 0 0 1 802.3304 947.0799)"><tspan x="0" y="0" class="st5 st6">RC </tspan><tspan x="92" y="0" class="st5 st6 st10">R</tspan><tspan x="128.2" y="0" class="st5 st6">ecei</tspan><tspan x="232.7" y="0" class="st5 st6">v</tspan><tspan x="262.2" y="0" class="st5 st6">er</tspan></text>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_00000130607252134697782620000007941153577788369085_" width="1920" height="1080"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000168829390248542060830000011029723519784449157_">
|
||||||
|
<use xlink:href="#SVGID_00000130607252134697782620000007941153577788369085_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:none;stroke:#D5D5D5;stroke-width:6;" d="
|
||||||
|
M429.1,526.4c96.1,19.6,194.9,26.9,296.4,22l3-0.2"/>
|
||||||
|
<polygon style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:#D5D5D5;" points="726.2,560.4
|
||||||
|
749.5,547.1 724.8,536.5 "/>
|
||||||
|
<g style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);">
|
||||||
|
<text transform="matrix(1 0 0 1 571.0244 599.9149)" class="st5 st14">SPI</text>
|
||||||
|
</g>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:none;stroke:#D5D5D5;stroke-width:6;stroke-dasharray:12,12;" d="
|
||||||
|
M991.9,843.9c7.9-38.5,9.3-84.5,4.4-137.8l-0.3-3"/>
|
||||||
|
<polygon style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:#D5D5D5;" points="1008.2,704.8
|
||||||
|
993.7,682.3 984.4,707.4 "/>
|
||||||
|
<g style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);">
|
||||||
|
<text transform="matrix(1 0 0 1 746.5599 778.8257)"><tspan x="0" y="0" class="st5 st14">SBUS (</tspan><tspan x="122.2" y="0" class="st5 st14">U</tspan><tspan x="148.3" y="0" class="st5 st14">A</tspan><tspan x="172.2" y="0" class="st5 st14 st10">R</tspan><tspan x="196" y="0" class="st5 st14">T</tspan><tspan x="219.8" y="0" class="st5 st14">)</tspan></text>
|
||||||
|
</g>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:none;stroke:#D5D5D5;stroke-width:6;" d="
|
||||||
|
M1170.5,537.8c72.8,3.7,147.2,3.8,223,0.3l3-0.2"/>
|
||||||
|
<polygon style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:#D5D5D5;" points="1394.1,550
|
||||||
|
1417.5,536.8 1392.9,526 "/>
|
||||||
|
<g style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);">
|
||||||
|
<text transform="matrix(1 0 0 1 1236.025 523.2462)" class="st5 st14">PWM</text>
|
||||||
|
</g>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:none;stroke:#D5D5D5;stroke-width:6;" d="
|
||||||
|
M1612.3,595.6c-10.7,73.2-11.3,149.1-2,227.5l0.4,3"/>
|
||||||
|
<polygon style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:#D5D5D5;" points="1598.5,824.7
|
||||||
|
1613.5,846.9 1622.2,821.6 "/>
|
||||||
|
<g style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);">
|
||||||
|
<text transform="matrix(1 0 0 1 1450.277 736.9998)"><tspan x="0" y="0" class="st5 st14 st10">V</tspan><tspan x="22.1" y="0" class="st5 st14">o</tspan><tspan x="43.8" y="0" class="st5 st14">l</tspan><tspan x="53" y="0" class="st5 st14">tage</tspan></text>
|
||||||
|
</g>
|
||||||
|
<g style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);">
|
||||||
|
<text transform="matrix(1 0 0 1 212.8847 595.784)"><tspan x="0" y="0" class="st5 st6">G</tspan><tspan x="40" y="0" class="st5 st6 st16">Y</tspan><tspan x="70.8" y="0" class="st5 st6">-91</tspan></text>
|
||||||
|
</g>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000168829390248542060830000011029723519784449157_);fill:none;stroke:#0076BA;stroke-width:6;" d="
|
||||||
|
M777.9,77.5h364.3c7.5,0,11.9,0,14.9,1.2c4.3,1.6,7.7,5,9.3,9.3c1.2,3,1.2,7.5,1.2,14.9v101.7c0,7.5,0,11.9-1.2,14.9
|
||||||
|
c-1.6,4.3-5,7.7-9.3,9.3c-3,1.2-7.5,1.2-14.9,1.2H777.9c-7.5,0-11.9,0-14.9-1.2c-4.3-1.6-7.7-5-9.3-9.3c-1.2-3-1.2-7.5-1.2-14.9
|
||||||
|
V103c0-7.5,0-11.9,1.2-14.9c1.6-4.3,5-7.7,9.3-9.3C765.9,77.5,770.4,77.5,777.9,77.5z"/>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_00000137820956330754408580000017691839315522467728_" x="737.3" y="77.5" width="445.4" height="152.5"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000016789657776342930330000013964875638603798149_">
|
||||||
|
<use xlink:href="#SVGID_00000137820956330754408580000017691839315522467728_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
<g style="clip-path:url(#SVGID_00000016789657776342930330000013964875638603798149_);">
|
||||||
|
<text transform="matrix(1 0 0 1 865.0551 177.6901)"><tspan x="0" y="0" class="st5 st6">B</tspan><tspan x="35.6" y="0" class="st5 st6">a</tspan><tspan x="67.1" y="0" class="st5 st6">t</tspan><tspan x="86.7" y="0" class="st5 st6">tery</tspan></text>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_00000016756559387490335270000000552908433054081441_" width="1920" height="1080"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000171720285722730791730000010936644841389779363_">
|
||||||
|
<use xlink:href="#SVGID_00000016756559387490335270000000552908433054081441_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);fill:none;stroke:#D5D5D5;stroke-width:6;" d="
|
||||||
|
M925.7,233.1c-5.3,27.2-6.8,58.4-4.3,93.4l0.3,3"/>
|
||||||
|
<polygon style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);fill:#D5D5D5;" points="909.4,327.6
|
||||||
|
923.5,350.4 933.3,325.4 "/>
|
||||||
|
<g style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);">
|
||||||
|
<text transform="matrix(1 0 0 1 937.7745 299.4789)"><tspan x="0" y="0" class="st5 st14">>3</tspan><tspan x="50.9" y="0" class="st5 st14">.</tspan><tspan x="62.1" y="0" class="st5 st14">7V</tspan></text>
|
||||||
|
</g>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);fill:none;stroke:#D5D5D5;stroke-width:6;" d="
|
||||||
|
M1170.6,161.5c228,25.6,371.6,110,430.8,253.1l1.1,2.8"/>
|
||||||
|
<polygon style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);fill:#D5D5D5;" points="1590.2,418.8
|
||||||
|
1609.8,437.1 1612.6,410.4 "/>
|
||||||
|
<g style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);">
|
||||||
|
<text transform="matrix(1 0 0 1 1396.229 204.8126)"><tspan x="0" y="0" class="st5 st14">>3</tspan><tspan x="50.9" y="0" class="st5 st14">.</tspan><tspan x="62.1" y="0" class="st5 st14">7V</tspan></text>
|
||||||
|
</g>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000171720285722730791730000010936644841389779363_);fill:none;stroke:#FF9300;stroke-width:6;" d="
|
||||||
|
M1445.9,849.9h364.3c7.5,0,11.9,0,14.9,1.2c4.3,1.6,7.7,5,9.3,9.3c1.2,3,1.2,7.5,1.2,14.9V977c0,7.5,0,11.9-1.2,14.9
|
||||||
|
c-1.6,4.3-5,7.7-9.3,9.3c-3,1.2-7.5,1.2-14.9,1.2h-364.3c-7.5,0-11.9,0-14.9-1.2c-4.3-1.6-7.7-5-9.3-9.3c-1.2-3-1.2-7.5-1.2-14.9
|
||||||
|
V875.4c0-7.5,0-11.9,1.2-14.9c1.6-4.3,5-7.7,9.3-9.3C1434,849.9,1438.5,849.9,1445.9,849.9z"/>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_00000125590519588794066770000004908208256101094292_" x="1405.4" y="849.9" width="445.4" height="152.5"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000020367246295901477730000005237269270844408247_">
|
||||||
|
<use xlink:href="#SVGID_00000125590519588794066770000004908208256101094292_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
<g style="clip-path:url(#SVGID_00000020367246295901477730000005237269270844408247_);">
|
||||||
|
<text transform="matrix(1 0 0 1 1507.9561 950.0799)" class="st5 st6">Motors </text>
|
||||||
|
</g>
|
||||||
|
<g style="clip-path:url(#SVGID_00000020367246295901477730000005237269270844408247_);">
|
||||||
|
<text transform="matrix(1 0 0 1 1706.5596 950.0799)" class="st5 st14">x4</text>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_00000078757851010072822240000012642622956562684587_" width="1920" height="1080"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000132802581807603645050000011682039405646066589_">
|
||||||
|
<use xlink:href="#SVGID_00000078757851010072822240000012642622956562684587_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000132802581807603645050000011682039405646066589_);fill:none;stroke:#0076BA;stroke-width:6;" d="
|
||||||
|
M1445.9,440.1h364.3c7.5,0,11.9,0,14.9,1.2c4.3,1.6,7.7,5,9.3,9.3c1.2,3,1.2,7.5,1.2,14.9v101.7c0,7.5,0,11.9-1.2,14.9
|
||||||
|
c-1.6,4.3-5,7.7-9.3,9.3c-3,1.2-7.5,1.2-14.9,1.2h-364.3c-7.5,0-11.9,0-14.9-1.2c-4.3-1.6-7.7-5-9.3-9.3c-1.2-3-1.2-7.5-1.2-14.9
|
||||||
|
V465.5c0-7.5,0-11.9,1.2-14.9c1.6-4.3,5-7.7,9.3-9.3C1434,440.1,1438.5,440.1,1445.9,440.1z"/>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_00000121968229548182703620000008187702022402881724_" x="1405.4" y="440.1" width="445.4" height="152.5"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000130637550574198708210000000321319364498620830_">
|
||||||
|
<use xlink:href="#SVGID_00000121968229548182703620000008187702022402881724_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
<g style="clip-path:url(#SVGID_00000130637550574198708210000000321319364498620830_);">
|
||||||
|
<text transform="matrix(1 0 0 1 1486.833 540.213)" class="st5 st6">MOSFE</text>
|
||||||
|
</g>
|
||||||
|
<g style="clip-path:url(#SVGID_00000130637550574198708210000000321319364498620830_);">
|
||||||
|
<text transform="matrix(1 0 0 1 1673.8936 540.213)" class="st26 st5 st6">T</text>
|
||||||
|
</g>
|
||||||
|
<g style="clip-path:url(#SVGID_00000130637550574198708210000000321319364498620830_);">
|
||||||
|
<text transform="matrix(1 0 0 1 1708.9326 540.213)" class="st5 st6"> </text>
|
||||||
|
</g>
|
||||||
|
<g style="clip-path:url(#SVGID_00000130637550574198708210000000321319364498620830_);">
|
||||||
|
<text transform="matrix(1 0 0 1 1727.6826 540.213)" class="st5 st14">x4</text>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_00000038395453607794357290000016650519059911045024_" width="1920" height="1080"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000077303055156502403190000000114138446408493755_">
|
||||||
|
<use xlink:href="#SVGID_00000038395453607794357290000016650519059911045024_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
|
||||||
|
<path style="clip-path:url(#SVGID_00000077303055156502403190000000114138446408493755_);fill:none;stroke:#0076BA;stroke-width:3;" d="
|
||||||
|
M167.8,451H416c4.5,0,7.1,0,8.9,0.7c2.6,0.9,4.6,3,5.5,5.5c0.7,1.8,0.7,4.5,0.7,8.9v46.6c0,4.5,0,7.1-0.7,8.9
|
||||||
|
c-0.9,2.6-3,4.6-5.5,5.5c-1.8,0.7-4.5,0.7-8.9,0.7H167.8c-4.5,0-7.1,0-8.9-0.7c-2.6-0.9-4.6-3-5.5-5.5c-0.7-1.8-0.7-4.5-0.7-8.9
|
||||||
|
v-46.6c0-4.5,0-7.1,0.7-8.9c0.9-2.6,3-4.6,5.5-5.5C160.7,451,163.4,451,167.8,451z"/>
|
||||||
|
</g>
|
||||||
|
<g>
|
||||||
|
<defs>
|
||||||
|
<rect id="SVGID_00000077301502947632695740000005629016913768095395_" x="145.2" y="451" width="293.5" height="77"/>
|
||||||
|
</defs>
|
||||||
|
<clipPath id="SVGID_00000004518590643829462700000008680026774255780777_">
|
||||||
|
<use xlink:href="#SVGID_00000077301502947632695740000005629016913768095395_" style="overflow:visible;"/>
|
||||||
|
</clipPath>
|
||||||
|
<g style="clip-path:url(#SVGID_00000004518590643829462700000008680026774255780777_);">
|
||||||
|
<text transform="matrix(1 0 0 1 197.8359 501.2101)" class="st5 st29">MPU9250 IMU</text>
|
||||||
|
</g>
|
||||||
|
</g>
|
||||||
|
</svg>
|
||||||
|
After Width: | Height: | Size: 17 KiB |
BIN
docs/img/screw-m1.4.jpg
Normal file
|
After Width: | Height: | Size: 30 KiB |
BIN
docs/img/screw-m3.jpg
Normal file
|
After Width: | Height: | Size: 3.7 KiB |
BIN
docs/img/washer-m3.jpg
Normal file
|
After Width: | Height: | Size: 5.9 KiB |
BIN
docs/img/wire-28awg.jpg
Normal file
|
After Width: | Height: | Size: 37 KiB |
72
docs/log.md
Normal file
@@ -0,0 +1,72 @@
|
|||||||
|
# Log analysis
|
||||||
|
|
||||||
|
Flix quadcopter uses RAM to store flight log data. The default log capacity is 10 seconds at 100 Hz. This configuration can be adjusted in the `log.ino` file.
|
||||||
|
|
||||||
|
To perform log analysis, you need to download the log right after the flight without powering off the drone. Then you can use several tools to analyze the log data.
|
||||||
|
|
||||||
|
## Log download
|
||||||
|
|
||||||
|
To download the log, connect the ESP32 using USB right after the flight and run the following command:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
make log
|
||||||
|
```
|
||||||
|
|
||||||
|
Logs are stored in `tools/log/*.csv` files.
|
||||||
|
|
||||||
|
## Analysis
|
||||||
|
|
||||||
|
### PlotJuggler
|
||||||
|
|
||||||
|
The recommended tool for log analysis is PlotJuggler.
|
||||||
|
|
||||||
|
<img src="img/plotjuggler.png" width="500">
|
||||||
|
|
||||||
|
1. Install PlotJuggler using the [official instructions](https://github.com/facontidavide/PlotJuggler?tab=readme-ov-file#installation).
|
||||||
|
|
||||||
|
2. Run PlotJuggler and drag'n'drop the downloaded log file there. Choose `t` column to be used as X axis.
|
||||||
|
|
||||||
|
You can open the most recent downloaded file using the command:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
make plot
|
||||||
|
```
|
||||||
|
|
||||||
|
You can perform both log download and run PlotJuggler in one command:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
make log plot
|
||||||
|
```
|
||||||
|
|
||||||
|
### FlightPlot
|
||||||
|
|
||||||
|
FlightPlot is a powerful tool for analyzing logs in [ULog format](https://docs.px4.io/main/en/dev_log/ulog_file_format.html). This format is used in PX4 and ArduPilot flight software.
|
||||||
|
|
||||||
|
<img src="img/flightplot.png" width="500">
|
||||||
|
|
||||||
|
1. [Install FlightPlot](https://github.com/PX4/FlightPlot).
|
||||||
|
2. Flix repository contains a tool for converting CSV logs to ULog format. Build the tool using [the instructions](../tools/csv_to_ulog/README.md) and convert the log you want to analyze.
|
||||||
|
3. Run FlightPlot and drag'n'drop the converted ULog-file there.
|
||||||
|
|
||||||
|
### Foxglove Studio
|
||||||
|
|
||||||
|
Foxglove is a tool for visualizing and analyzing robotics data with very rich functionality. It can import various formats, but mainly focuses on its own format, called [MCAP](https://mcap.dev).
|
||||||
|
|
||||||
|
<img src="img/foxglove.png" width="500">
|
||||||
|
|
||||||
|
1. Install Foxglove Studio from the [official website](https://foxglove.dev/download).
|
||||||
|
|
||||||
|
2. Flix repository contains a tool for converting CSV logs to MCAP format. First, install its dependencies:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
cd tools
|
||||||
|
pip install -r requirements.txt
|
||||||
|
```
|
||||||
|
|
||||||
|
3. Convert the log you want to analyze:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
csv_to_mcap.py log_file.csv
|
||||||
|
```
|
||||||
|
|
||||||
|
4. Open the log in Foxglove Studio using *Open local file* command.
|
||||||
30
docs/version0.md
Normal file
@@ -0,0 +1,30 @@
|
|||||||
|
# Flix version 0
|
||||||
|
|
||||||
|
Flix version 0 (obsolete):
|
||||||
|
|
||||||
|
<img src="img/flix.jpg" width=500 alt="Flix quadcopter">
|
||||||
|
|
||||||
|
## Components list
|
||||||
|
|
||||||
|
|Type|Part|Image|Quantity|
|
||||||
|
|-|-|-|-|
|
||||||
|
|Microcontroller board|ESP32 Mini|<img src="img/esp32.jpg" width=100>|1|
|
||||||
|
|IMU and barometer² board|GY-91 (or other MPU-9250 board)|<img src="img/gy-91.jpg" width=100>|1|
|
||||||
|
|Quadcopter frame|K100|<img src="img/frame.jpg" width=100>|1|
|
||||||
|
|Motor|8520 3.7V brushed motor (**shaft 0.8mm!**)|<img src="img/motor.jpeg" width=100>|4|
|
||||||
|
|Propeller|Hubsan 55 mm|<img src="img/prop.jpg" width=100>|4|
|
||||||
|
|Motor ESC|2.7A 1S Dual Way Micro Brush ESC|<img src="img/esc.jpg" width=100>|4|
|
||||||
|
|RC transmitter|KINGKONG TINY X8|<img src="img/tx.jpg" width=100>|1|
|
||||||
|
|RC receiver|DF500 (SBUS)|<img src="img/rx.jpg" width=100>|1|
|
||||||
|
|~~SBUS inverter~~*||<img src="img/inv.jpg" width=100>|~~1~~|
|
||||||
|
|Battery|3.7 Li-Po 850 MaH 60C|||
|
||||||
|
|Battery charger||<img src="img/charger.jpg" width=100>|1|
|
||||||
|
|Wires, connectors, tape, ...|||
|
||||||
|
|
||||||
|
*\* — not needed as ESP32 supports [software pin inversion](https://github.com/bolderflight/sbus#inverted-serial).*
|
||||||
|
|
||||||
|
## Schematics
|
||||||
|
|
||||||
|
<img src="img/schematics.svg" width=800 alt="Flix schematics">
|
||||||
|
|
||||||
|
You can also check a user contributed [variant of complete circuit diagram](https://miro.com/app/board/uXjVN-dTjoo=/) of the drone.
|
||||||
@@ -102,7 +102,7 @@ void doCommand(String& command, String& value) {
|
|||||||
} else if (command == "mrl") {
|
} else if (command == "mrl") {
|
||||||
cliTestMotor(MOTOR_REAR_LEFT);
|
cliTestMotor(MOTOR_REAR_LEFT);
|
||||||
} else if (command == "fullmot") {
|
} else if (command == "fullmot") {
|
||||||
fullMotorTest(value.toInt(), false);
|
fullMotorTest(value.toInt());
|
||||||
} else if (command == "reset") {
|
} else if (command == "reset") {
|
||||||
attitude = Quaternion();
|
attitude = Quaternion();
|
||||||
} else {
|
} else {
|
||||||
|
|||||||
@@ -81,22 +81,22 @@ void interpretRC() {
|
|||||||
if (mode == ACRO) {
|
if (mode == ACRO) {
|
||||||
yawMode = YAW_RATE;
|
yawMode = YAW_RATE;
|
||||||
ratesTarget.x = controls[RC_CHANNEL_ROLL] * ROLLRATE_MAX;
|
ratesTarget.x = controls[RC_CHANNEL_ROLL] * ROLLRATE_MAX;
|
||||||
ratesTarget.y = -controls[RC_CHANNEL_PITCH] * PITCHRATE_MAX; // up pitch stick means tilt clockwise in frd
|
ratesTarget.y = controls[RC_CHANNEL_PITCH] * PITCHRATE_MAX;
|
||||||
ratesTarget.z = controls[RC_CHANNEL_YAW] * YAWRATE_MAX;
|
ratesTarget.z = -controls[RC_CHANNEL_YAW] * YAWRATE_MAX; // positive yaw stick means clockwise rotation in FLU
|
||||||
|
|
||||||
} else if (mode == STAB) {
|
} else if (mode == STAB) {
|
||||||
yawMode = controls[RC_CHANNEL_YAW] == 0 ? YAW : YAW_RATE;
|
yawMode = controls[RC_CHANNEL_YAW] == 0 ? YAW : YAW_RATE;
|
||||||
|
|
||||||
attitudeTarget = Quaternion::fromEulerZYX(Vector(
|
attitudeTarget = Quaternion::fromEulerZYX(Vector(
|
||||||
controls[RC_CHANNEL_ROLL] * MAX_TILT,
|
controls[RC_CHANNEL_ROLL] * MAX_TILT,
|
||||||
-controls[RC_CHANNEL_PITCH] * MAX_TILT,
|
controls[RC_CHANNEL_PITCH] * MAX_TILT,
|
||||||
attitudeTarget.getYaw()));
|
attitudeTarget.getYaw()));
|
||||||
ratesTarget.z = controls[RC_CHANNEL_YAW] * YAWRATE_MAX;
|
ratesTarget.z = -controls[RC_CHANNEL_YAW] * YAWRATE_MAX; // positive yaw stick means clockwise rotation in FLU
|
||||||
|
|
||||||
} else if (mode == MANUAL) {
|
} else if (mode == MANUAL) {
|
||||||
// passthrough mode
|
// passthrough mode
|
||||||
yawMode = YAW_RATE;
|
yawMode = YAW_RATE;
|
||||||
torqueTarget = Vector(controls[RC_CHANNEL_ROLL], -controls[RC_CHANNEL_PITCH], controls[RC_CHANNEL_YAW]) * 0.01;
|
torqueTarget = Vector(controls[RC_CHANNEL_ROLL], controls[RC_CHANNEL_PITCH], -controls[RC_CHANNEL_YAW]) * 0.01;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (yawMode == YAW_RATE || !motorsActive()) {
|
if (yawMode == YAW_RATE || !motorsActive()) {
|
||||||
@@ -113,7 +113,7 @@ void controlAttitude() {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
const Vector up(0, 0, -1);
|
const Vector up(0, 0, 1);
|
||||||
Vector upActual = attitude.rotate(up);
|
Vector upActual = attitude.rotate(up);
|
||||||
Vector upTarget = attitudeTarget.rotate(up);
|
Vector upTarget = attitudeTarget.rotate(up);
|
||||||
|
|
||||||
@@ -123,7 +123,8 @@ void controlAttitude() {
|
|||||||
ratesTarget.y = pitchPID.update(error.y, dt);
|
ratesTarget.y = pitchPID.update(error.y, dt);
|
||||||
|
|
||||||
if (yawMode == YAW) {
|
if (yawMode == YAW) {
|
||||||
ratesTarget.z = yawPID.update(wrapAngle(attitudeTarget.getYaw() - attitude.getYaw()), dt);
|
float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw());
|
||||||
|
ratesTarget.z = yawPID.update(yawError, dt);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -149,10 +150,10 @@ void controlTorque() {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
motors[MOTOR_FRONT_LEFT] = thrustTarget + torqueTarget.x + torqueTarget.y - torqueTarget.z;
|
motors[MOTOR_FRONT_LEFT] = thrustTarget + torqueTarget.x - torqueTarget.y + torqueTarget.z;
|
||||||
motors[MOTOR_FRONT_RIGHT] = thrustTarget - torqueTarget.x + torqueTarget.y + torqueTarget.z;
|
motors[MOTOR_FRONT_RIGHT] = thrustTarget - torqueTarget.x - torqueTarget.y - torqueTarget.z;
|
||||||
motors[MOTOR_REAR_LEFT] = thrustTarget + torqueTarget.x - torqueTarget.y + torqueTarget.z;
|
motors[MOTOR_REAR_LEFT] = thrustTarget + torqueTarget.x + torqueTarget.y - torqueTarget.z;
|
||||||
motors[MOTOR_REAR_RIGHT] = thrustTarget - torqueTarget.x - torqueTarget.y - torqueTarget.z;
|
motors[MOTOR_REAR_RIGHT] = thrustTarget - torqueTarget.x + torqueTarget.y + torqueTarget.z;
|
||||||
|
|
||||||
motors[0] = constrain(motors[0], 0, 1);
|
motors[0] = constrain(motors[0], 0, 1);
|
||||||
motors[1] = constrain(motors[1], 0, 1);
|
motors[1] = constrain(motors[1], 0, 1);
|
||||||
|
|||||||
@@ -36,7 +36,7 @@ void applyAcc() {
|
|||||||
if (!landed) return;
|
if (!landed) return;
|
||||||
|
|
||||||
// calculate accelerometer correction
|
// calculate accelerometer correction
|
||||||
Vector up = attitude.rotate(Vector(0, 0, -1));
|
Vector up = attitude.rotate(Vector(0, 0, 1));
|
||||||
Vector correction = Vector::angularRatesBetweenVectors(acc, up) * dt * WEIGHT_ACC;
|
Vector correction = Vector::angularRatesBetweenVectors(acc, up) * dt * WEIGHT_ACC;
|
||||||
|
|
||||||
// apply correction
|
// apply correction
|
||||||
@@ -45,6 +45,6 @@ void applyAcc() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void signalizeHorizontality() {
|
void signalizeHorizontality() {
|
||||||
float angle = Vector::angleBetweenVectors(attitude.rotate(Vector(0, 0, -1)), Vector(0, 0, -1));
|
float angle = Vector::angleBetweenVectors(attitude.rotate(Vector(0, 0, 1)), Vector(0, 0, 1));
|
||||||
setLED(angle < radians(15));
|
setLED(angle < radians(15));
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -8,9 +8,9 @@
|
|||||||
|
|
||||||
#define SERIAL_BAUDRATE 115200
|
#define SERIAL_BAUDRATE 115200
|
||||||
|
|
||||||
#define WIFI_ENABLED 0
|
#define WIFI_ENABLED 1
|
||||||
|
|
||||||
#define RC_CHANNELS 6
|
#define RC_CHANNELS 16
|
||||||
#define RC_CHANNEL_ROLL 0
|
#define RC_CHANNEL_ROLL 0
|
||||||
#define RC_CHANNEL_PITCH 1
|
#define RC_CHANNEL_PITCH 1
|
||||||
#define RC_CHANNEL_THROTTLE 2
|
#define RC_CHANNEL_THROTTLE 2
|
||||||
@@ -26,7 +26,7 @@
|
|||||||
float t = NAN; // current step time, s
|
float t = NAN; // current step time, s
|
||||||
float dt; // time delta from previous step, s
|
float dt; // time delta from previous step, s
|
||||||
float loopFreq; // loop frequency, Hz
|
float loopFreq; // loop frequency, Hz
|
||||||
int16_t channels[16]; // raw rc channels
|
int16_t channels[RC_CHANNELS]; // raw rc channels
|
||||||
float controls[RC_CHANNELS]; // normalized controls in range [-1..1] ([0..1] for throttle)
|
float controls[RC_CHANNELS]; // normalized controls in range [-1..1] ([0..1] for throttle)
|
||||||
Vector gyro; // gyroscope data
|
Vector gyro; // gyroscope data
|
||||||
Vector acc; // accelerometer data, m/s/s
|
Vector acc; // accelerometer data, m/s/s
|
||||||
|
|||||||
@@ -2,6 +2,9 @@
|
|||||||
// Repository: https://github.com/okalachev/flix
|
// Repository: https://github.com/okalachev/flix
|
||||||
|
|
||||||
// Work with the IMU sensor
|
// Work with the IMU sensor
|
||||||
|
// IMU is oriented FLU (front-left-up) style.
|
||||||
|
// In case of FRD (front-right-down) orientation of the IMU, use this code:
|
||||||
|
// https://gist.github.com/okalachev/713db47e31bce643dbbc9539d166ce98.
|
||||||
|
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#include <MPU9250.h>
|
#include <MPU9250.h>
|
||||||
|
|||||||
@@ -38,8 +38,9 @@ void sendMavlink() {
|
|||||||
lastFast = t;
|
lastFast = t;
|
||||||
|
|
||||||
const float zeroQuat[] = {0, 0, 0, 0};
|
const float zeroQuat[] = {0, 0, 0, 0};
|
||||||
|
Quaternion attitudeFRD = FLU2FRD(attitude); // MAVLink uses FRD coordinate system
|
||||||
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||||
time, attitude.w, attitude.x, attitude.y, attitude.z, rates.x, rates.y, rates.z, zeroQuat);
|
time, attitudeFRD.w, attitudeFRD.x, attitudeFRD.y, attitudeFRD.z, rates.x, rates.y, rates.z, zeroQuat);
|
||||||
sendMessage(&msg);
|
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, time, 0,
|
||||||
@@ -97,4 +98,9 @@ void handleMavlink(const void *_msg) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Convert Forward-Left-Up to Forward-Right-Down quaternion
|
||||||
|
inline Quaternion FLU2FRD(const Quaternion &q) {
|
||||||
|
return Quaternion(q.w, q.x, -q.y, -q.z);
|
||||||
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
@@ -1,69 +1,50 @@
|
|||||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||||
// Repository: https://github.com/okalachev/flix
|
// Repository: https://github.com/okalachev/flix
|
||||||
|
|
||||||
// Motors output control
|
// 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
|
// Motor: 8520 3.7V
|
||||||
// ESC: KINGDUO Micro Mini 4A 1S Brushed Esc 3.6-6V
|
|
||||||
|
|
||||||
#define MOTOR_0_PIN 12
|
#define MOTOR_0_PIN 12 // rear left
|
||||||
#define MOTOR_1_PIN 13
|
#define MOTOR_1_PIN 13 // rear right
|
||||||
#define MOTOR_2_PIN 14
|
#define MOTOR_2_PIN 14 // front right
|
||||||
#define MOTOR_3_PIN 15
|
#define MOTOR_3_PIN 15 // front left
|
||||||
|
|
||||||
#define PWM_FREQUENCY 200
|
#define PWM_FREQUENCY 200
|
||||||
#define PWM_RESOLUTION 8
|
#define PWM_RESOLUTION 8
|
||||||
#define PWM_NEUTRAL 1500
|
|
||||||
#define PWM_MIN 1600
|
|
||||||
#define PWM_MAX 2300
|
|
||||||
#define PWM_REVERSE_MIN 1400
|
|
||||||
#define PWM_REVERSE_MAX 700
|
|
||||||
|
|
||||||
void setupMotors() {
|
void setupMotors() {
|
||||||
Serial.println("Setup Motors");
|
Serial.println("Setup Motors");
|
||||||
|
|
||||||
// configure PWM channels
|
// configure pins
|
||||||
ledcSetup(0, PWM_FREQUENCY, PWM_RESOLUTION);
|
ledcAttach(MOTOR_0_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
||||||
ledcSetup(1, PWM_FREQUENCY, PWM_RESOLUTION);
|
ledcAttach(MOTOR_1_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
||||||
ledcSetup(2, PWM_FREQUENCY, PWM_RESOLUTION);
|
ledcAttach(MOTOR_2_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
||||||
ledcSetup(3, PWM_FREQUENCY, PWM_RESOLUTION);
|
ledcAttach(MOTOR_3_PIN, PWM_FREQUENCY, PWM_RESOLUTION);
|
||||||
|
|
||||||
// attach channels to motor pins
|
|
||||||
ledcAttachPin(MOTOR_0_PIN, 0);
|
|
||||||
ledcAttachPin(MOTOR_1_PIN, 1);
|
|
||||||
ledcAttachPin(MOTOR_2_PIN, 2);
|
|
||||||
ledcAttachPin(MOTOR_3_PIN, 3);
|
|
||||||
|
|
||||||
sendMotors();
|
sendMotors();
|
||||||
Serial.println("Motors initialized");
|
Serial.println("Motors initialized");
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t getPWM(float val, int n) {
|
uint8_t signalToDutyCycle(float control) {
|
||||||
if (val == 0) {
|
float duty = mapff(control, 0, 1, 0, (1 << PWM_RESOLUTION) - 1);
|
||||||
return PWM_NEUTRAL;
|
return round(constrain(duty, 0, (1 << PWM_RESOLUTION) - 1));
|
||||||
} else if (val > 0) {
|
|
||||||
return mapff(val, 0, 1, PWM_MIN, PWM_MAX);
|
|
||||||
} else {
|
|
||||||
return mapff(val, 0, -1, PWM_REVERSE_MIN, PWM_REVERSE_MAX);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t pwmToDutyCycle(uint16_t pwm) {
|
|
||||||
return map(pwm, 0, 1000000 / PWM_FREQUENCY, 0, (1 << PWM_RESOLUTION) - 1);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void sendMotors() {
|
void sendMotors() {
|
||||||
ledcWrite(0, pwmToDutyCycle(getPWM(motors[0], 0)));
|
ledcWrite(MOTOR_0_PIN, signalToDutyCycle(motors[0]));
|
||||||
ledcWrite(1, pwmToDutyCycle(getPWM(motors[1], 1)));
|
ledcWrite(MOTOR_1_PIN, signalToDutyCycle(motors[1]));
|
||||||
ledcWrite(2, pwmToDutyCycle(getPWM(motors[2], 2)));
|
ledcWrite(MOTOR_2_PIN, signalToDutyCycle(motors[2]));
|
||||||
ledcWrite(3, pwmToDutyCycle(getPWM(motors[3], 3)));
|
ledcWrite(MOTOR_3_PIN, signalToDutyCycle(motors[3]));
|
||||||
}
|
}
|
||||||
|
|
||||||
void fullMotorTest(int n, bool reverse) {
|
void fullMotorTest(int n) {
|
||||||
printf("Full test for motor %d\n", n);
|
printf("Full test for motor %d\n", n);
|
||||||
for (int pwm = PWM_NEUTRAL; pwm <= 2300 && pwm >= 700; pwm += reverse ? -100 : 100) {
|
for (float signal = 0; signal <= 1; signal += 0.1) {
|
||||||
printf("Motor %d: %d\n", n, pwm);
|
printf("Motor %d: %f\n", n, signal);
|
||||||
ledcWrite(n, pwmToDutyCycle(pwm));
|
ledcWrite(n, signalToDutyCycle(signal));
|
||||||
delay(3000);
|
delay(3000);
|
||||||
}
|
}
|
||||||
printf("Motor %d: %d\n", n, PWM_NEUTRAL);
|
printf("Motor %d: %f\n", n, 0);
|
||||||
ledcWrite(n, pwmToDutyCycle(PWM_NEUTRAL));
|
ledcWrite(n, signalToDutyCycle(0));
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -75,7 +75,7 @@ public:
|
|||||||
float sqz = z * z;
|
float sqz = z * z;
|
||||||
float sqw = w * w;
|
float sqw = w * w;
|
||||||
// Cases derived from https://orbitalstation.wordpress.com/tag/quaternion/
|
// Cases derived from https://orbitalstation.wordpress.com/tag/quaternion/
|
||||||
float sarg = -2 * (x * z - w * y) / (sqx + sqy + sqz + sqw); /* normalization added from urdfom_headers */
|
float sarg = -2 * (x * z - w * y) / (sqx + sqy + sqz + sqw);
|
||||||
if (sarg <= -0.99999) {
|
if (sarg <= -0.99999) {
|
||||||
euler.x = 0;
|
euler.x = 0;
|
||||||
euler.y = -0.5 * PI;
|
euler.y = -0.5 * PI;
|
||||||
|
|||||||
@@ -6,10 +6,10 @@
|
|||||||
#include <SBUS.h>
|
#include <SBUS.h>
|
||||||
|
|
||||||
// NOTE: use 'cr' command to calibrate the RC and put the values here
|
// NOTE: use 'cr' command to calibrate the RC and put the values here
|
||||||
int channelNeutral[] = {995, 883, 200, 972, 512, 512};
|
int channelNeutral[] = {995, 883, 200, 972, 512, 512, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
|
||||||
int channelMax[] = {1651, 1540, 1713, 1630, 1472, 1472};
|
int channelMax[] = {1651, 1540, 1713, 1630, 1472, 1472, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
|
||||||
|
|
||||||
SBUS RC(Serial2);
|
SBUS RC(Serial2, 16, 17); // NOTE: remove pin numbers (16, 17) if you use the new default pins for Serial2 (4, 25)
|
||||||
|
|
||||||
void setupRC() {
|
void setupRC() {
|
||||||
Serial.println("Setup RC");
|
Serial.println("Setup RC");
|
||||||
|
|||||||
@@ -7,6 +7,7 @@
|
|||||||
|
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
#include <string>
|
#include <string>
|
||||||
|
#include <stdint.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#include <sys/poll.h>
|
#include <sys/poll.h>
|
||||||
@@ -116,7 +117,7 @@ public:
|
|||||||
int read() {
|
int read() {
|
||||||
if (available()) {
|
if (available()) {
|
||||||
char c;
|
char c;
|
||||||
::read(STDIN_FILENO, &c, 1); // use raw read to avoid C++ buffering
|
size_t res = ::read(STDIN_FILENO, &c, 1); // use raw read to avoid C++ buffering
|
||||||
// https://stackoverflow.com/questions/45238997/does-getchar-function-has-its-own-buffer-to-store-remaining-input
|
// https://stackoverflow.com/questions/45238997/does-getchar-function-has-its-own-buffer-to-store-remaining-input
|
||||||
return c;
|
return c;
|
||||||
}
|
}
|
||||||
@@ -133,7 +134,8 @@ void delay(uint32_t ms) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
unsigned long __micros;
|
unsigned long __micros;
|
||||||
|
unsigned long __resetTime = 0;
|
||||||
|
|
||||||
unsigned long micros() {
|
unsigned long micros() {
|
||||||
return __micros;
|
return __micros + __resetTime; // keep the time monotonic
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -15,6 +15,7 @@ set(CMAKE_BUILD_TYPE RelWithDebInfo)
|
|||||||
add_library(flix SHARED simulator.cpp)
|
add_library(flix SHARED simulator.cpp)
|
||||||
target_link_libraries(flix ${GAZEBO_LIBRARIES} ${SDL2_LIBRARIES})
|
target_link_libraries(flix ${GAZEBO_LIBRARIES} ${SDL2_LIBRARIES})
|
||||||
target_include_directories(flix PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
|
target_include_directories(flix PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
|
||||||
|
target_compile_options(flix PRIVATE -Wno-address-of-packed-member) # disable unneeded mavlink warnings
|
||||||
|
|
||||||
# Include dir for MAVLink-Arduino library
|
# Include dir for MAVLink-Arduino library
|
||||||
target_include_directories(flix PUBLIC $ENV{HOME}/Arduino/libraries/MAVLink)
|
target_include_directories(flix PUBLIC $ENV{HOME}/Arduino/libraries/MAVLink)
|
||||||
|
|||||||
@@ -12,6 +12,7 @@ struct SBUSData {
|
|||||||
class SBUS {
|
class SBUS {
|
||||||
public:
|
public:
|
||||||
SBUS(HardwareSerial& bus, const bool inv = true) {};
|
SBUS(HardwareSerial& bus, const bool inv = true) {};
|
||||||
|
SBUS(HardwareSerial& bus, const int8_t rxpin, const int8_t txpin, const bool inv = true) {};
|
||||||
void begin() {};
|
void begin() {};
|
||||||
bool read() { return joystickGet(); };
|
bool read() { return joystickGet(); };
|
||||||
SBUSData data() {
|
SBUSData data() {
|
||||||
|
|||||||
@@ -10,7 +10,7 @@
|
|||||||
#include "Arduino.h"
|
#include "Arduino.h"
|
||||||
#include "wifi.h"
|
#include "wifi.h"
|
||||||
|
|
||||||
#define RC_CHANNELS 6
|
#define RC_CHANNELS 16
|
||||||
|
|
||||||
#define MOTOR_REAR_LEFT 0
|
#define MOTOR_REAR_LEFT 0
|
||||||
#define MOTOR_FRONT_LEFT 3
|
#define MOTOR_FRONT_LEFT 3
|
||||||
@@ -49,11 +49,12 @@ void sendMavlink();
|
|||||||
void sendMessage(const void *msg);
|
void sendMessage(const void *msg);
|
||||||
void receiveMavlink();
|
void receiveMavlink();
|
||||||
void handleMavlink(const void *_msg);
|
void handleMavlink(const void *_msg);
|
||||||
|
inline Quaternion FLU2FRD(const Quaternion &q);
|
||||||
|
|
||||||
// mocks
|
// mocks
|
||||||
void setLED(bool on) {};
|
void setLED(bool on) {};
|
||||||
void calibrateGyro() { printf("Skip gyro calibrating\n"); };
|
void calibrateGyro() { printf("Skip gyro calibrating\n"); };
|
||||||
void calibrateAccel() { printf("Skip accel calibrating\n"); };
|
void calibrateAccel() { printf("Skip accel calibrating\n"); };
|
||||||
void fullMotorTest(int n, bool reverse) { printf("Skip full motor test\n"); };
|
void fullMotorTest(int n) { printf("Skip full motor test\n"); };
|
||||||
void sendMotors() {};
|
void sendMotors() {};
|
||||||
void printIMUCal() { printf("cal: N/A\n"); };
|
void printIMUCal() { printf("cal: N/A\n"); };
|
||||||
|
|||||||
@@ -9,7 +9,7 @@
|
|||||||
</scene>
|
</scene>
|
||||||
<gui>
|
<gui>
|
||||||
<camera name="user_camera">
|
<camera name="user_camera">
|
||||||
<pose>-2 -0.3 1.5 0 0.5 0.1</pose>
|
<pose>-2.3 0 1.1 0 0.3 0</pose>
|
||||||
</camera>
|
</camera>
|
||||||
</gui>
|
</gui>
|
||||||
<physics type="ode">
|
<physics type="ode">
|
||||||
@@ -23,7 +23,7 @@
|
|||||||
</include>
|
</include>
|
||||||
<include>
|
<include>
|
||||||
<uri>model://flix</uri>
|
<uri>model://flix</uri>
|
||||||
<pose>0 0 0.2 0 0 0</pose>
|
<pose>0 0 0.3 0 0 0</pose>
|
||||||
</include>
|
</include>
|
||||||
</world>
|
</world>
|
||||||
</sdf>
|
</sdf>
|
||||||
|
|||||||
@@ -13,15 +13,10 @@
|
|||||||
<collision name="collision">
|
<collision name="collision">
|
||||||
<geometry>
|
<geometry>
|
||||||
<box>
|
<box>
|
||||||
<size>0.125711 0.125711 0.022</size>
|
<size>0.095 0.095 0.0276</size>
|
||||||
</box>
|
</box>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<visual name="body">
|
|
||||||
<geometry>
|
|
||||||
<mesh><uri>model://flix/flix.dae</uri></mesh>
|
|
||||||
</geometry>
|
|
||||||
</visual>
|
|
||||||
<sensor name="imu" type="imu">
|
<sensor name="imu" type="imu">
|
||||||
<always_on>1</always_on>
|
<always_on>1</always_on>
|
||||||
<visualize>1</visualize>
|
<visualize>1</visualize>
|
||||||
@@ -63,6 +58,37 @@
|
|||||||
</linear_acceleration>
|
</linear_acceleration>
|
||||||
</imu>
|
</imu>
|
||||||
</sensor>
|
</sensor>
|
||||||
|
<visual name="body">
|
||||||
|
<geometry>
|
||||||
|
<mesh><uri>model://flix/flix.stl</uri></mesh>
|
||||||
|
</geometry>
|
||||||
|
<material>
|
||||||
|
<ambient>0.5 0.5 0.6 1</ambient>
|
||||||
|
<diffuse>0.5 0.5 0.6 1</diffuse>
|
||||||
|
<specular>0 0 0 1</specular>
|
||||||
|
<emissive>0 0 0 1</emissive>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<visual name="prop0"><!-- rear left -->
|
||||||
|
<geometry><cylinder><radius>0.0275</radius><length>0</length></cylinder></geometry>
|
||||||
|
<pose>-0.04243 0.04243 0.0142 0 0 0</pose>
|
||||||
|
<material><ambient>0.8 0.3 0.3 0.5</ambient><diffuse>0.8 0.3 0.3 0.5</diffuse></material>
|
||||||
|
</visual>
|
||||||
|
<visual name="prop1"><!-- rear right -->
|
||||||
|
<geometry><cylinder><radius>0.0275</radius><length>0</length></cylinder></geometry>
|
||||||
|
<pose>-0.04243 -0.04243 0.0142 0 0 0</pose>
|
||||||
|
<material><ambient>0.8 0.3 0.3 0.5</ambient><diffuse>0.8 0.3 0.3 0.5</diffuse></material>
|
||||||
|
</visual>
|
||||||
|
<visual name="prop2"><!-- front right -->
|
||||||
|
<geometry><cylinder><radius>0.0275</radius><length>0</length></cylinder></geometry>
|
||||||
|
<pose>0.04243 -0.04243 0.0142 0 0 0</pose>
|
||||||
|
<material><ambient>1 1 1 0.5</ambient><diffuse>1 1 1 0.5</diffuse></material>
|
||||||
|
</visual>
|
||||||
|
<visual name="prop3"><!-- front left -->
|
||||||
|
<geometry><cylinder><radius>0.0275</radius><length>0</length></cylinder></geometry>
|
||||||
|
<pose>0.04243 0.04243 0.0142 0 0 0</pose>
|
||||||
|
<material><ambient>1 1 1 0.5</ambient><diffuse>1 1 1 0.5</diffuse></material>
|
||||||
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
<plugin name="flix" filename="libflix.so"/>
|
<plugin name="flix" filename="libflix.so"/>
|
||||||
</model>
|
</model>
|
||||||
|
|||||||
BIN
gazebo/models/flix/flix.stl
Normal file
@@ -17,7 +17,6 @@
|
|||||||
|
|
||||||
#include "Arduino.h"
|
#include "Arduino.h"
|
||||||
#include "flix.h"
|
#include "flix.h"
|
||||||
#include "util.h"
|
|
||||||
#include "util.ino"
|
#include "util.ino"
|
||||||
#include "rc.ino"
|
#include "rc.ino"
|
||||||
#include "time.ino"
|
#include "time.ino"
|
||||||
@@ -47,8 +46,8 @@ public:
|
|||||||
this->model = _parent;
|
this->model = _parent;
|
||||||
this->body = this->model->GetLink("body");
|
this->body = this->model->GetLink("body");
|
||||||
this->imu = dynamic_pointer_cast<sensors::ImuSensor>(sensors::get_sensor(model->GetScopedName(true) + "::body::imu")); // default::flix::body::imu
|
this->imu = dynamic_pointer_cast<sensors::ImuSensor>(sensors::get_sensor(model->GetScopedName(true) + "::body::imu")); // default::flix::body::imu
|
||||||
this->updateConnection = event::Events::ConnectWorldUpdateBegin(bind(&ModelFlix::OnUpdate, this));
|
this->updateConnection = event::Events::ConnectWorldUpdateBegin(std::bind(&ModelFlix::OnUpdate, this));
|
||||||
this->resetConnection = event::Events::ConnectWorldReset(bind(&ModelFlix::OnReset, this));
|
this->resetConnection = event::Events::ConnectWorldReset(std::bind(&ModelFlix::OnReset, this));
|
||||||
initNode();
|
initNode();
|
||||||
Serial.begin(0);
|
Serial.begin(0);
|
||||||
gzmsg << "Flix plugin loaded" << endl;
|
gzmsg << "Flix plugin loaded" << endl;
|
||||||
@@ -56,6 +55,7 @@ public:
|
|||||||
|
|
||||||
void OnReset() {
|
void OnReset() {
|
||||||
attitude = Quaternion(); // reset estimated attitude
|
attitude = Quaternion(); // reset estimated attitude
|
||||||
|
__resetTime += __micros;
|
||||||
gzmsg << "Flix plugin reset" << endl;
|
gzmsg << "Flix plugin reset" << endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -63,9 +63,9 @@ public:
|
|||||||
__micros = model->GetWorld()->SimTime().Double() * 1000000;
|
__micros = model->GetWorld()->SimTime().Double() * 1000000;
|
||||||
step();
|
step();
|
||||||
|
|
||||||
// read imu
|
// read virtual imu
|
||||||
gyro = flu2frd(imu->AngularVelocity());
|
gyro = Vector(imu->AngularVelocity().X(), imu->AngularVelocity().Y(), imu->AngularVelocity().Z());
|
||||||
acc = this->accFilter.update(flu2frd(imu->LinearAcceleration()));
|
acc = this->accFilter.update(Vector(imu->LinearAcceleration().X(), imu->LinearAcceleration().Y(), imu->LinearAcceleration().Z()));
|
||||||
|
|
||||||
// read rc
|
// read rc
|
||||||
readRC();
|
readRC();
|
||||||
@@ -75,7 +75,7 @@ public:
|
|||||||
estimate();
|
estimate();
|
||||||
|
|
||||||
// correct yaw to the actual yaw
|
// correct yaw to the actual yaw
|
||||||
attitude.setYaw(-this->model->WorldPose().Yaw());
|
attitude.setYaw(this->model->WorldPose().Yaw());
|
||||||
|
|
||||||
control();
|
control();
|
||||||
parseInput();
|
parseInput();
|
||||||
|
|||||||
@@ -1,14 +0,0 @@
|
|||||||
#include <ignition/math/Vector3.hh>
|
|
||||||
#include <ignition/math/Pose3.hh>
|
|
||||||
|
|
||||||
using ignition::math::Vector3d;
|
|
||||||
using ignition::math::Pose3d;
|
|
||||||
|
|
||||||
Pose3d flu2frd(const Pose3d& p) {
|
|
||||||
return ignition::math::Pose3d(p.Pos().X(), -p.Pos().Y(), -p.Pos().Z(),
|
|
||||||
p.Rot().W(), p.Rot().X(), -p.Rot().Y(), -p.Rot().Z());
|
|
||||||
}
|
|
||||||
|
|
||||||
Vector flu2frd(const Vector3d& v) {
|
|
||||||
return Vector(v.X(), -v.Y(), -v.Z());
|
|
||||||
}
|
|
||||||
@@ -18,7 +18,7 @@ int wifiSocket;
|
|||||||
|
|
||||||
void setupWiFi() {
|
void setupWiFi() {
|
||||||
wifiSocket = socket(AF_INET, SOCK_DGRAM, 0);
|
wifiSocket = socket(AF_INET, SOCK_DGRAM, 0);
|
||||||
sockaddr_in addr;
|
sockaddr_in addr; // local address
|
||||||
addr.sin_family = AF_INET;
|
addr.sin_family = AF_INET;
|
||||||
addr.sin_addr.s_addr = INADDR_ANY;
|
addr.sin_addr.s_addr = INADDR_ANY;
|
||||||
addr.sin_port = htons(WIFI_UDP_PORT_LOCAL);
|
addr.sin_port = htons(WIFI_UDP_PORT_LOCAL);
|
||||||
@@ -30,7 +30,7 @@ void setupWiFi() {
|
|||||||
|
|
||||||
void sendWiFi(const uint8_t *buf, int len) {
|
void sendWiFi(const uint8_t *buf, int len) {
|
||||||
if (wifiSocket == 0) setupWiFi();
|
if (wifiSocket == 0) setupWiFi();
|
||||||
sockaddr_in addr;
|
sockaddr_in addr; // remote address
|
||||||
addr.sin_family = AF_INET;
|
addr.sin_family = AF_INET;
|
||||||
addr.sin_addr.s_addr = INADDR_BROADCAST; // send UDP broadcast
|
addr.sin_addr.s_addr = INADDR_BROADCAST; // send UDP broadcast
|
||||||
addr.sin_port = htons(WIFI_UDP_PORT_REMOTE);
|
addr.sin_port = htons(WIFI_UDP_PORT_REMOTE);
|
||||||
|
|||||||
61
tools/check_c_cpp_properties.py
Executable file
@@ -0,0 +1,61 @@
|
|||||||
|
#!/usr/bin/env python3
|
||||||
|
|
||||||
|
import os
|
||||||
|
import platform
|
||||||
|
import json
|
||||||
|
import re
|
||||||
|
|
||||||
|
path = '.vscode/c_cpp_properties.json' if os.path.exists('./.vscode/c_cpp_properties.json') else '../.vscode/c_cpp_properties.json'
|
||||||
|
txt = open(path).read()
|
||||||
|
# remove comments
|
||||||
|
txt = re.sub(r'//.*', '', txt)
|
||||||
|
props = json.loads(txt)
|
||||||
|
|
||||||
|
env = props.get('env', {})
|
||||||
|
env['workspaceFolder'] = '.'
|
||||||
|
|
||||||
|
def check_path(s):
|
||||||
|
source = s
|
||||||
|
# replace env
|
||||||
|
for key, value in env.items():
|
||||||
|
s = s.replace('${' + key + '}', value)
|
||||||
|
# remove globs from the end
|
||||||
|
if s.endswith('**'):
|
||||||
|
s = s[:-2]
|
||||||
|
elif s.endswith('*'):
|
||||||
|
s = s[:-1]
|
||||||
|
s = os.path.expanduser(s)
|
||||||
|
if s == '':
|
||||||
|
s = '.'
|
||||||
|
print('Check', source, '->', s)
|
||||||
|
assert os.path.exists(s), 'Path does not exist: ' + s
|
||||||
|
|
||||||
|
# linux, macos or windows:
|
||||||
|
platform = platform.system().lower()
|
||||||
|
if platform == 'darwin':
|
||||||
|
platform = 'mac'
|
||||||
|
elif platform == 'windows':
|
||||||
|
platform = 'win32'
|
||||||
|
elif platform == 'linux':
|
||||||
|
pass
|
||||||
|
else:
|
||||||
|
raise Exception('Unknown platform: ' + platform)
|
||||||
|
|
||||||
|
for configuration in props['configurations']:
|
||||||
|
if platform not in configuration['name'].lower():
|
||||||
|
print('Skip configuration', configuration['name'])
|
||||||
|
continue
|
||||||
|
|
||||||
|
print('Check configuration', configuration['name'])
|
||||||
|
|
||||||
|
for include_path in configuration.get('includePath', []):
|
||||||
|
check_path(include_path)
|
||||||
|
|
||||||
|
for forced_include in configuration.get('forcedInclude', []):
|
||||||
|
check_path(forced_include)
|
||||||
|
|
||||||
|
for browse in configuration.get('browse', {}).get('path', []):
|
||||||
|
check_path(browse)
|
||||||
|
|
||||||
|
if 'compilerPath' in configuration:
|
||||||
|
check_path(configuration['compilerPath'])
|
||||||
46
tools/csv_to_mcap.py
Executable file
@@ -0,0 +1,46 @@
|
|||||||
|
#!/usr/bin/env python3
|
||||||
|
|
||||||
|
"""Convert CSV log file to MCAP file.
|
||||||
|
|
||||||
|
Usage:
|
||||||
|
csv_to_mcap.py <csv_file> [<mcap_file>]
|
||||||
|
"""
|
||||||
|
|
||||||
|
import csv
|
||||||
|
import json
|
||||||
|
import docopt
|
||||||
|
from mcap.writer import Writer
|
||||||
|
|
||||||
|
args = docopt.docopt(__doc__)
|
||||||
|
input_file = args['<csv_file>']
|
||||||
|
output_file = args['<mcap_file>'] or input_file.replace('.csv', '.mcap')
|
||||||
|
if input_file == output_file:
|
||||||
|
raise ValueError('Input and output files are the same')
|
||||||
|
|
||||||
|
csv_file = open(input_file, 'r')
|
||||||
|
csv_reader = csv.reader(csv_file, delimiter=',')
|
||||||
|
header = next(csv_reader)
|
||||||
|
|
||||||
|
mcap_file = open(output_file, 'wb')
|
||||||
|
writer = Writer(mcap_file)
|
||||||
|
writer.start()
|
||||||
|
|
||||||
|
properties = {key: {'type': 'number'} for key in header}
|
||||||
|
schema_id = writer.register_schema(
|
||||||
|
name="state",
|
||||||
|
encoding="jsonschema",
|
||||||
|
data=json.dumps({"type": "object", "properties": properties}).encode(),
|
||||||
|
)
|
||||||
|
|
||||||
|
channel_id = writer.register_channel(
|
||||||
|
schema_id=schema_id,
|
||||||
|
topic="state",
|
||||||
|
message_encoding="json",
|
||||||
|
)
|
||||||
|
|
||||||
|
for row in csv_reader:
|
||||||
|
data = {key: float(value) for key, value in zip(header, row)}
|
||||||
|
timestamp = round(float(row[0]) * 1e9)
|
||||||
|
writer.add_message(channel_id=channel_id, log_time=timestamp, data=json.dumps(data).encode(), publish_time=timestamp,)
|
||||||
|
|
||||||
|
writer.finish()
|
||||||
23
tools/csv_to_ulog/CMakeLists.txt
Normal file
@@ -0,0 +1,23 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.15)
|
||||||
|
project(csv_to_ulog)
|
||||||
|
include(FetchContent)
|
||||||
|
set(CMAKE_CXX_STANDARD 17)
|
||||||
|
|
||||||
|
FetchContent_Declare(
|
||||||
|
ulog_cpp
|
||||||
|
GIT_REPOSITORY https://github.com/PX4/ulog_cpp.git
|
||||||
|
GIT_TAG cf24ec6
|
||||||
|
)
|
||||||
|
|
||||||
|
FetchContent_Declare(
|
||||||
|
rapidcsv
|
||||||
|
GIT_REPOSITORY https://github.com/d99kris/rapidcsv.git
|
||||||
|
GIT_TAG v8.82
|
||||||
|
)
|
||||||
|
|
||||||
|
FetchContent_MakeAvailable(ulog_cpp)
|
||||||
|
FetchContent_MakeAvailable(rapidcsv)
|
||||||
|
|
||||||
|
add_executable(csv_to_ulog csv_to_ulog.cpp)
|
||||||
|
target_link_libraries(csv_to_ulog PUBLIC ulog_cpp::ulog_cpp)
|
||||||
|
target_include_directories(csv_to_ulog PUBLIC ${rapidcsv_SOURCE_DIR}/src)
|
||||||
20
tools/csv_to_ulog/README.md
Normal file
@@ -0,0 +1,20 @@
|
|||||||
|
# csv_to_ulog
|
||||||
|
|
||||||
|
Tool for converting CSV flight logs to ULog format so they can be analyzed using [FlightPlot](https://github.com/PX4/FlightPlot) software.
|
||||||
|
|
||||||
|
To build, go to the `<flix>/tools/csv_to_ulog` directory and run:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
mkdir build
|
||||||
|
cd build
|
||||||
|
cmake ..
|
||||||
|
make
|
||||||
|
```
|
||||||
|
|
||||||
|
Convert a CSV file to ULog:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
./csv_to_ulog log_file.csv
|
||||||
|
```
|
||||||
|
|
||||||
|
ULog file will be saved in the same directory.
|
||||||
72
tools/csv_to_ulog/csv_to_ulog.cpp
Normal file
@@ -0,0 +1,72 @@
|
|||||||
|
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||||
|
// Repository: https://github.com/okalachev/flix
|
||||||
|
|
||||||
|
// Tool for conversion CSV log file to ULog format
|
||||||
|
|
||||||
|
#include <ulog_cpp/simple_writer.hpp>
|
||||||
|
#include <rapidcsv.h>
|
||||||
|
#include <vector>
|
||||||
|
#include <string>
|
||||||
|
#include <filesystem>
|
||||||
|
|
||||||
|
using std::vector;
|
||||||
|
using std::string;
|
||||||
|
|
||||||
|
struct Data {
|
||||||
|
uint64_t timestamp;
|
||||||
|
float values[30];
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char** argv)
|
||||||
|
{
|
||||||
|
if (argc < 2) {
|
||||||
|
printf("Usage: %s file.csv [file.ulg]\n", argv[0]);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// check input file exists
|
||||||
|
if (!std::filesystem::exists(argv[1])) {
|
||||||
|
printf("Input file \"%s\" does not exist\n", argv[1]);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// open csv file
|
||||||
|
rapidcsv::Document csv(argv[1]);
|
||||||
|
auto columns = csv.GetColumnNames();
|
||||||
|
|
||||||
|
|
||||||
|
// open ulog file
|
||||||
|
string ulog_file;
|
||||||
|
if (argc < 3) {
|
||||||
|
ulog_file = std::filesystem::path(argv[1]).replace_extension(".ulg").string();
|
||||||
|
} else {
|
||||||
|
ulog_file = argv[2];
|
||||||
|
}
|
||||||
|
ulog_cpp::SimpleWriter writer(ulog_file.c_str(), 0);
|
||||||
|
writer.writeInfo("sys_name", "flix");
|
||||||
|
|
||||||
|
vector<ulog_cpp::Field> fields;
|
||||||
|
fields.push_back(ulog_cpp::Field("uint64_t", "timestamp"));
|
||||||
|
columns.erase(columns.begin()); // remove timestamp column
|
||||||
|
for (auto& column : columns) {
|
||||||
|
// Valid field name for ULog: [a-z0-9_]+
|
||||||
|
std::replace(column.begin(), column.end(), '.', '_'); // replace dots with underscores
|
||||||
|
std::transform(column.begin(), column.end(), column.begin(), [](unsigned char c) { return std::tolower(c); }); // lowercase column name
|
||||||
|
fields.push_back(ulog_cpp::Field("float", column));
|
||||||
|
}
|
||||||
|
|
||||||
|
const char* msg_name = "state";
|
||||||
|
writer.writeMessageFormat(msg_name, fields);
|
||||||
|
writer.headerComplete();
|
||||||
|
|
||||||
|
const uint16_t msg_id = writer.writeAddLoggedMessage(msg_name);
|
||||||
|
|
||||||
|
for (size_t i = 0; i < csv.GetRowCount(); i++) {
|
||||||
|
Data data;
|
||||||
|
data.timestamp = csv.GetCell<float>(0, i) * 1000000.0;
|
||||||
|
for (size_t j = 1; j <= columns.size(); j++) {
|
||||||
|
data.values[j - 1] = csv.GetCell<float>(j, i);
|
||||||
|
}
|
||||||
|
writer.writeData(msg_id, data);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,2 +1,3 @@
|
|||||||
docopt
|
docopt
|
||||||
matplotlib
|
matplotlib
|
||||||
|
mcap
|
||||||
|
|||||||