37 Commits

Author SHA1 Message Date
Oleg Kalachev
00286c3b67 Try to build the sim on the latest macos 2024-12-10 09:36:36 +03:00
Oleg Kalachev
09466b1d61 Remove verbosity and debug 2024-12-10 09:36:19 +03:00
Oleg Kalachev
d46438baaa Merge branch 'master' into fix-macos-ci 2024-12-10 06:15:23 +03:00
Oleg Kalachev
6e7aa78680 Try different version of new Gazebo to install on macOS 2024-12-10 06:02:09 +03:00
Oleg Kalachev
fcb426a16f Update MAVLink-Arduino to 2.0.11 2024-12-09 08:04:36 +03:00
Oleg Kalachev
eea1a6a83c Minor fix in troubleshooting article 2024-12-08 07:40:24 +03:00
Oleg Kalachev
9d470cbdfa Add info on required version of Ubuntu for the simulation 2024-12-05 09:28:44 +03:00
Oleg Kalachev
6e140d673c Cleanup unused utility functions 2024-12-05 08:29:21 +03:00
Oleg Kalachev
c75760e9e6 Some readme change regarding using different IMU board 2024-12-04 23:00:26 +03:00
Oleg Kalachev
172b6becc6 Use new FlixPeriph library with ICM-20948 support 2024-12-04 14:41:23 +03:00
Oleg Kalachev
475e9a87ba Configure IMU before calibrating the gyro which improves calibration 2024-12-04 12:25:07 +03:00
Oleg Kalachev
ea141f851f Use 'loop rate' term instead of misleading 'loop frequency' 2024-12-04 07:00:00 +03:00
Oleg Kalachev
7fa3baa76a Add some minor clarification under the IMU orientation picture 2024-11-30 04:59:04 +03:00
Oleg Kalachev
2c5eac92ea Add diagram for IMU orientation 2024-11-29 10:14:11 +03:00
Oleg Kalachev
048a3c6375 Use the new UART2 pins for RC by default
To make it consistent with the documentation
2024-11-27 23:02:20 +03:00
Oleg Kalachev
a65ec946c0 Update ESP32 core to 3.0.7 2024-11-24 01:45:41 +03:00
Oleg Kalachev
429aecbbad Temporarily disable macOS simulation build in CI 2024-11-24 01:08:03 +03:00
Oleg Kalachev
a7b69f99d0 Fix non-working motor control commands 2024-11-24 00:17:47 +03:00
Oleg Kalachev
b015c15a7e Remove non-working fullmot command 2024-11-24 00:10:37 +03:00
Oleg Kalachev
0c59188c6c Try to debug and fix macos simulation build failure 2024-11-23 19:32:43 +03:00
Oleg Kalachev
bb6d5aa2f0 Use macos-14 to build simulator 2024-11-23 18:57:38 +03:00
Oleg Kalachev
7a2f2d955b Minor fix to the troubleshooting 2024-11-23 18:18:19 +03:00
Oleg Kalachev
c611549f67 Update link to the troubleshooting article 2024-11-23 18:16:46 +03:00
Oleg Kalachev
be3c5bf312 Add troubleshooting article 2024-11-23 18:13:41 +03:00
Oleg Kalachev
f6ddeb4689 Clarify GY-91 pin names 2024-11-12 21:02:47 +03:00
Oleg Kalachev
f6006d3305 Fix c_cpp_properties.json to match updated ESP32 core version 2024-11-04 16:35:22 +03:00
Oleg Kalachev
eca48c6546 Minor fix 2024-11-04 16:28:54 +03:00
Oleg Kalachev
cd5f6721dc Updates to LED control code
Don't call digitaWrite on each setLED call
2024-11-04 16:28:43 +03:00
Oleg Kalachev
e7445599cc Update core and libraries to the most recent versions 2024-11-04 16:28:13 +03:00
Oleg Kalachev
6327585754 Print accel calibration parameters in more convenient way 2024-11-04 14:37:05 +03:00
Oleg Kalachev
ec832d4e37 Implement RC fail-safe 2024-11-04 11:51:17 +03:00
Oleg Kalachev
2fdad7bdb6 Remove LED horizontality signalization
It's better to control the attitude estimation using QGC
2024-11-03 17:41:13 +03:00
Oleg Kalachev
c5c889679b Fix simulation build 2024-10-31 19:27:27 +03:00
Oleg Kalachev
ad2c64625c Print the IMU information in imu command 2024-10-31 10:24:00 +03:00
Oleg Kalachev
39d4f39932 Some updates in docs 2024-10-30 09:45:27 +03:00
Oleg Kalachev
57fe3fef2a Upload STEP files for models 2024-10-29 14:18:03 +03:00
Oleg Kalachev
4ba9accf4b Fix image for washer-m3 model 2024-10-29 14:04:42 +03:00
26 changed files with 6720 additions and 97 deletions

View File

@@ -19,7 +19,7 @@ jobs:
run: tools/check_c_cpp_properties.py
build_macos:
runs-on: macos-latest
runs-on: macos-14
steps:
- uses: actions/checkout@v4
- name: Install Arduino CLI
@@ -61,7 +61,7 @@ jobs:
retention-days: 1
build_simulator_macos:
runs-on: macos-latest
runs-on: macos-15
steps:
- name: Install Arduino CLI
run: brew install arduino-cli
@@ -79,3 +79,21 @@ jobs:
run: brew install sdl2
- name: Build simulator
run: make build_simulator
install_gz_ionic_macos:
runs-on: macos-15
steps:
- name: Install Gazebo
run: brew update && brew tap osrf/simulation && brew install gz-ionic
install_gz_jetty_macos:
runs-on: macos-15
steps:
- name: Install Gazebo
run: brew update && brew tap osrf/simulation && brew install gz-jetty
install_gz_harmonic_macos:
runs-on: macos-15
steps:
- name: Install Gazebo
run: brew update && brew tap osrf/simulation && brew install gz-harmonic

View File

@@ -5,18 +5,18 @@
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/libraries/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/**",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/dio_qspi/include",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/**",
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include",
"~/Arduino/libraries/**",
"/usr/include/**"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32/Arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32/pins_arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32/Arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",
@@ -52,18 +52,18 @@
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/libraries/**",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/include/**",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/dio_qspi/include",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/include/**",
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include",
"~/Documents/Arduino/libraries/**",
"/opt/homebrew/include/**"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32/Arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32/pins_arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32/Arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/flix.ino",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
@@ -100,17 +100,17 @@
"includePath": [
"${workspaceFolder}/flix",
"${workspaceFolder}/gazebo",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/libraries/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/**",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-dc859c1e67/esp32/dio_qspi/include",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/libraries/**",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/**",
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.1-632e0c2a/esp32/dio_qspi/include",
"~/Documents/Arduino/libraries/**"
],
"forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/cores/esp32/Arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.3/variants/d1_mini32/pins_arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/cores/esp32/Arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.0.7/variants/d1_mini32/pins_arduino.h",
"${workspaceFolder}/flix/cli.ino",
"${workspaceFolder}/flix/control.ino",
"${workspaceFolder}/flix/estimate.ino",

View File

@@ -13,10 +13,10 @@ monitor:
dependencies .dependencies:
arduino-cli core update-index --config-file arduino-cli.yaml
arduino-cli core install esp32:esp32@3.0.3 --config-file arduino-cli.yaml
arduino-cli core install esp32:esp32@3.0.7 --config-file arduino-cli.yaml
arduino-cli lib update-index
arduino-cli lib install "FlixPeriph"
arduino-cli lib install "MAVLink"@2.0.10
arduino-cli lib install "MAVLink"@2.0.12
touch .dependencies
gazebo/build cmake: gazebo/CMakeLists.txt

View File

@@ -53,25 +53,27 @@ See [instructions on running the simulation](docs/build.md).
|Type|Part|Image|Quantity|
|-|-|:-:|:-:|
|Microcontroller board|ESP32 Mini|<img src="docs/img/esp32.jpg" width=100>|1|
|IMU and barometer² board|GY-91 (or other MPU-9250 board)|<img src="docs/img/gy-91.jpg" width=100>|1|
|IMU (and barometer²) board|GY91 (or other MPU9250/MPU6500 board), ICM20948³|<img src="docs/img/gy-91.jpg" width=90 align=center><img src="docs/img/icm-20948.jpg" width=100>|1|
|Motor|8520 3.7V brushed motor (**shaft 0.8mm!**)|<img src="docs/img/motor.jpeg" width=100>|4|
|Propeller|Hubsan 55 mm|<img src="docs/img/prop.jpg" width=100>|4|
|MOSFET (transistor)|100N03A or [compatible](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4|
|MOSFET (transistor)|100N03A or [analog](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4|
|Pull-down resistor|10 kΩ|<img src="docs/img/resistor10k.jpg" width=100>|4|
|3.7V Li-Po battery|LW 952540 (or any compatible by the size)|<img src="docs/img/battery.jpg" width=100>|1|
|Li-Po Battery charger|Any|<img src="docs/img/charger.jpg" width=100>|1|
|Screws for IMU board mounting|M3x5|<img src="docs/img/screw-m3.jpg" width=100>|2|
|Screws for frame assembly|M1.4x5|<img src="docs/img/screw-m1.4.jpg" height=30 align=center>|4|
|Frame bottom part|3D printed: [`flix-frame.stl`](docs/assets/flix-frame.stl)|<img src="docs/img/frame1.jpg" width=100>|1|
|Frame top part|3D printed: [`esp32-holder.stl`](docs/assets/esp32-holder.stl)|<img src="docs/img/esp32-holder.jpg" width=100>|1|
|Washer for IMU board mounting|3D printed: [`washer-m3.stl`](docs/assets/washer-m3.stl)|<img src="docs/img/washer-m3.jpg" width=100>|1|
|*RC transmitter (optional)*|*KINGKONG TINY X8 or other³*|<img src="docs/img/tx.jpg" width=100>|1|
|*RC receiver (optional)*|*DF500 or other³*|<img src="docs/img/rx.jpg" width=100>|1|
|Frame bottom part|3D printed⁴:<br>[`flix-frame.stl`](docs/assets/flix-frame.stl) [`flix-frame.step`](docs/assets/flix-frame.step)|<img src="docs/img/frame1.jpg" width=100>|1|
|Frame top part|3D printed:<br>[`esp32-holder.stl`](docs/assets/esp32-holder.stl) [`esp32-holder.step`](docs/assets/esp32-holder.step)|<img src="docs/img/esp32-holder.jpg" width=100>|1|
|Washer for IMU board mounting|3D printed:<br>[`washer-m3.stl`](docs/assets/washer-m3.stl) [`washer-m3.step`](docs/assets/washer-m3.step)|<img src="docs/img/washer-m3.jpg" width=100>|1|
|*RC transmitter (optional)*|*KINGKONG TINY X8 or other*|<img src="docs/img/tx.jpg" width=100>|1|
|*RC receiver (optional)*|*DF500 or other*|<img src="docs/img/rx.jpg" width=100>|1|
|Wires|28 AWG recommended|<img src="docs/img/wire-28awg.jpg" width=100>||
|Tape, double-sided tape||||
*² — barometer is not used for now.*<br>
*³ — you may use any transmitter-receiver pair with SBUS interface.*
*³ — change `MPU9250` to `ICM20948` in `imu.ino` file if using ICM-20948 board.*<br>
*⁴ — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*<br>
*⁵ — you may use any transmitter-receiver pair with SBUS interface.*
Tools required for assembly:
@@ -98,15 +100,15 @@ Complete diagram is Work-in-Progress.
### Notes
* Power ESP32 Mini with Li-Po battery using VCC (+) and GND (-) pins.
* Connect the GY-91 board to the ESP32 Mini using VSPI, power it using 3.3V and GND pins:
* Connect the IMU board to the ESP32 Mini using VSPI, power it using 3.3V and GND pins:
|GY-91 pin|ESP32 pin|
|IMU pin|ESP32 pin|
|-|-|
|GND|GND|
|3.3V|3.3V|
|SCK|SVP (GPIO18)|
|MOSI|GPIO23|
|MISO|GPIO19|
|SCL *(SCK)*|SVP (GPIO18)|
|SDA *(MOSI)*|GPIO23|
|SAO *(MISO)*|GPIO19|
|NCS|GPIO5|
* Solder pull-down resistors to the MOSFETs.
@@ -127,9 +129,19 @@ Complete diagram is Work-in-Progress.
|-|-|
|GND|GND|
|VIN|VC (or 3.3V depending on the receiver)|
|Signal|GPIO4|
|Signal|GPIO4|
* — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.*
* — UART2 RX pin was [changed](https://docs.espressif.com/projects/arduino-esp32/en/latest/migration_guides/2.x_to_3.0.html#id14) to GPIO4 in Arduino ESP32 core 3.0.*
### IMU placement
Required IMU orientation on the drone is **FLU** (Forward, Left, Up)⁷:
<img src="docs/img/flu.svg" width=400 alt="GY-91 axis">
In case of using **FRD** orientation (Forward, Right, Down), use [the code for rotation](https://gist.github.com/okalachev/713db47e31bce643dbbc9539d166ce98).
*⁷ — This X/Y/Z IMU axis orientation is used in the Flix IMU library, internal accel/gyro/mag axes differ.*
## Version 0

File diff suppressed because it is too large Load Diff

5113
docs/assets/flix-frame.step Normal file

File diff suppressed because it is too large Load Diff

200
docs/assets/washer-m3.step Normal file
View File

@@ -0,0 +1,200 @@
ISO-10303-21;
HEADER;
FILE_DESCRIPTION(
/* description */ (''),
/* implementation_level */ '2;1');
FILE_NAME(
/* name */ 'washer-m3.step',
/* time_stamp */ '2024-10-29T13:59:42+03:00',
/* author */ (''),
/* organization */ (''),
/* preprocessor_version */ '',
/* originating_system */ '',
/* authorisation */ '');
FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }'));
ENDSEC;
DATA;
#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#125);
#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#132,#12);
#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#124);
#13=STYLED_ITEM('',(#141),#14);
#14=MANIFOLD_SOLID_BREP('Body1',#65);
#15=FACE_BOUND('',#26,.T.);
#16=FACE_BOUND('',#28,.T.);
#17=PLANE('',#85);
#18=PLANE('',#86);
#19=FACE_OUTER_BOUND('',#23,.T.);
#20=FACE_OUTER_BOUND('',#24,.T.);
#21=FACE_OUTER_BOUND('',#25,.T.);
#22=FACE_OUTER_BOUND('',#27,.T.);
#23=EDGE_LOOP('',(#47,#48,#49,#50));
#24=EDGE_LOOP('',(#51,#52,#53,#54));
#25=EDGE_LOOP('',(#55));
#26=EDGE_LOOP('',(#56));
#27=EDGE_LOOP('',(#57));
#28=EDGE_LOOP('',(#58));
#29=LINE('',#112,#31);
#30=LINE('',#118,#32);
#31=VECTOR('',#93,1.7);
#32=VECTOR('',#100,2.7);
#33=CIRCLE('',#80,1.7);
#34=CIRCLE('',#81,1.7);
#35=CIRCLE('',#83,2.7);
#36=CIRCLE('',#84,2.7);
#37=VERTEX_POINT('',#109);
#38=VERTEX_POINT('',#111);
#39=VERTEX_POINT('',#115);
#40=VERTEX_POINT('',#117);
#41=EDGE_CURVE('',#37,#37,#33,.T.);
#42=EDGE_CURVE('',#37,#38,#29,.T.);
#43=EDGE_CURVE('',#38,#38,#34,.T.);
#44=EDGE_CURVE('',#39,#39,#35,.T.);
#45=EDGE_CURVE('',#39,#40,#30,.T.);
#46=EDGE_CURVE('',#40,#40,#36,.T.);
#47=ORIENTED_EDGE('',*,*,#41,.F.);
#48=ORIENTED_EDGE('',*,*,#42,.T.);
#49=ORIENTED_EDGE('',*,*,#43,.T.);
#50=ORIENTED_EDGE('',*,*,#42,.F.);
#51=ORIENTED_EDGE('',*,*,#44,.F.);
#52=ORIENTED_EDGE('',*,*,#45,.T.);
#53=ORIENTED_EDGE('',*,*,#46,.T.);
#54=ORIENTED_EDGE('',*,*,#45,.F.);
#55=ORIENTED_EDGE('',*,*,#44,.T.);
#56=ORIENTED_EDGE('',*,*,#41,.T.);
#57=ORIENTED_EDGE('',*,*,#46,.F.);
#58=ORIENTED_EDGE('',*,*,#43,.F.);
#59=CYLINDRICAL_SURFACE('',#79,1.7);
#60=CYLINDRICAL_SURFACE('',#82,2.7);
#61=ADVANCED_FACE('',(#19),#59,.F.);
#62=ADVANCED_FACE('',(#20),#60,.T.);
#63=ADVANCED_FACE('',(#21,#15),#17,.T.);
#64=ADVANCED_FACE('',(#22,#16),#18,.F.);
#65=CLOSED_SHELL('',(#61,#62,#63,#64));
#66=DERIVED_UNIT_ELEMENT(#68,1.);
#67=DERIVED_UNIT_ELEMENT(#127,-3.);
#68=(
MASS_UNIT()
NAMED_UNIT(*)
SI_UNIT(.KILO.,.GRAM.)
);
#69=DERIVED_UNIT((#66,#67));
#70=MEASURE_REPRESENTATION_ITEM('density measure',
POSITIVE_RATIO_MEASURE(7850.),#69);
#71=PROPERTY_DEFINITION_REPRESENTATION(#76,#73);
#72=PROPERTY_DEFINITION_REPRESENTATION(#77,#74);
#73=REPRESENTATION('material name',(#75),#124);
#74=REPRESENTATION('density',(#70),#124);
#75=DESCRIPTIVE_REPRESENTATION_ITEM('Steel','Steel');
#76=PROPERTY_DEFINITION('material property','material name',#134);
#77=PROPERTY_DEFINITION('material property','density of part',#134);
#78=AXIS2_PLACEMENT_3D('',#107,#87,#88);
#79=AXIS2_PLACEMENT_3D('',#108,#89,#90);
#80=AXIS2_PLACEMENT_3D('',#110,#91,#92);
#81=AXIS2_PLACEMENT_3D('',#113,#94,#95);
#82=AXIS2_PLACEMENT_3D('',#114,#96,#97);
#83=AXIS2_PLACEMENT_3D('',#116,#98,#99);
#84=AXIS2_PLACEMENT_3D('',#119,#101,#102);
#85=AXIS2_PLACEMENT_3D('',#120,#103,#104);
#86=AXIS2_PLACEMENT_3D('',#121,#105,#106);
#87=DIRECTION('axis',(0.,0.,1.));
#88=DIRECTION('refdir',(1.,0.,0.));
#89=DIRECTION('center_axis',(0.,0.,1.));
#90=DIRECTION('ref_axis',(1.,0.,0.));
#91=DIRECTION('center_axis',(0.,0.,-1.));
#92=DIRECTION('ref_axis',(1.,0.,0.));
#93=DIRECTION('',(0.,0.,-1.));
#94=DIRECTION('center_axis',(0.,0.,-1.));
#95=DIRECTION('ref_axis',(1.,0.,0.));
#96=DIRECTION('center_axis',(0.,0.,1.));
#97=DIRECTION('ref_axis',(1.,0.,0.));
#98=DIRECTION('center_axis',(0.,0.,1.));
#99=DIRECTION('ref_axis',(1.,0.,0.));
#100=DIRECTION('',(0.,0.,-1.));
#101=DIRECTION('center_axis',(0.,0.,1.));
#102=DIRECTION('ref_axis',(1.,0.,0.));
#103=DIRECTION('center_axis',(0.,0.,1.));
#104=DIRECTION('ref_axis',(1.,0.,0.));
#105=DIRECTION('center_axis',(0.,0.,1.));
#106=DIRECTION('ref_axis',(1.,0.,0.));
#107=CARTESIAN_POINT('',(0.,0.,0.));
#108=CARTESIAN_POINT('Origin',(0.,0.,0.));
#109=CARTESIAN_POINT('',(-1.7,-2.0818995585505E-16,2.));
#110=CARTESIAN_POINT('Origin',(0.,0.,2.));
#111=CARTESIAN_POINT('',(-1.7,-2.0818995585505E-16,0.));
#112=CARTESIAN_POINT('',(-1.7,-2.0818995585505E-16,0.));
#113=CARTESIAN_POINT('Origin',(0.,0.,0.));
#114=CARTESIAN_POINT('Origin',(0.,0.,0.));
#115=CARTESIAN_POINT('',(-2.7,-3.30654635769785E-16,2.));
#116=CARTESIAN_POINT('Origin',(0.,0.,2.));
#117=CARTESIAN_POINT('',(-2.7,-3.30654635769785E-16,0.));
#118=CARTESIAN_POINT('',(-2.7,-3.30654635769785E-16,0.));
#119=CARTESIAN_POINT('Origin',(0.,0.,0.));
#120=CARTESIAN_POINT('Origin',(0.,0.,2.));
#121=CARTESIAN_POINT('Origin',(0.,0.,0.));
#122=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#126,
'DISTANCE_ACCURACY_VALUE',
'Maximum model space distance between geometric entities at asserted c
onnectivities');
#123=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#126,
'DISTANCE_ACCURACY_VALUE',
'Maximum model space distance between geometric entities at asserted c
onnectivities');
#124=(
GEOMETRIC_REPRESENTATION_CONTEXT(3)
GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#122))
GLOBAL_UNIT_ASSIGNED_CONTEXT((#126,#128,#129))
REPRESENTATION_CONTEXT('','3D')
);
#125=(
GEOMETRIC_REPRESENTATION_CONTEXT(3)
GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#123))
GLOBAL_UNIT_ASSIGNED_CONTEXT((#126,#128,#129))
REPRESENTATION_CONTEXT('','3D')
);
#126=(
LENGTH_UNIT()
NAMED_UNIT(*)
SI_UNIT(.MILLI.,.METRE.)
);
#127=(
LENGTH_UNIT()
NAMED_UNIT(*)
SI_UNIT($,.METRE.)
);
#128=(
NAMED_UNIT(*)
PLANE_ANGLE_UNIT()
SI_UNIT($,.RADIAN.)
);
#129=(
NAMED_UNIT(*)
SI_UNIT($,.STERADIAN.)
SOLID_ANGLE_UNIT()
);
#130=SHAPE_DEFINITION_REPRESENTATION(#131,#132);
#131=PRODUCT_DEFINITION_SHAPE('',$,#134);
#132=SHAPE_REPRESENTATION('',(#78),#124);
#133=PRODUCT_DEFINITION_CONTEXT('part definition',#138,'design');
#134=PRODUCT_DEFINITION('washer-m3','washer-m3',#135,#133);
#135=PRODUCT_DEFINITION_FORMATION('',$,#140);
#136=PRODUCT_RELATED_PRODUCT_CATEGORY('washer-m3','washer-m3',(#140));
#137=APPLICATION_PROTOCOL_DEFINITION('international standard',
'automotive_design',2009,#138);
#138=APPLICATION_CONTEXT(
'Core Data for Automotive Mechanical Design Process');
#139=PRODUCT_CONTEXT('part definition',#138,'mechanical');
#140=PRODUCT('washer-m3','washer-m3',$,(#139));
#141=PRESENTATION_STYLE_ASSIGNMENT((#142));
#142=SURFACE_STYLE_USAGE(.BOTH.,#143);
#143=SURFACE_SIDE_STYLE('',(#144));
#144=SURFACE_STYLE_FILL_AREA(#145);
#145=FILL_AREA_STYLE('Steel - Satin',(#146));
#146=FILL_AREA_STYLE_COLOUR('Steel - Satin',#147);
#147=COLOUR_RGB('Steel - Satin',0.627450980392157,0.627450980392157,0.627450980392157);
ENDSEC;
END-ISO-10303-21;

View File

@@ -9,7 +9,9 @@ cd flix
## Simulation
### Ubuntu
### Ubuntu 20.04
The latest version of Ubuntu supported by Gazebo 11 simulator is 20.04. If you have a newer version, consider using a virtual machine.
1. Install Arduino CLI:
@@ -104,10 +106,10 @@ cd flix
### Arduino IDE (Windows, Linux, macOS)
1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended).
2. Install ESP32 core, version 3.0.3 (version 2.x is not supported). See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
2. Install ESP32 core, version 3.0.7 (version 2.x is not supported). See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
3. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
* `FlixPeriph`.
* `MAVLink`, version 2.0.10.
* `FlixPeriph`, the latest version.
* `MAVLink`, version 2.0.12.
4. Clone the project using git or [download the source code as a ZIP archive](https://codeload.github.com/okalachev/flix/zip/refs/heads/master).
5. Open the downloaded Arduino sketch `flix/flix.ino` in Arduino IDE.
6. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
@@ -163,6 +165,9 @@ Before flight using remote control, you need to calibrate it:
Then you can use your remote control to fly the drone!
> [!NOTE]
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.
### Firmware code structure
See [firmware overview](firmware.md) for more details.

81
docs/img/flu.svg Normal file

File diff suppressed because one or more lines are too long

After

Width:  |  Height:  |  Size: 47 KiB

BIN
docs/img/icm-20948.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 36 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 5.9 KiB

After

Width:  |  Height:  |  Size: 6.7 KiB

32
docs/troubleshooting.md Normal file
View File

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

View File

@@ -30,8 +30,7 @@ const char* motd =
"cr - calibrate RC\n"
"cg - calibrate gyro\n"
"ca - calibrate accel\n"
"mfr, mfl, mrr, mrl - test appropriate motor\n"
"fullmot <n> - full motor test\n"
"mfr, mfl, mrr, mrl - test motor\n"
"reset - reset drone's state\n";
const struct Param {
@@ -54,7 +53,7 @@ const struct Param {
{"lpr", &ratesFilter.alpha, nullptr},
{"lpd", &rollRatePID.lpf.alpha, &pitchRatePID.lpf.alpha},
{"ss", &loopFreq, nullptr},
{"ss", &loopRate, nullptr},
{"dt", &dt, nullptr},
{"t", &t, nullptr},
};
@@ -70,10 +69,11 @@ void doCommand(String& command, String& value) {
} else if (command == "psq") {
Serial.printf("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
} else if (command == "imu") {
printIMUInfo();
Serial.printf("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
Serial.printf("acc: %f %f %f\n", acc.x, acc.y, acc.z);
printIMUCal();
Serial.printf("frequency: %f\n", loopFreq);
Serial.printf("rate: %f\n", loopRate);
} else if (command == "rc") {
Serial.printf("Raw: throttle %d yaw %d pitch %d roll %d armed %d mode %d\n",
channels[RC_CHANNEL_THROTTLE], channels[RC_CHANNEL_YAW], channels[RC_CHANNEL_PITCH],
@@ -101,8 +101,6 @@ void doCommand(String& command, String& value) {
cliTestMotor(MOTOR_REAR_RIGHT);
} else if (command == "mrl") {
cliTestMotor(MOTOR_REAR_LEFT);
} else if (command == "fullmot") {
fullMotorTest(value.toInt());
} else if (command == "reset") {
attitude = Quaternion();
} else {
@@ -134,8 +132,9 @@ void showTable() {
void cliTestMotor(uint8_t n) {
Serial.printf("Testing motor %d\n", n);
motors[n] = 1;
delay(50); // ESP32 may need to wait until the end of the current cycle to change duty https://github.com/espressif/arduino-esp32/issues/5306
sendMotors();
delay(5000);
delay(3000);
motors[n] = 0;
sendMotors();
Serial.println("Done");

View File

@@ -52,6 +52,7 @@ float thrustTarget;
void control() {
interpretRC();
failsafe();
if (mode == STAB) {
controlAttitude();
controlRate();

View File

@@ -16,7 +16,6 @@ LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
void estimate() {
applyGyro();
applyAcc();
signalizeHorizontality();
}
void applyGyro() {
@@ -43,8 +42,3 @@ void applyAcc() {
attitude *= Quaternion::fromAngularRates(correction);
attitude.normalize();
}
void signalizeHorizontality() {
float angle = Vector::angleBetweenVectors(attitude.rotate(Vector(0, 0, 1)), Vector(0, 0, 1));
setLED(angle < radians(15));
}

22
flix/failsafe.ino Normal file
View File

@@ -0,0 +1,22 @@
// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Fail-safe for RC loss
#define RC_LOSS_TIMEOUT 0.2
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
void failsafe() {
if (t - controlsTime > RC_LOSS_TIMEOUT) {
descend();
}
}
void descend() {
// Smooth descend on RC lost
mode = STAB;
controls[RC_CHANNEL_ROLL] = 0;
controls[RC_CHANNEL_PITCH] = 0;
controls[RC_CHANNEL_YAW] = 0;
controls[RC_CHANNEL_THROTTLE] -= dt / DESCEND_TIME;
}

View File

@@ -25,9 +25,10 @@
float t = NAN; // current step time, s
float dt; // time delta from previous step, s
float loopFreq; // loop frequency, Hz
float loopRate; // loop rate, Hz
int16_t channels[RC_CHANNELS]; // raw rc channels
float controls[RC_CHANNELS]; // normalized controls in range [-1..1] ([0..1] for throttle)
float controlsTime; // time of the last controls update
Vector gyro; // gyroscope data
Vector acc; // accelerometer data, m/s/s
Vector rates; // filtered angular rates, rad/s

View File

@@ -27,14 +27,15 @@ void setupIMU() {
delay(1000);
}
}
configureIMU();
calibrateGyro();
}
void configureIMU() {
IMU.setAccelRange(IMU.ACCEL_RANGE_4G);
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
IMU.setDlpfBandwidth(IMU.DLPF_BANDWIDTH_184HZ);
IMU.setSrd(0); // set sample rate to 1000 Hz
IMU.setDLPF(IMU.DLPF_MAX);
IMU.setRate(IMU.RATE_1KHZ_APPROX);
}
void readIMU() {
@@ -66,8 +67,6 @@ void calibrateGyro() {
void calibrateAccel() {
Serial.println("Calibrating accelerometer");
IMU.setAccelRange(IMU.ACCEL_RANGE_2G); // the most sensitive mode
IMU.setDlpfBandwidth(IMU.DLPF_BANDWIDTH_20HZ);
IMU.setSrd(19);
Serial.setTimeout(60000);
Serial.print("Place level [enter] "); Serial.readStringUntil('\n');
@@ -88,7 +87,7 @@ void calibrateAccel() {
}
void calibrateAccelOnce() {
const int samples = 100;
const int samples = 1000;
static Vector accMax(-INFINITY, -INFINITY, -INFINITY);
static Vector accMin(INFINITY, INFINITY, INFINITY);
@@ -118,7 +117,12 @@ void calibrateAccelOnce() {
}
void printIMUCal() {
Serial.printf("gyro bias: %f %f %f\n", gyroBias.x, gyroBias.y, gyroBias.z);
Serial.printf("accel bias: %f %f %f\n", accBias.x, accBias.y, accBias.z);
Serial.printf("accel scale: %f %f %f\n", accScale.x, accScale.y, accScale.z);
Serial.printf("gyro bias: %f, %f, %f\n", gyroBias.x, gyroBias.y, gyroBias.z);
Serial.printf("accel bias: %f, %f, %f\n", accBias.x, accBias.y, accBias.z);
Serial.printf("accel scale: %f, %f, %f\n", accScale.x, accScale.y, accScale.z);
}
void printIMUInfo() {
Serial.printf("model: %s\n", IMU.getModel());
Serial.printf("who am I: 0x%02X\n", IMU.whoAmI());
}

View File

@@ -1,7 +1,7 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Main LED control
// Board's LED control
#define BLINK_PERIOD 500000
@@ -14,7 +14,12 @@ void setupLED() {
}
void setLED(bool on) {
static bool state = false;
if (on == state) {
return; // don't call digitalWrite if the state is the same
}
digitalWrite(LED_BUILTIN, on ? HIGH : LOW);
state = on;
}
void blinkLED() {

View File

@@ -93,6 +93,7 @@ void handleMavlink(const void *_msg) {
controls[RC_CHANNEL_YAW] = manualControl.r / 1000.0f * MAVLINK_CONTROL_SCALE;
controls[RC_CHANNEL_MODE] = 1; // STAB mode
controls[RC_CHANNEL_ARMED] = 1; // armed
controlsTime = t;
if (abs(controls[RC_CHANNEL_YAW]) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controls[RC_CHANNEL_YAW] = 0;
}

View File

@@ -37,14 +37,3 @@ void sendMotors() {
ledcWrite(MOTOR_2_PIN, signalToDutyCycle(motors[2]));
ledcWrite(MOTOR_3_PIN, signalToDutyCycle(motors[3]));
}
void fullMotorTest(int n) {
printf("Full test for motor %d\n", n);
for (float signal = 0; signal <= 1; signal += 0.1) {
printf("Motor %d: %f\n", n, signal);
ledcWrite(n, signalToDutyCycle(signal));
delay(3000);
}
printf("Motor %d: %f\n", n, 0);
ledcWrite(n, signalToDutyCycle(0));
}

View File

@@ -9,7 +9,7 @@
int channelNeutral[] = {995, 883, 200, 972, 512, 512, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
int channelMax[] = {1651, 1540, 1713, 1630, 1472, 1472, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
SBUS RC(Serial2, 16, 17); // NOTE: remove pin numbers (16, 17) if you use the new default pins for Serial2 (4, 25)
SBUS RC(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
void setupRC() {
Serial.println("Setup RC");
@@ -21,6 +21,7 @@ void readRC() {
SBUSData data = RC.data();
memcpy(channels, data.ch, sizeof(channels)); // copy channels data
normalizeRC();
controlsTime = t;
}
}

View File

@@ -12,16 +12,16 @@ void step() {
dt = 0; // assume dt to be zero on first step and on reset
}
computeLoopFreq();
computeLoopRate();
}
void computeLoopFreq() {
void computeLoopRate() {
static float windowStart = 0;
static uint32_t freq = 0;
freq++;
static uint32_t rate = 0;
rate++;
if (t - windowStart >= 1) { // 1 second window
loopFreq = freq;
loopRate = rate;
windowStart = t;
freq = 0;
rate = 0;
}
}

View File

@@ -15,14 +15,6 @@ float mapff(float x, float in_min, float in_max, float out_min, float out_max) {
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
int8_t sign(float x) {
return (x > 0) - (x < 0);
}
float randomFloat(float min, float max) {
return min + (max - min) * (float)rand() / RAND_MAX;
}
// Wrap angle to [-PI, PI)
float wrapAngle(float angle) {
angle = fmodf(angle, 2 * PI);

View File

@@ -21,20 +21,20 @@
float t = NAN;
float dt;
float loopFreq;
float loopRate;
float motors[4];
int16_t channels[16]; // raw rc channels
float controls[RC_CHANNELS];
float controlsTime;
Vector acc;
Vector gyro;
Vector rates;
Quaternion attitude;
// declarations
void computeLoopFreq();
void computeLoopRate();
void applyGyro();
void applyAcc();
void signalizeHorizontality();
void control();
void interpretRC();
void controlAttitude();
@@ -49,12 +49,14 @@ void sendMavlink();
void sendMessage(const void *msg);
void receiveMavlink();
void handleMavlink(const void *_msg);
void failsafe();
void descend();
inline Quaternion FLU2FRD(const Quaternion &q);
// mocks
void setLED(bool on) {};
void calibrateGyro() { printf("Skip gyro calibrating\n"); };
void calibrateAccel() { printf("Skip accel calibrating\n"); };
void fullMotorTest(int n) { printf("Skip full motor test\n"); };
void sendMotors() {};
void printIMUCal() { printf("cal: N/A\n"); };
void printIMUInfo() {};

View File

@@ -25,6 +25,7 @@
#include "log.ino"
#include "cli.ino"
#include "mavlink.ino"
#include "failsafe.ino"
#include "lpf.h"
using ignition::math::Vector3d;