1 Commits

Author SHA1 Message Date
Oleg Kalachev
1d99d255d0 Add parameters for IMU orientation definition 2025-12-25 09:05:06 +03:00
34 changed files with 182 additions and 345 deletions

View File

@@ -65,6 +65,5 @@
"PX4" "PX4"
] ]
}, },
"MD045": false, "MD045": false
"MD060": false
} }

View File

@@ -18,7 +18,20 @@
"forcedInclude": [ "forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h", "${workspaceFolder}/.vscode/intellisense.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h", "~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h" "~/.arduino15/packages/esp32/hardware/esp32/3.2.0/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/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
], ],
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++", "compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
"cStandard": "c11", "cStandard": "c11",
@@ -52,7 +65,20 @@
"forcedInclude": [ "forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h", "${workspaceFolder}/.vscode/intellisense.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h", "~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h" "~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/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/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
], ],
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++", "compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
"cStandard": "c11", "cStandard": "c11",
@@ -87,7 +113,20 @@
"forcedInclude": [ "forcedInclude": [
"${workspaceFolder}/.vscode/intellisense.h", "${workspaceFolder}/.vscode/intellisense.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h", "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32/pins_arduino.h" "~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/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/wifi.ino",
"${workspaceFolder}/flix/parameters.ino"
], ],
"compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++.exe", "compilerPath": "~/AppData/Local/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++.exe",
"cStandard": "c11", "cStandard": "c11",

View File

@@ -1,9 +1,6 @@
<!-- markdownlint-disable MD041 --> # Flix
<p align="center"> **Flix** (*flight + X*) — open source ESP32-based quadcopter made from scratch.
<img src="docs/img/flix.svg" width=180 alt="Flix logo"><br>
<b>Flix</b> (<i>flight + X</i>) — open source ESP32-based quadcopter made from scratch.
</p>
<table> <table>
<tr> <tr>

View File

@@ -35,7 +35,7 @@
### Подсистема управления ### Подсистема управления
Состояние органов управления обрабатывается в функции `interpretControls()` и преобразуется в **команду управления**, которая включает следующее: Состояние органов управления обрабатывается в функции `interpretControls()` и преобразуется в *команду управления*, которая включает следующее:
* `attitudeTarget` *(Quaternion)* — целевая ориентация дрона. * `attitudeTarget` *(Quaternion)* — целевая ориентация дрона.
* `ratesTarget` *(Vector)* — целевые угловые скорости, *рад/с*. * `ratesTarget` *(Vector)* — целевые угловые скорости, *рад/с*.

View File

@@ -38,13 +38,13 @@ Utility files:
### Control subsystem ### Control subsystem
Pilot inputs are interpreted in `interpretControls()`, and then converted to the **control command**, which consists of the following: Pilot inputs are interpreted in `interpretControls()`, and then converted to the *control command*, which consists of the following:
* `attitudeTarget` *(Quaternion)* — target attitude of the drone. * `attitudeTarget` *(Quaternion)* — target attitude of the drone.
* `ratesTarget` *(Vector)* — target angular rates, *rad/s*. * `ratesTarget` *(Vector)* — target angular rates, *rad/s*.
* `ratesExtra` *(Vector)* — additional (feed-forward) angular rates , used for yaw rate control in STAB mode, *rad/s*. * `ratesExtra` *(Vector)* — additional (feed-forward) angular rates , used for yaw rate control in STAB mode, *rad/s*.
* `torqueTarget` *(Vector)* — target torque, range [-1, 1]. * `torqueTarget` *(Vector)* — target torque, range [-1, 1].
* `thrustTarget` *(float)* — collective motor thrust target, range [0, 1]. * `thrustTarget` *(float)* — collective thrust target, range [0, 1].
Control command is handled in `controlAttitude()`, `controlRates()`, `controlTorque()` functions. Each function may be skipped if the corresponding control target is set to `NAN`. Control command is handled in `controlAttitude()`, `controlRates()`, `controlTorque()` functions. Each function may be skipped if the corresponding control target is set to `NAN`.
@@ -62,11 +62,6 @@ print("Test value: %.2f\n", testValue);
In order to add a console command, modify the `doCommand()` function in `cli.ino` file. In order to add a console command, modify the `doCommand()` function in `cli.ino` file.
> [!IMPORTANT]
> Avoid using delays in in-flight commands, it will **crash** the drone! (The design is one-threaded.)
>
> For on-the-ground commands, use `pause()` function, instead of `delay()`. This function allows to pause in a way that MAVLink connection will continue working.
## Building the firmware ## Building the firmware
See build instructions in [usage.md](usage.md). See build instructions in [usage.md](usage.md).

View File

@@ -1,38 +0,0 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 734.86 378.46">
<defs>
<style>
.a {
fill: none;
stroke: #d5d5d5;
stroke-miterlimit: 10;
stroke-width: 31px;
}
.b {
fill: #c1c1c1;
}
.c {
fill: #ff9400;
}
.d {
fill: #d5d5d5;
}
</style>
</defs>
<g>
<g>
<line class="a" x1="448.78" y1="294.23" x2="648.77" y2="93.24"/>
<line class="a" x1="449.78" y1="94.24" x2="649.77" y2="295.23"/>
<circle class="b" cx="549.27" cy="193.73" r="41.5"/>
<circle class="c" cx="449.35" cy="93.74" r="77.95"/>
<circle class="c" cx="648.89" cy="93.53" r="77.95"/>
<circle class="c" cx="647.89" cy="294.51" r="77.95"/>
<circle class="c" cx="448.9" cy="294.51" r="77.95"/>
</g>
<path class="d" d="M8,161.93q0-17.85,22.36-17.85h4.81V100.57Q35.17,8.49,131.23,8h1q36.87,0,47.31,7.48L181,17.41l1,2.41V50q0,12.32-5.82,12.31-2.43,0-7.4-4.64t-14.19-9a48.63,48.63,0,0,0-21.22-4.41q-12,0-19.17,3.5a18.85,18.85,0,0,0-9.82,10.62,67.35,67.35,0,0,0-3.52,12.06,82.52,82.52,0,0,0-.85,13.39v60.32h27.28q10.86,0,16.05,5.43a17.52,17.52,0,0,1,5.19,12.42,22.5,22.5,0,0,1-1.21,7.36q-1.22,3.51-6.64,7.24t-14.36,3.74H101.64V344.82a56,56,0,0,1-.61,9.65,37.8,37.8,0,0,1-2.56,7.6,11.83,11.83,0,0,1-6.94,6.4q-5,1.93-13.51,1.93H57.08q-10.47,0-15.7-4.71t-5.73-8.44a77.31,77.31,0,0,1-.48-9.53V180.27H29.4Q8,180.27,8,161.93Z"/>
<path class="d" d="M201.21,348.2V37q0-23.16,20.86-23.4h22.81q22.8,0,22.8,22.44V346.27a68.92,68.92,0,0,1-.49,9.41,22.59,22.59,0,0,1-2.42,7.12,11.48,11.48,0,0,1-6.67,5.43,47.78,47.78,0,0,1-12.74,2.17H225q-11.4,0-17.58-4.47T201.21,348.2Z"/>
<path class="d" d="M284.9,61.08V36.47a40.39,40.39,0,0,1,1.7-12.91,11.36,11.36,0,0,1,6.18-7,25.27,25.27,0,0,1,6.68-2.3c1.45-.15,4-.4,7.76-.72h25.23q10.43,0,16.73,4.7t6.31,18.22V62.05a27.94,27.94,0,0,1-.85,7.11,23,23,0,0,1-2.06,5.43,20,20,0,0,1-2.91,4,10,10,0,0,1-3.52,2.54c-1.21.48-2.54,1-4,1.44a11.53,11.53,0,0,1-3.4.73,13.71,13.71,0,0,0-3.15.48H307.7q-10.43,0-16.61-4.7T284.9,61.08Zm1.94,284.71V166.28q0-22.2,21.83-22.2h20.38q10.92,0,16.62,4t6.67,8.45a60.47,60.47,0,0,1,1,12.18V348.2q0,22.2-21.83,22.2H308.67q-10.43,0-15.64-4.95t-5.7-8.81A90.93,90.93,0,0,1,286.84,345.79Z"/>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 2.2 KiB

View File

@@ -4,7 +4,7 @@
Do the following: Do the following:
* **Check ESP32 core is installed**. Check if the version matches the one used in the [tutorial](usage.md#building-the-firmware). * **Check ESP32 core is installed**. Check if the version matches the one used in the [tutorial](usage.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. * **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.
* **Check the chosen board**. The correct board to choose in Arduino IDE for ESP32 Mini is *WEMOS D1 MINI ESP32*. * **Check the chosen board**. The correct board to choose in Arduino IDE for ESP32 Mini is *WEMOS D1 MINI ESP32*.
@@ -25,7 +25,7 @@ Do the following:
* The `accel` and `gyro` fields should change as you move the drone. * The `accel` and `gyro` fields should change as you move the drone.
* **Calibrate the accelerometer.** if is wasn't done before. Type `ca` command in Serial Monitor and follow the instructions. * **Calibrate the accelerometer.** if is wasn't done before. Type `ca` command in Serial Monitor and follow the instructions.
* **Check the attitude estimation**. Connect to the drone using QGroundControl. Rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. * **Check the attitude estimation**. Connect to the drone using QGroundControl. Rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct.
* **Check the IMU orientation is set correctly**. If the attitude estimation is rotated, set the correct IMU orientation as described in the [tutorial](usage.md#define-imu-orientation). * **Check the IMU orientation is set correctly**. If the attitude estimation is rotated, make sure `rotateIMU` function is defined correctly in `imu.ino` file.
* **Check the motors type**. Motors with exact 3.7V voltage are needed, not ranged working voltage (3.7V — 6V). * **Check the motors type**. Motors with exact 3.7V voltage are needed, not ranged working voltage (3.7V — 6V).
* **Check the motors**. Perform the following commands using Serial Monitor: * **Check the motors**. Perform the following commands using Serial Monitor:
* `mfr` — should rotate front right motor (counter-clockwise). * `mfr` — should rotate front right motor (counter-clockwise).

View File

@@ -80,7 +80,7 @@ QGroundControl is a ground control station software that can be used to monitor
1. Install mobile or desktop version of [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html). 1. Install mobile or desktop version of [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html).
2. Power up the drone. 2. Power up the drone.
3. Connect your computer or smartphone to the appeared `flix` Wi-Fi network (password: `flixwifi`). 3. Connect your computer or smartphone to the appeared `flix` Wi-Fi network (password: `flixwifi`).
4. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically. 4. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically
### Access console ### Access console
@@ -96,8 +96,7 @@ To access the console using QGroundControl:
1. Connect to the drone using QGroundControl app. 1. Connect to the drone using QGroundControl app.
2. Go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*. 2. Go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*.
<img src="img/cli.png" width="400">
<img src="img/cli.png" width="400">
> [!TIP] > [!TIP]
> Use `help` command to see the list of available commands. > Use `help` command to see the list of available commands.
@@ -108,13 +107,11 @@ The drone is configured using parameters. To access and modify them, go to the Q
<img src="img/parameters.png" width="400"> <img src="img/parameters.png" width="400">
You can also work with parameters using `p` command in the console.
### Define IMU orientation ### Define IMU orientation
Use parameters, to define the IMU board axes orientation relative to the drone's axes: `IMU_ROT_ROLL`, `IMU_ROT_PITCH`, and `IMU_ROT_YAW`. Use parameters, to define the IMU board axes orientation relative to the drone's axes: `IMU_ROT_ROLL`, `IMU_ROT_PITCH`, and `IMU_ROT_YAW`.
The drone has *X* axis pointing forward, *Y* axis pointing left, and *Z* axis pointing up, and the supported IMU boards have *X* axis pointing to the pins side and *Z* axis pointing up from the component side: The drone has *X* axis pointing forward, *Y* axis pointing left, and *Z* axis pointing up, and the supported IMU boards have *X* axis pointing to the pins side and *Z* axis pointing up from the side with the components:
<img src="img/imu-axes.png" width="200"> <img src="img/imu-axes.png" width="200">
@@ -122,10 +119,10 @@ Use the following table to set the parameters for common IMU orientations:
|Orientation|Parameters|Orientation|Parameters| |Orientation|Parameters|Orientation|Parameters|
|:-:|-|-|-| |:-:|-|-|-|
|<img src="img/imu-rot-1.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0 |<img src="img/imu-rot-5.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0| |<img src="img/imu-rot-1.png" width="200">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0 |<img src="img/imu-rot-5.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0|
|<img src="img/imu-rot-2.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|<img src="img/imu-rot-6.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571| |<img src="img/imu-rot-2.png" width="200">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|<img src="img/imu-rot-6.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|
|<img src="img/imu-rot-3.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|<img src="img/imu-rot-7.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142| |<img src="img/imu-rot-3.png" width="200">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|<img src="img/imu-rot-7.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|
|<img src="img/imu-rot-4.png" width="180"><br>☑️ **Default**|<br>`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|<img src="img/imu-rot-8.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571| |<img src="img/imu-rot-4.png" width="200"><br><b style="text-align:center">☑️ Default</b>|<br>`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|<img src="img/imu-rot-8.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|
### Calibrate accelerometer ### Calibrate accelerometer
@@ -154,10 +151,6 @@ Before flight you need to calibrate the accelerometer:
* `mrl` — should rotate rear left motor (counter-clockwise). * `mrl` — should rotate rear left motor (counter-clockwise).
* `mrr` — should rotate rear right motor (clockwise). * `mrr` — should rotate rear right motor (clockwise).
Rotation diagram:
<img src="img/motors.svg" width=200>
> [!WARNING] > [!WARNING]
> Never run the motors when powering the drone from USB, always use the battery for that. > Never run the motors when powering the drone from USB, always use the battery for that.
@@ -165,7 +158,7 @@ Before flight you need to calibrate the accelerometer:
There are several ways to control the drone's flight: using **smartphone** (Wi-Fi), using **SBUS remote control**, or using **USB remote control** (Wi-Fi). There are several ways to control the drone's flight: using **smartphone** (Wi-Fi), using **SBUS remote control**, or using **USB remote control** (Wi-Fi).
### Control with a smartphone ### Control with smartphone
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone. 1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone.
2. Power the drone using the battery. 2. Power the drone using the battery.
@@ -177,7 +170,7 @@ There are several ways to control the drone's flight: using **smartphone** (Wi-F
> [!TIP] > [!TIP]
> Decrease `CTL_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive. > Decrease `CTL_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
### Control with a remote control ### Control with remote control
Before using remote SBUS-connected remote control, you need to calibrate it: Before using remote SBUS-connected remote control, you need to calibrate it:
@@ -185,7 +178,7 @@ Before using remote SBUS-connected remote control, you need to calibrate it:
2. Type `cr` command and follow the instructions. 2. Type `cr` command and follow the instructions.
3. Use the remote control to fly the drone! 3. Use the remote control to fly the drone!
### Control with a USB remote control ### Control with USB remote control
If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it. If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it.
@@ -243,6 +236,8 @@ In this mode, the pilot inputs are ignored (except the mode switch, if configure
If the pilot moves the control sticks, the drone will switch back to *STAB* mode. If the pilot moves the control sticks, the drone will switch back to *STAB* mode.
<img src="img/parameters.png" width="400">
## Flight log ## Flight log
After the flight, you can download the flight log for analysis wirelessly. Use the following for that: After the flight, you can download the flight log for analysis wirelessly. Use the following for that:

View File

@@ -16,7 +16,7 @@ Author: [goldarte](https://t.me/goldarte).<br>
## School 548 course ## School 548 course
Special course on quadcopter design and engineering took place in october-november 2025 in School 548, Moscow. The course included UAV control theory, electronics, drone assembly and setup practice, using the Flix project. Special quadcopter design and engineering course took place in october-november 2025 in School 548, Moscow. Course included UAV control theory, electronics, and practical drone assembly and setup using the Flix project.
<img height=200 src="img/user/school548/1.jpg"> <img height=200 src="img/user/school548/2.jpg"> <img height=200 src="img/user/school548/3.jpg"> <img height=200 src="img/user/school548/1.jpg"> <img height=200 src="img/user/school548/2.jpg"> <img height=200 src="img/user/school548/3.jpg">
@@ -25,7 +25,7 @@ STL files and other materials: see [here](https://drive.google.com/drive/folders
### Selected works ### Selected works
Author: [KiraFlux](https://t.me/@kiraflux_0XC0000005).<br> Author: [KiraFlux](https://t.me/@kiraflux_0XC0000005).<br>
Description: **custom ESPNOW remote control** was implemented, modified firmware to support ESPNOW protocol.<br> Description: **custom ESPNOW remote control** is implemented, firmware modified to support ESPNOW protocol.<br>
Telegram posts: [1](https://t.me/opensourcequadcopter/106), [2](https://t.me/opensourcequadcopter/114).<br> Telegram posts: [1](https://t.me/opensourcequadcopter/106), [2](https://t.me/opensourcequadcopter/114).<br>
Modified Flix firmware: https://github.com/KiraFlux/flix/tree/klyax.<br> Modified Flix firmware: https://github.com/KiraFlux/flix/tree/klyax.<br>
Remote control project: https://github.com/KiraFlux/ESP32-DJC.<br> Remote control project: https://github.com/KiraFlux/ESP32-DJC.<br>

View File

@@ -3,8 +3,6 @@
// Implementation of command line interface // Implementation of command line interface
#include <Arduino.h>
#include "flix.h"
#include "pid.h" #include "pid.h"
#include "vector.h" #include "vector.h"
#include "util.h" #include "util.h"
@@ -13,7 +11,7 @@ extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRO
extern const int RAW, ACRO, STAB, AUTO; extern const int RAW, ACRO, STAB, AUTO;
extern float t, dt, loopRate; extern float t, dt, loopRate;
extern uint16_t channels[16]; extern uint16_t channels[16];
extern float controlTime; extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
extern int mode; extern int mode;
extern bool armed; extern bool armed;
@@ -73,7 +71,7 @@ void pause(float duration) {
} }
} }
void doCommand(String str, bool echo) { void doCommand(String str, bool echo = false) {
// parse command // parse command
String command, arg0, arg1; String command, arg0, arg1;
splitString(str, command, arg0, arg1); splitString(str, command, arg0, arg1);
@@ -134,7 +132,6 @@ void doCommand(String str, bool echo) {
} }
print("\nroll: %g pitch: %g yaw: %g throttle: %g mode: %g\n", print("\nroll: %g pitch: %g yaw: %g throttle: %g mode: %g\n",
controlRoll, controlPitch, controlYaw, controlThrottle, controlMode); controlRoll, controlPitch, controlYaw, controlThrottle, controlMode);
print("time: %.1f\n", controlTime);
print("mode: %s\n", getModeName()); print("mode: %s\n", getModeName());
print("armed: %d\n", armed); print("armed: %d\n", armed);
} else if (command == "wifi") { } else if (command == "wifi") {

View File

@@ -1,55 +0,0 @@
// Wi-Fi
#define WIFI_ENABLED 1
#define WIFI_SSID "flix"
#define WIFI_PASSWORD "flixwifi"
#define WIFI_UDP_PORT 14550
#define WIFI_UDP_REMOTE_PORT 14550
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
// Motors
#define MOTOR_0_PIN 12 // rear left
#define MOTOR_1_PIN 13 // rear right
#define MOTOR_2_PIN 14 // front right
#define MOTOR_3_PIN 15 // front left
#define PWM_FREQUENCY 78000
#define PWM_RESOLUTION 10
#define PWM_STOP 0
#define PWM_MIN 0
#define PWM_MAX 1000000 / PWM_FREQUENCY
// Control
#define PITCHRATE_P 0.05
#define PITCHRATE_I 0.2
#define PITCHRATE_D 0.001
#define PITCHRATE_I_LIM 0.3
#define ROLLRATE_P PITCHRATE_P
#define ROLLRATE_I PITCHRATE_I
#define ROLLRATE_D PITCHRATE_D
#define ROLLRATE_I_LIM PITCHRATE_I_LIM
#define YAWRATE_P 0.3
#define YAWRATE_I 0.0
#define YAWRATE_D 0.0
#define YAWRATE_I_LIM 0.3
#define ROLL_P 6
#define ROLL_I 0
#define ROLL_D 0
#define PITCH_P ROLL_P
#define PITCH_I ROLL_I
#define PITCH_D ROLL_D
#define YAW_P 3
#define PITCHRATE_MAX radians(360)
#define ROLLRATE_MAX radians(360)
#define YAWRATE_MAX radians(300)
#define TILT_MAX radians(30)
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
// Estimation
#define WEIGHT_ACC 0.003
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
// MAVLink
#define SYSTEM_ID 1
// Safety
#define RC_LOSS_TIMEOUT 1
#define DESCEND_TIME 10

View File

@@ -3,25 +3,41 @@
// Flight control // Flight control
#include "config.h"
#include "flix.h"
#include "vector.h" #include "vector.h"
#include "quaternion.h" #include "quaternion.h"
#include "pid.h" #include "pid.h"
#include "lpf.h" #include "lpf.h"
#include "util.h" #include "util.h"
extern const int RAW = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes #define PITCHRATE_P 0.05
#define PITCHRATE_I 0.2
#define PITCHRATE_D 0.001
#define PITCHRATE_I_LIM 0.3
#define ROLLRATE_P PITCHRATE_P
#define ROLLRATE_I PITCHRATE_I
#define ROLLRATE_D PITCHRATE_D
#define ROLLRATE_I_LIM PITCHRATE_I_LIM
#define YAWRATE_P 0.3
#define YAWRATE_I 0.0
#define YAWRATE_D 0.0
#define YAWRATE_I_LIM 0.3
#define ROLL_P 6
#define ROLL_I 0
#define ROLL_D 0
#define PITCH_P ROLL_P
#define PITCH_I ROLL_I
#define PITCH_D ROLL_D
#define YAW_P 3
#define PITCHRATE_MAX radians(360)
#define ROLLRATE_MAX radians(360)
#define YAWRATE_MAX radians(300)
#define TILT_MAX radians(30)
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
const int RAW = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
int mode = STAB; int mode = STAB;
bool armed = false; bool armed = false;
Quaternion attitudeTarget;
Vector ratesTarget;
Vector ratesExtra; // feedforward rates
Vector torqueTarget;
float thrustTarget;
PID rollRatePID(ROLLRATE_P, ROLLRATE_I, ROLLRATE_D, ROLLRATE_I_LIM, RATES_D_LPF_ALPHA); PID rollRatePID(ROLLRATE_P, ROLLRATE_I, ROLLRATE_D, ROLLRATE_I_LIM, RATES_D_LPF_ALPHA);
PID pitchRatePID(PITCHRATE_P, PITCHRATE_I, PITCHRATE_D, PITCHRATE_I_LIM, RATES_D_LPF_ALPHA); PID pitchRatePID(PITCHRATE_P, PITCHRATE_I, PITCHRATE_D, PITCHRATE_I_LIM, RATES_D_LPF_ALPHA);
PID yawRatePID(YAWRATE_P, YAWRATE_I, YAWRATE_D); PID yawRatePID(YAWRATE_P, YAWRATE_I, YAWRATE_D);
@@ -31,6 +47,12 @@ PID yawPID(YAW_P, 0, 0);
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX); Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
float tiltMax = TILT_MAX; float tiltMax = TILT_MAX;
Quaternion attitudeTarget;
Vector ratesTarget;
Vector ratesExtra; // feedforward rates
Vector torqueTarget;
float thrustTarget;
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT; extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode; extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;

View File

@@ -3,17 +3,11 @@
// Attitude estimation from gyro and accelerometer // Attitude estimation from gyro and accelerometer
#include "config.h"
#include "flix.h"
#include "quaternion.h" #include "quaternion.h"
#include "vector.h" #include "vector.h"
#include "lpf.h" #include "lpf.h"
#include "util.h" #include "util.h"
Vector rates; // estimated angular rates, rad/s
Quaternion attitude; // estimated attitude
bool landed;
float accWeight = 0.003; float accWeight = 0.003;
LowPassFilter<Vector> ratesFilter(0.2); // cutoff frequency ~ 40 Hz LowPassFilter<Vector> ratesFilter(0.2); // cutoff frequency ~ 40 Hz

View File

@@ -1,90 +0,0 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// All-in-one header file
#pragma once
#include <Arduino.h>
#include "vector.h"
#include "quaternion.h"
extern float t, dt;
extern float loopRate;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
extern Vector gyro, acc;
extern Vector rates;
extern Quaternion attitude;
extern bool landed;
extern int mode;
extern bool armed;
extern Quaternion attitudeTarget;
extern Vector ratesTarget, ratesExtra, torqueTarget;
extern float thrustTarget;
extern float motors[4];
void print(const char* format, ...);
void pause(float duration);
void doCommand(String str, bool echo = false);
void handleInput();
void control();
void interpretControls();
void controlAttitude();
void controlRates();
void controlTorque();
const char *getModeName();
void estimate();
void applyGyro();
void applyAcc();
void setupIMU();
void configureIMU();
void readIMU();
void rotateIMU(Vector& data);
void calibrateGyroOnce();
void calibrateAccel();
void calibrateAccelOnce();
void printIMUCalibration();
void printIMUInfo();
void setupLED();
void setLED(bool on);
void blinkLED();
void prepareLogData();
void logData();
void printLogHeader();
void printLogData();
void processMavlink();
void sendMavlink();
void sendMessage(const void *msg);
void receiveMavlink();
void handleMavlink(const void *_msg);
void mavlinkPrint(const char* str);
void sendMavlinkPrint();
void setupMotors();
int getDutyCycle(float value);
void sendMotors();
bool motorsActive();
void testMotor(int n);
void setupParameters();
int parametersCount();
const char *getParameterName(int index);
float getParameter(int index);
float getParameter(const char *name);
bool setParameter(const char *name, const float value);
void syncParameters();
void printParameters();
void resetParameters();
void setupRC();
bool readRC();
void normalizeRC();
void calibrateRC();
void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const char *str);
void printRCCalibration();
void failsafe();
void rcLossFailsafe();
void descend();
void autoFailsafe();
void step();
void computeLoopRate();
void setupWiFi();
void sendWiFi(const uint8_t *buf, int len);
int receiveWiFi(uint8_t *buf, int len);

View File

@@ -3,11 +3,22 @@
// Main firmware file // Main firmware file
#include "config.h"
#include "vector.h" #include "vector.h"
#include "quaternion.h" #include "quaternion.h"
#include "util.h" #include "util.h"
#include "flix.h"
#define WIFI_ENABLED 1
float t = NAN; // current step time, s
float dt; // time delta from previous step, s
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN;
Vector gyro; // gyroscope data
Vector acc; // accelerometer data, m/s/s
Vector rates; // filtered angular rates, rad/s
Quaternion attitude; // estimated attitude
bool landed; // are we landed and stationary
float motors[4]; // normalized motors thrust in range [0..1]
void setup() { void setup() {
Serial.begin(115200); Serial.begin(115200);

View File

@@ -12,12 +12,9 @@
MPU9250 imu(SPI); MPU9250 imu(SPI);
Vector imuRotation(0, 0, -PI / 2); // imu orientation as Euler angles Vector imuRotation(0, 0, -PI / 2); // imu orientation as Euler angles
Vector gyro; // gyroscope output, rad/s
Vector gyroBias;
Vector acc; // accelerometer output, m/s/s
Vector accBias; Vector accBias;
Vector accScale(1, 1, 1); Vector accScale(1, 1, 1);
Vector gyroBias;
void setupIMU() { void setupIMU() {
print("Setup IMU\n"); print("Setup IMU\n");
@@ -47,6 +44,7 @@ void readIMU() {
gyro = Quaternion::rotateVector(gyro, rotation.inversed()); gyro = Quaternion::rotateVector(gyro, rotation.inversed());
} }
void calibrateGyroOnce() { void calibrateGyroOnce() {
static Delay landedDelay(2); static Delay landedDelay(2);
if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary

View File

@@ -3,8 +3,6 @@
// Board's LED control // Board's LED control
#include <Arduino.h>
#define BLINK_PERIOD 500000 #define BLINK_PERIOD 500000
#ifndef LED_BUILTIN #ifndef LED_BUILTIN

View File

@@ -3,7 +3,6 @@
// In-RAM logging // In-RAM logging
#include "flix.h"
#include "vector.h" #include "vector.h"
#include "util.h" #include "util.h"

View File

@@ -5,8 +5,6 @@
#pragma once #pragma once
#include <Arduino.h>
template <typename T> // Using template to make the filter usable for scalar and vector values template <typename T> // Using template to make the filter usable for scalar and vector values
class LowPassFilter { class LowPassFilter {
public: public:

View File

@@ -3,10 +3,6 @@
// MAVLink communication // MAVLink communication
#include <Arduino.h>
#include "config.h"
#include "flix.h"
#if WIFI_ENABLED #if WIFI_ENABLED
#include <MAVLink.h> #include <MAVLink.h>
@@ -16,13 +12,12 @@
#define MAVLINK_RATE_SLOW 1 #define MAVLINK_RATE_SLOW 1
#define MAVLINK_RATE_FAST 10 #define MAVLINK_RATE_FAST 10
extern const int AUTO, STAB;
extern uint16_t channels[16];
extern float controlTime;
bool mavlinkConnected = false; bool mavlinkConnected = false;
String mavlinkPrintBuffer; String mavlinkPrintBuffer;
extern float controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
void processMavlink() { void processMavlink() {
sendMavlink(); sendMavlink();
receiveMavlink(); receiveMavlink();
@@ -212,7 +207,6 @@ void handleMavlink(const void *_msg) {
armed = motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0; armed = motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0;
} }
/* TODO:
if (msg.msgid == MAVLINK_MSG_ID_LOG_REQUEST_DATA) { if (msg.msgid == MAVLINK_MSG_ID_LOG_REQUEST_DATA) {
mavlink_log_request_data_t m; mavlink_log_request_data_t m;
mavlink_msg_log_request_data_decode(&msg, &m); mavlink_msg_log_request_data_decode(&msg, &m);
@@ -226,7 +220,6 @@ void handleMavlink(const void *_msg) {
sendMessage(&msg); sendMessage(&msg);
} }
} }
*/
// Handle commands // Handle commands
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) { if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {

View File

@@ -4,17 +4,24 @@
// Motors output control using MOSFETs // Motors output control using MOSFETs
// In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400) // In case of using ESCs, change PWM_STOP, PWM_MIN and PWM_MAX to appropriate values in μs, decrease PWM_FREQUENCY (to 400)
#include <Arduino.h>
#include "config.h"
#include "flix.h"
#include "util.h" #include "util.h"
float motors[4]; // normalized motor thrusts in range [0..1] #define MOTOR_0_PIN 12 // rear left
#define MOTOR_1_PIN 13 // rear right
#define MOTOR_2_PIN 14 // front right
#define MOTOR_3_PIN 15 // front left
extern const int MOTOR_REAR_LEFT = 0; #define PWM_FREQUENCY 78000
extern const int MOTOR_REAR_RIGHT = 1; #define PWM_RESOLUTION 10
extern const int MOTOR_FRONT_RIGHT = 2; #define PWM_STOP 0
extern const int MOTOR_FRONT_LEFT = 3; #define PWM_MIN 0
#define PWM_MAX 1000000 / PWM_FREQUENCY
// Motors array indexes:
const int MOTOR_REAR_LEFT = 0;
const int MOTOR_REAR_RIGHT = 1;
const int MOTOR_FRONT_RIGHT = 2;
const int MOTOR_FRONT_LEFT = 3;
void setupMotors() { void setupMotors() {
print("Setup Motors\n"); print("Setup Motors\n");

View File

@@ -4,22 +4,11 @@
// Parameters storage in flash memory // Parameters storage in flash memory
#include <Preferences.h> #include <Preferences.h>
#include "flix.h"
#include "pid.h"
#include "lpf.h"
#include "util.h" #include "util.h"
extern float channelZero[16]; extern float channelZero[16];
extern float channelMax[16]; extern float channelMax[16];
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel; extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern float tiltMax;
extern PID rollPID, pitchPID, yawPID;
extern PID rollRatePID, pitchRatePID, yawRatePID;
extern Vector maxRate;
extern Vector imuRotation;
extern Vector accBias, accScale;
extern float accWeight;
extern LowPassFilter<Vector> ratesFilter;
Preferences storage; Preferences storage;

View File

@@ -5,8 +5,6 @@
#pragma once #pragma once
#include "Arduino.h"
#include "flix.h"
#include "lpf.h" #include "lpf.h"
class PID { class PID {

View File

@@ -5,7 +5,6 @@
#pragma once #pragma once
#include <Arduino.h>
#include "vector.h" #include "vector.h"
class Quaternion : public Printable { class Quaternion : public Printable {

View File

@@ -6,16 +6,13 @@
#include <SBUS.h> #include <SBUS.h>
#include "util.h" #include "util.h"
SBUS rc(Serial2); SBUS rc(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
uint16_t channels[16]; // raw rc channels uint16_t channels[16]; // raw rc channels
float controlTime; // time of the last controls update
float channelZero[16]; // calibration zero values float channelZero[16]; // calibration zero values
float channelMax[16]; // calibration max values float channelMax[16]; // calibration max values
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN; //
float controlTime; // time of the last controls update (0 when no RC)
// Channels mapping (using float to store in parameters): // Channels mapping (using float to store in parameters):
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN; float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
@@ -41,11 +38,11 @@ void normalizeRC() {
controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1); controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1);
} }
// Update control values // Update control values
controlRoll = rollChannel >= 0 ? controls[(int)rollChannel] : 0; controlRoll = rollChannel >= 0 ? controls[(int)rollChannel] : NAN;
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : 0; controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN;
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : 0; controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN;
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : 0; controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN;
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN; // mode switch should not have affect if not set controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN;
} }
void calibrateRC() { void calibrateRC() {

View File

@@ -3,11 +3,11 @@
// Fail-safe functions // Fail-safe functions
#include "config.h" #define RC_LOSS_TIMEOUT 1
#include "flix.h" #define DESCEND_TIME 10
extern float controlTime; extern float controlTime;
extern const int AUTO, STAB; extern float controlRoll, controlPitch, controlThrottle, controlYaw;
void failsafe() { void failsafe() {
rcLossFailsafe(); rcLossFailsafe();

View File

@@ -3,11 +3,6 @@
// Time related functions // Time related functions
#include "Arduino.h"
#include "flix.h"
float t = NAN; // current time, s
float dt; // time delta with the previous step, s
float loopRate; // Hz float loopRate; // Hz
void step() { void step() {

View File

@@ -8,24 +8,24 @@
#include <math.h> #include <math.h>
#include <soc/soc.h> #include <soc/soc.h>
#include <soc/rtc_cntl_reg.h> #include <soc/rtc_cntl_reg.h>
#include "flix.h"
const float ONE_G = 9.80665; const float ONE_G = 9.80665;
extern float t;
inline float mapf(float x, float in_min, float in_max, float out_min, float out_max) { float mapf(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; return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
} }
inline bool invalid(float x) { bool invalid(float x) {
return !isfinite(x); return !isfinite(x);
} }
inline bool valid(float x) { bool valid(float x) {
return isfinite(x); return isfinite(x);
} }
// Wrap angle to [-PI, PI) // Wrap angle to [-PI, PI)
inline float wrapAngle(float angle) { float wrapAngle(float angle) {
angle = fmodf(angle, 2 * PI); angle = fmodf(angle, 2 * PI);
if (angle > PI) { if (angle > PI) {
angle -= 2 * PI; angle -= 2 * PI;
@@ -36,12 +36,12 @@ inline float wrapAngle(float angle) {
} }
// Disable reset on low voltage // Disable reset on low voltage
inline void disableBrownOut() { void disableBrownOut() {
REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA); REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA);
} }
// Trim and split string by spaces // Trim and split string by spaces
inline void splitString(String& str, String& token0, String& token1, String& token2) { void splitString(String& str, String& token0, String& token1, String& token2) {
str.trim(); str.trim();
char chars[str.length() + 1]; char chars[str.length() + 1];
str.toCharArray(chars, str.length() + 1); str.toCharArray(chars, str.length() + 1);

View File

@@ -5,8 +5,6 @@
#pragma once #pragma once
#include <Arduino.h>
class Vector : public Printable { class Vector : public Printable {
public: public:
float x, y, z; float x, y, z;
@@ -37,6 +35,7 @@ public:
z = NAN; z = NAN;
} }
float norm() const { float norm() const {
return sqrt(x * x + y * y + z * z); return sqrt(x * x + y * y + z * z);
} }
@@ -125,5 +124,5 @@ public:
} }
}; };
inline Vector operator * (const float a, const Vector& b) { return b * a; } Vector operator * (const float a, const Vector& b) { return b * a; }
inline Vector operator + (const float a, const Vector& b) { return b + a; } Vector operator + (const float a, const Vector& b) { return b + a; }

View File

@@ -3,18 +3,19 @@
// Wi-Fi support // Wi-Fi support
#include "config.h"
#include "flix.h"
#if WIFI_ENABLED #if WIFI_ENABLED
#include <WiFi.h> #include <WiFi.h>
#include <WiFiAP.h> #include <WiFiAP.h>
#include <WiFiUdp.h> #include <WiFiUdp.h>
WiFiUDP udp; #define WIFI_SSID "flix"
#define WIFI_PASSWORD "flixwifi"
#define WIFI_UDP_PORT 14550
#define WIFI_UDP_REMOTE_PORT 14550
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
extern bool mavlinkConnected; WiFiUDP udp;
void setupWiFi() { void setupWiFi() {
print("Setup Wi-Fi\n"); print("Setup Wi-Fi\n");

View File

@@ -10,23 +10,9 @@ list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}")
set(FLIX_SOURCE_DIR ../flix) set(FLIX_SOURCE_DIR ../flix)
include_directories(${FLIX_SOURCE_DIR}) include_directories(${FLIX_SOURCE_DIR})
set(FLIX_SOURCE_DIR ../flix)
include_directories(${FLIX_SOURCE_DIR})
set(FLIX_SOURCES
${FLIX_SOURCE_DIR}/cli.cpp
${FLIX_SOURCE_DIR}/control.cpp
${FLIX_SOURCE_DIR}/estimate.cpp
${FLIX_SOURCE_DIR}/safety.cpp
${FLIX_SOURCE_DIR}/log.cpp
${FLIX_SOURCE_DIR}/mavlink.cpp
${FLIX_SOURCE_DIR}/motors.cpp
${FLIX_SOURCE_DIR}/parameters.cpp
${FLIX_SOURCE_DIR}/rc.cpp
${FLIX_SOURCE_DIR}/time.cpp
)
set(CMAKE_BUILD_TYPE RelWithDebInfo) set(CMAKE_BUILD_TYPE RelWithDebInfo)
add_library(flix SHARED simulator.cpp ${FLIX_SOURCES}) 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 target_compile_options(flix PRIVATE -Wno-address-of-packed-member) # disable unneeded mavlink warnings

View File

@@ -12,15 +12,16 @@
#define WIFI_ENABLED 1 #define WIFI_ENABLED 1
extern float t, dt; float t = NAN;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode; float dt;
extern Vector rates; float motors[4];
extern Quaternion attitude; float controlRoll, controlPitch, controlYaw, controlThrottle = NAN;
extern bool landed; float controlMode = NAN;
extern float motors[4]; Vector acc;
Vector gyro;
Vector gyro, acc, imuRotation; Vector rates;
Vector accBias, gyroBias, accScale(1, 1, 1); Quaternion attitude;
bool landed;
// declarations // declarations
void step(); void step();
@@ -73,3 +74,4 @@ void calibrateAccel() { print("Skip accel calibrating\n"); };
void printIMUCalibration() { print("cal: N/A\n"); }; void printIMUCalibration() { print("cal: N/A\n"); };
void printIMUInfo() {}; void printIMUInfo() {};
void printWiFiInfo() {}; void printWiFiInfo() {};
Vector accBias, gyroBias, accScale(1, 1, 1);

View File

@@ -18,6 +18,18 @@
#include "Arduino.h" #include "Arduino.h"
#include "flix.h" #include "flix.h"
#include "cli.ino"
#include "control.ino"
#include "estimate.ino"
#include "safety.ino"
#include "log.ino"
#include "lpf.h"
#include "mavlink.ino"
#include "motors.ino"
#include "parameters.ino"
#include "rc.ino"
#include "time.ino"
using ignition::math::Vector3d; using ignition::math::Vector3d;
using namespace gazebo; using namespace gazebo;
using namespace std; using namespace std;

View File

@@ -95,7 +95,7 @@ Full list of events:
|`armed`|Armed state update|Armed state (*bool*)| |`armed`|Armed state update|Armed state (*bool*)|
|`mode`|Flight mode update|Flight mode (*str*)| |`mode`|Flight mode update|Flight mode (*str*)|
|`landed`|Landed state update|Landed state (*bool*)| |`landed`|Landed state update|Landed state (*bool*)|
|`print`|The drone prints text to the console|Text| |`print`|The drone sends text to the console|Text|
|`attitude`|Attitude update|Attitude quaternion (*list*)| |`attitude`|Attitude update|Attitude quaternion (*list*)|
|`attitude_euler`|Attitude update|Euler angles (*list*)| |`attitude_euler`|Attitude update|Euler angles (*list*)|
|`rates`|Angular rates update|Angular rates (*list*)| |`rates`|Angular rates update|Angular rates (*list*)|
@@ -112,7 +112,7 @@ Full list of events:
> [!NOTE] > [!NOTE]
> Update events trigger on every new piece of data from the drone, and do not mean the value has changed. > Update events trigger on every new piece of data from the drone, and do not mean the value has changed.
### Basic methods ### Common methods
Get and set firmware parameters using `get_param` and `set_param` methods: Get and set firmware parameters using `get_param` and `set_param` methods: