11 Commits

Author SHA1 Message Date
Oleg Kalachev
24f7b02ed5 Add commands for switching modes
Make mode simple int instead of enum for simplify using in other subsystems
2025-08-11 22:35:38 +03:00
Oleg Kalachev
d5c3b5b5f7 Bring back handling old message for motor outputs in pyflix 2025-07-31 12:35:59 +03:00
Oleg Kalachev
37b9a3a41c Add support form arm/disarm mavlink command 2025-07-31 12:35:41 +03:00
Oleg Kalachev
7f4fc7acea Make rc loss timeout longer 2025-07-31 12:32:43 +03:00
Oleg Kalachev
3f269f57be Fixes 2025-07-31 12:23:26 +03:00
Oleg Kalachev
8e043555c5 Fix 2025-07-30 00:38:55 +03:00
Oleg Kalachev
c39e2ca998 Fixes 2025-07-30 00:38:34 +03:00
Oleg Kalachev
f46842f341 Fixed 2025-07-30 00:38:24 +03:00
Oleg Kalachev
3d72224b32 Print armed state in rc command 2025-07-30 00:38:13 +03:00
Oleg Kalachev
dfceb8a6b2 Implement auto mode for automatic flight
Use arm/disarm gestures
Add arm/disarm commands
Add ratesExtra variable for 
Rename interpretRC to interpretControls
Rename controlRate to controlRates
Remove USER mode
Add invalidate methods for vector and quaternion
Add valid/invalid method for vector and quaternion
Add valid/invalid function
Print armed in rc command
Pass auto mode to heartbeat
Use actuator_control_target for motors
2025-07-29 18:02:09 +03:00
Oleg Kalachev
2066d05a60 Implement set_mode, set_attitude and set_rates in pyflix 2025-07-28 22:36:41 +03:00
35 changed files with 690 additions and 696 deletions

View File

@@ -17,11 +17,11 @@
* Dedicated for education and research. * Dedicated for education and research.
* Made from general-purpose components. * Made from general-purpose components.
* Simple and clean source code in Arduino (<2k lines firmware). * Simple and clean source code in Arduino.
* Control using USB gamepad, remote control or smartphone. * Control using remote control or smartphone.
* Precise simulation with Gazebo.
* Wi-Fi and MAVLink support. * Wi-Fi and MAVLink support.
* Wireless command line interface and analyzing. * Wireless command line interface and analyzing.
* Precise simulation with Gazebo.
* Python library. * Python library.
* Textbook on flight control theory and practice ([in development](https://quadcopter.dev)). * Textbook on flight control theory and practice ([in development](https://quadcopter.dev)).
* *Position control (using external camera) and autonomous flights¹*. * *Position control (using external camera) and autonomous flights¹*.
@@ -38,11 +38,7 @@ Version 0 demo video: https://youtu.be/8GzzIQ3C6DQ.
<a href="https://youtu.be/8GzzIQ3C6DQ"><img width=500 src="https://i3.ytimg.com/vi/8GzzIQ3C6DQ/maxresdefault.jpg"></a> <a href="https://youtu.be/8GzzIQ3C6DQ"><img width=500 src="https://i3.ytimg.com/vi/8GzzIQ3C6DQ/maxresdefault.jpg"></a>
Usage in education (RoboCamp): https://youtu.be/Wd3yaorjTx0. See the [user builds gallery](docs/user.md).
<a href="https://youtu.be/Wd3yaorjTx0"><img width=500 src="https://i3.ytimg.com/vi/Wd3yaorjTx0/sddefault.jpg"></a>
See the [user builds gallery](docs/user.md):
<a href="docs/user.md"><img src="docs/img/user/user.jpg" width=500></a> <a href="docs/user.md"><img src="docs/img/user/user.jpg" width=500></a>
@@ -55,7 +51,7 @@ The simulator is implemented using Gazebo and runs the original Arduino code:
## Articles ## Articles
* [Assembly instructions](docs/assembly.md). * [Assembly instructions](docs/assembly.md).
* [Usage: build, setup and flight](docs/usage.md). * [Building and running the code](docs/build.md).
* [Troubleshooting](docs/troubleshooting.md). * [Troubleshooting](docs/troubleshooting.md).
* [Firmware architecture overview](docs/firmware.md). * [Firmware architecture overview](docs/firmware.md).
* [Python library tutorial](tools/pyflix/README.md). * [Python library tutorial](tools/pyflix/README.md).
@@ -67,8 +63,8 @@ The simulator is implemented using Gazebo and runs the original Arduino code:
|Type|Part|Image|Quantity| |Type|Part|Image|Quantity|
|-|-|:-:|:-:| |-|-|:-:|:-:|
|Microcontroller board|ESP32 Mini|<img src="docs/img/esp32.jpg" width=100>|1| |Microcontroller board|ESP32 Mini|<img src="docs/img/esp32.jpg" width=100>|1|
|IMU (and barometer²) board|GY91, MPU-9265 (or other MPU9250/MPU6500 board)<br>ICM20948V2 (ICM20948)³<br>GY-521 (MPU-6050)³⁻¹|<img src="docs/img/gy-91.jpg" width=90 align=center><br><img src="docs/img/icm-20948.jpg" width=100><br><img src="docs/img/gy-521.jpg" width=100>|1| |IMU (and barometer²) board|GY91, MPU-9265 (or other MPU9250/MPU6500 board)<br>ICM20948³<br>GY-521 (MPU-6050)³⁻¹|<img src="docs/img/gy-91.jpg" width=90 align=center><br><img src="docs/img/icm-20948.jpg" width=100><br><img src="docs/img/gy-521.jpg" width=100>|1|
|<span style="background:yellow">Buck-boost converter</span> (recommended)|To be determined, output 5V or 3.3V, see [user-contributed schematics](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612179508274&cot=14)|<img src="docs/img/buck-boost.jpg" width=100>|1| |<span style="background:yellow">(Recommended) Buck-boost converter</span>|To be determined, output 5V or 3.3V, see [user-contributed schematics](https://miro.com/app/board/uXjVN-dTjoo=/?moveToWidget=3458764612179508274&cot=14)|<img src="docs/img/buck-boost.jpg" width=100>|1|
|Motor|8520 3.7V brushed motor (shaft 0.8mm).<br>Motor with exact 3.7V voltage is needed, not ranged working voltage (3.7V — 6V).|<img src="docs/img/motor.jpeg" width=100>|4| |Motor|8520 3.7V brushed motor (shaft 0.8mm).<br>Motor with exact 3.7V voltage is needed, not ranged working voltage (3.7V — 6V).|<img src="docs/img/motor.jpeg" width=100>|4|
|Propeller|Hubsan 55 mm|<img src="docs/img/prop.jpg" width=100>|4| |Propeller|Hubsan 55 mm|<img src="docs/img/prop.jpg" width=100>|4|
|MOSFET (transistor)|100N03A or [analog](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4| |MOSFET (transistor)|100N03A or [analog](https://t.me/opensourcequadcopter/33)|<img src="docs/img/100n03a.jpg" width=100>|4|
@@ -81,7 +77,7 @@ The simulator is implemented using Gazebo and runs the original Arduino code:
|Frame main part|3D printed⁴:<br>[`flix-frame-1.1.stl`](docs/assets/flix-frame-1.1.stl) [`flix-frame-1.1.step`](docs/assets/flix-frame-1.1.step)<br>Recommended settings: layer 0.2 mm, line 0.4 mm, infill 100%.|<img src="docs/img/frame1.jpg" width=100>|1| |Frame main part|3D printed⁴:<br>[`flix-frame-1.1.stl`](docs/assets/flix-frame-1.1.stl) [`flix-frame-1.1.step`](docs/assets/flix-frame-1.1.step)<br>Recommended settings: layer 0.2 mm, line 0.4 mm, infill 100%.|<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| |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>|2| |Washer for IMU board mounting|3D printed:<br>[`washer-m3.stl`](docs/assets/washer-m3.stl) [`washer-m3.step`](docs/assets/washer-m3.step)|<img src="docs/img/washer-m3.jpg" width=100>|2|
|Controller (recommended)|CC2500 transmitter, like BetaFPV LiteRadio CC2500 (RC receiver/Wi-Fi).<br>Two-sticks gamepad (Wi-Fi only) — see [recommended gamepads](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/joystick.html#supported-joysticks).<br>Other⁵|<img src="docs/img/betafpv.jpg" width=100><img src="docs/img/logitech.jpg" width=80>|1| |*RC transmitter (optional)*|*KINGKONG TINY X8 (warning: lacks USB support) or other⁵*|<img src="docs/img/tx.jpg" width=100>|1|
|*RC receiver (optional)*|*DF500 or other⁵*|<img src="docs/img/rx.jpg" width=100>|1| |*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>|| |Wires|28 AWG recommended|<img src="docs/img/wire-28awg.jpg" width=100>||
|Tape, double-sided tape|||| |Tape, double-sided tape||||
@@ -90,7 +86,7 @@ The simulator is implemented using Gazebo and runs the original Arduino code:
*³ — change `MPU9250` to `ICM20948` in `imu.ino` file if using ICM-20948 board.*<br> *³ — change `MPU9250` to `ICM20948` in `imu.ino` file if using ICM-20948 board.*<br>
*³⁻¹ — MPU-6050 supports I²C interface only (not recommended). To use it change IMU declaration to `MPU6050 IMU(Wire)`.*<br> *³⁻¹ — MPU-6050 supports I²C interface only (not recommended). To use it change IMU declaration to `MPU6050 IMU(Wire)`.*<br>
*⁴ — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*<br> *⁴ — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*<br>
*⁵ — you also may use any transmitter-receiver pair with SBUS interface.* *⁵ — you may use any transmitter-receiver pair with SBUS interface.*
Tools required for assembly: Tools required for assembly:

View File

@@ -1,10 +1,8 @@
# Архитектура прошивки # Архитектура прошивки
Прошивка Flix это обычный скетч Arduino, реализованный в однопоточном стиле. Код инициализации находится в функции `setup()`, а главный цикл — в функции `loop()`. Скетч состоит из нескольких файлов, каждый из которых отвечает за определенную подсистему. <img src="img/dataflow.svg" width=800 alt="Firmware dataflow diagram">
<img src="img/dataflow.svg" width=600 alt="Firmware dataflow diagram"> Главный цикл работает на частоте 1000 Гц. Передача данных между подсистемами происходит через глобальные переменные:
Главный цикл `loop()` работает на частоте 1000 Гц. Передача данных между подсистемами происходит через глобальные переменные:
* `t` *(float)* — текущее время шага, *с*. * `t` *(float)* — текущее время шага, *с*.
* `dt` *(float)* — дельта времени между текущим и предыдущим шагами, *с*. * `dt` *(float)* — дельта времени между текущим и предыдущим шагами, *с*.
@@ -17,34 +15,18 @@
## Исходные файлы ## Исходные файлы
Исходные файлы прошивки находятся в директории `flix`. Основные файлы: Исходные файлы прошивки находятся в директории `flix`. Ключевые файлы:
* [`flix.ino`](https://github.com/okalachev/flix/blob/master/flix/flix.ino) — основной файл Arduino-скетча. Определяет некоторые глобальные переменные и главный цикл. * [`flix.ino`](https://github.com/okalachev/flix/blob/canonical/flix/flix.ino) — основной входной файл, скетч Arduino. Включает определение глобальных переменных и главный цикл.
* [`imu.ino`](https://github.com/okalachev/flix/blob/master/flix/imu.ino) — чтение данных с датчика IMU (гироскоп и акселерометр), калибровка IMU. * [`imu.ino`](https://github.com/okalachev/flix/blob/canonical/flix/imu.ino) — чтение данных с датчика IMU (гироскоп и акселерометр), калибровка IMU.
* [`rc.ino`](https://github.com/okalachev/flix/blob/master/flix/rc.ino) — чтение данных с RC-приемника, калибровка RC. * [`rc.ino`](https://github.com/okalachev/flix/blob/canonical/flix/rc.ino) — чтение данных с RC-приемника, калибровка RC.
* [`estimate.ino`](https://github.com/okalachev/flix/blob/master/flix/estimate.ino) — оценка ориентации дрона, комплементарный фильтр. * [`mavlink.ino`](https://github.com/okalachev/flix/blob/canonical/flix/mavlink.ino) — взаимодействие с QGroundControl через MAVLink.
* [`control.ino`](https://github.com/okalachev/flix/blob/master/flix/control.ino) — подсистема управления, трехмерный двухуровневый каскадный ПИД-регулятор. * [`estimate.ino`](https://github.com/okalachev/flix/blob/canonical/flix/estimate.ino) — оценка ориентации дрона, комплементарный фильтр.
* [`motors.ino`](https://github.com/okalachev/flix/blob/master/flix/motors.ino) — выход PWM на моторы. * [`control.ino`](https://github.com/okalachev/flix/blob/canonical/flix/control.ino) — управление ориентацией и угловыми скоростями дрона, трехмерный двухуровневый каскадный PID-регулятор.
* [`mavlink.ino`](https://github.com/okalachev/flix/blob/master/flix/mavlink.ino) — взаимодействие с QGroundControl или [pyflix](https://github.com/okalachev/flix/tree/master/tools/pyflix) через протокол MAVLink. * [`motors.ino`](https://github.com/okalachev/flix/blob/canonical/flix/motors.ino) — управление выходными сигналами на моторы через ШИМ.
Вспомогательные файлы: Вспомогательные файлы включают:
* [`vector.h`](https://github.com/okalachev/flix/blob/master/flix/vector.h), [`quaternion.h`](https://github.com/okalachev/flix/blob/master/flix/quaternion.h) — библиотеки векторов и кватернионов. * [`vector.h`](https://github.com/okalachev/flix/blob/canonical/flix/vector.h), [`quaternion.h`](https://github.com/okalachev/flix/blob/canonical/flix/quaternion.h) — реализация библиотек векторов и кватернионов проекта.
* [`pid.h`](https://github.com/okalachev/flix/blob/master/flix/pid.h) — ПИД-регулятор. * [`pid.h`](https://github.com/okalachev/flix/blob/canonical/flix/pid.h) — реализация общего ПИД-регулятора.
* [`lpf.h`](https://github.com/okalachev/flix/blob/master/flix/lpf.h) — фильтр нижних частот. * [`lpf.h`](https://github.com/okalachev/flix/blob/canonical/flix/lpf.h) — реализация общего фильтра нижних частот.
### Подсистема управления
Состояние органов управления обрабатывается в функции `interpretControls()` и преобразуется в *команду управления*, которая включает следующее:
* `attitudeTarget` *(Quaternion)* — целевая ориентация дрона.
* `ratesTarget` *(Vector)* — целевые угловые скорости, *рад/с*.
* `ratesExtra` *(Vector)* — дополнительные (feed-forward) угловые скорости, для управления рысканием в режиме STAB, *рад/с*.
* `torqueTarget` *(Vector)* — целевой крутящий момент, диапазон [-1, 1].
* `thrustTarget` *(float)* — целевая общая тяга, диапазон [0, 1].
Команда управления обрабатывается в функциях `controlAttitude()`, `controlRates()`, `controlTorque()`. Если значение одной из переменных установлено в `NAN`, то соответствующая функция пропускается.
<img src="img/control.svg" width=300 alt="Control subsystem diagram">
Состояние *armed* хранится в переменной `armed`, а текущий режим — в переменной `mode`.

View File

@@ -1 +0,0 @@
usage.md

205
docs/build.md Normal file
View File

@@ -0,0 +1,205 @@
# Building and running
To build the firmware or the simulator, you need to clone the repository using git:
```bash
git clone https://github.com/okalachev/flix.git
cd flix
```
## Simulation
### Ubuntu
The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you have a newer version, consider using a virtual machine.
1. Install Arduino CLI:
```bash
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
```
2. Install Gazebo 11:
```bash
curl -sSL http://get.gazebosim.org | sh
```
Set up your Gazebo environment variables:
```bash
echo "source /usr/share/gazebo/setup.sh" >> ~/.bashrc
source ~/.bashrc
```
3. Install SDL2 and other dependencies:
```bash
sudo apt-get update && sudo apt-get install build-essential libsdl2-dev
```
4. Add your user to the `input` group to enable joystick support (you need to re-login after this command):
```bash
sudo usermod -a -G input $USER
```
5. Run the simulation:
```bash
make simulator
```
### macOS
1. Install Homebrew package manager, if you don't have it installed:
```bash
/bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/HEAD/install.sh)"
```
2. Install Arduino CLI, Gazebo 11 and SDL2:
```bash
brew tap osrf/simulation
brew install arduino-cli
brew install gazebo11
brew install sdl2
```
Set up your Gazebo environment variables:
```bash
echo "source /opt/homebrew/share/gazebo/setup.sh" >> ~/.zshrc
source ~/.zshrc
```
3. Run the simulation:
```bash
make simulator
```
### Setup and flight
#### 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. For **iOS**, use [QGroundControl build from TAJISOFT](https://apps.apple.com/ru/app/qgc-from-tajisoft/id1618653051).
2. Connect your smartphone to the same Wi-Fi network as the machine running the simulator.
3. If you're using a virtual machine, make sure that its network is set to the **bridged** mode with Wi-Fi adapter selected.
4. Run the simulation.
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.
4. Run the simulation again.
5. Use the USB remote control to fly the drone!
## Firmware
### Arduino IDE (Windows, Linux, macOS)
1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended).
2. Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).
3. Install ESP32 core, version 3.2.0. See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
* `FlixPeriph`, the latest version.
* `MAVLink`, version 2.0.16.
5. Clone the project using git or [download the source code as a ZIP archive](https://codeload.github.com/okalachev/flix/zip/refs/heads/master).
6. Open the downloaded Arduino sketch `flix/flix.ino` in Arduino IDE.
7. Connect your ESP32 board to the computer and choose correct board type in Arduino IDE (*WEMOS D1 MINI ESP32* for ESP32 Mini) and the port.
8. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
### Command line (Windows, Linux, macOS)
1. [Install Arduino CLI](https://arduino.github.io/arduino-cli/installation/).
On Linux, use:
```bash
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
```
2. Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).
3. Compile the firmware using `make`. Arduino dependencies will be installed automatically:
```bash
make
```
You can flash the firmware to the board using command:
```bash
make upload
```
You can also compile the firmware, upload it and start serial port monitoring using command:
```bash
make upload monitor
```
See other available Make commands in the [Makefile](../Makefile).
> [!TIP]
> You can test the firmware on a bare ESP32 board without connecting IMU and other peripherals. The Wi-Fi network `flix` should appear and all the basic functionality including CLI and QGroundControl connection should work.
### Setup and flight
Before flight you need to calibrate the accelerometer:
1. Open Serial Monitor in Arduino IDE (or use `make monitor` command in the command line).
2. Type `ca` command there and follow the instructions.
#### Control with smartphone
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone.
2. Power the drone using the battery.
3. Connect your smartphone to the appeared `flix` Wi-Fi network (password: `flixwifi`).
4. Open QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
5. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
6. Use the virtual joystick to fly the drone!
#### Control with remote control
Before flight using remote control, you need to calibrate it:
1. Open Serial Monitor in Arduino IDE (or use `make monitor` command in the command line).
2. Type `cr` command there and follow the instructions.
3. Use the remote control to fly the drone!
#### Control with USB remote control
If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it.
1. Install [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html) app on your computer.
2. Connect your USB remote control to the computer.
3. Power up the drone.
4. Connect your computer to the appeared `flix` Wi-Fi network (password: `flixwifi`).
5. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
6. Go the the QGroundControl menu ⇒ *Vehicle Setup**Joystick*. Calibrate you USB remote control there.
7. Use the USB remote control to fly the drone!
#### Adjusting parameters
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl app. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup**Parameters*.
<img src="img/parameters.png" width="400">
#### CLI access
In addition to accessing the drone's command line interface (CLI) using the serial port, you can also access it with QGroundControl using Wi-Fi connection. To do that, go to the QGroundControl menu ⇒ *Vehicle Setup**Analyze Tools**MAVLink Console*.
<img src="img/cli.png" width="400">
> [!NOTE]
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.
### Firmware code structure
See [firmware overview](firmware.md) for more details.

View File

@@ -1,56 +1,39 @@
# Firmware overview # Firmware overview
The firmware is a regular Arduino sketch, and it follows the classic Arduino one-threaded design. The initialization code is in the `setup()` function, and the main loop is in the `loop()` function. The sketch includes several files, each responsible for a specific subsystem. The firmware is a regular Arduino sketch, and follows the classic Arduino one-threaded design. The initialization code is in the `setup()` function, and the main loop is in the `loop()` function. The sketch includes multiple files, each responsible for a specific part of the system.
## Dataflow ## Dataflow
<img src="img/dataflow.svg" width=600 alt="Firmware dataflow diagram"> <img src="img/dataflow.svg" width=800 alt="Firmware dataflow diagram">
The main loop is running at 1000 Hz. All the dataflow goes through global variables (for simplicity): The main loop is running at 1000 Hz. All the dataflow is happening through global variables (for simplicity):
* `t` *(double)* current step time, *s*. * `t` *(double)* current step time, *s*.
* `dt` *(float)* — time delta between the current and previous steps, *s*. * `dt` *(float)* — time delta between the current and previous steps, *s*.
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*. * `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*. * `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*.
* `rates` *(Vector)* — filtered angular rates, *rad/s*. * `rates` *(Vector)* — filtered angular rates, *rad/s*.
* `attitude` *(Quaternion)* — estimated attitude (orientation) of drone. * `attitude` *(Quaternion)* — estimated attitude (orientation) of drone.
* `controlRoll`, `controlPitch`, ... *(float[])* pilot control inputs, range [-1, 1]. * `controlRoll`, `controlPitch`, ... *(float[])* pilot's control inputs, range [-1, 1].
* `motors` *(float[])* motor outputs, range [0, 1]. * `motors` *(float[])* motor outputs, range [0, 1].
## Source files ## Source files
Firmware source files are located in `flix` directory. The core files are: Firmware source files are located in `flix` directory. The key files are:
* [`flix.ino`](../flix/flix.ino) — Arduino sketch main file, entry point.Includes some global variable definitions and the main loop. * [`flix.ino`](../flix/flix.ino) — main entry point, Arduino sketch. Includes global variables definition and the main loop.
* [`imu.ino`](../flix/imu.ino) — reading data from the IMU sensor (gyroscope and accelerometer), IMU calibration. * [`imu.ino`](../flix/imu.ino) — reading data from the IMU sensor (gyroscope and accelerometer), IMU calibration.
* [`rc.ino`](../flix/rc.ino) — reading data from the RC receiver, RC calibration. * [`rc.ino`](../flix/rc.ino) — reading data from the RC receiver, RC calibration.
* [`estimate.ino`](../flix/estimate.ino) — attitude estimation, complementary filter. * [`estimate.ino`](../flix/estimate.ino) — drone's attitude estimation, complementary filter.
* [`control.ino`](../flix/control.ino) — control subsystem, three-dimensional two-level cascade PID controller. * [`control.ino`](../flix/control.ino) — drone's attitude and rates control, three-dimensional two-level cascade PID controller.
* [`motors.ino`](../flix/motors.ino) — PWM motor output control. * [`motors.ino`](../flix/motors.ino) — PWM motor outputs control.
* [`mavlink.ino`](../flix/mavlink.ino) — interaction with QGroundControl or [pyflix](../tools/pyflix) via MAVLink protocol.
Utility files: Utility files include:
* [`vector.h`](../flix/vector.h), [`quaternion.h`](../flix/quaternion.h) — vector and quaternion libraries. * [`vector.h`](../flix/vector.h), [`quaternion.h`](../flix/quaternion.h) — project's vector and quaternion libraries implementation.
* [`pid.h`](../flix/pid.h) — generic PID controller. * [`pid.h`](../flix/pid.h) — generic PID controller implementation.
* [`lpf.h`](../flix/lpf.h) — generic low-pass filter. * [`lpf.h`](../flix/lpf.h) — generic low-pass filter implementation.
### Control subsystem
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.
* `ratesTarget` *(Vector)* — target angular rates, *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].
* `thrustTarget` *(float)* — collective thrust target, range [0, 1].
Control command is processed in `controlAttitude()`, `controlRates()`, `controlTorque()` functions. Each function may be skipped if the corresponding target is set to `NAN`.
<img src="img/control.svg" width=300 alt="Control subsystem diagram">
Armed state is stored in `armed` variable, and current mode is stored in `mode` variable.
## Building ## Building
See build instructions in [usage.md](usage.md). See build instructions in [build.md](build.md).

View File

@@ -1,22 +0,0 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 340.21 211.28">
<defs>
<style>
.a {
fill: #d5d5d5;
}
.b {
fill: #fff;
}
.c {
fill: #636363;
}
</style>
</defs>
<path class="a" d="M340,159.31c-4.74-86-35.9-128.7-35.9-128.7C288.3,9.53,269.17,2.91,251.87.39s-22.31,7.87-22.31,7.87C201.7,4,170.11,4.19,170.11,4.19S138.51,4,110.65,8.26c0,0-5-10.38-22.3-7.87S51.91,9.53,36.14,30.61c0,0-31.16,42.67-35.9,128.7-2.82,51.08,19.68,55.36,38.43,50.4a60.08,60.08,0,0,0,30.55-19.66c7.51-9,19.64-25.32,34-28,17.28-3.26,33.14-4.77,45.09-4.78l21.82,0,21.81,0c12,0,27.82,1.52,45.09,4.78,14.34,2.71,26.47,19,34,28a60.06,60.06,0,0,0,30.56,19.66C320.29,214.67,342.79,210.39,340,159.31Z"/>
<circle class="b" cx="88.54" cy="85.75" r="45.22"/>
<circle class="b" cx="251.67" cy="85.75" r="45.22"/>
<circle class="c" cx="251.67" cy="85.75" r="13.8"/>
<circle class="c" cx="103.8" cy="112.12" r="13.8"/>
</svg>

Before

Width:  |  Height:  |  Size: 971 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 26 KiB

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 140 KiB

View File

@@ -1,123 +0,0 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 464.2 249.05">
<defs>
<style>
.a {
fill: #d5d5d5;
}
.b {
fill: #fff;
}
.c {
fill: #636363;
}
.d {
opacity: 0.7;
}
.e {
fill: none;
stroke: #0076ba;
stroke-linecap: round;
stroke-miterlimit: 10;
stroke-width: 13px;
}
.f {
fill: #0076ba;
}
.g {
font-size: 30px;
font-family: Tahoma;
}
.h {
letter-spacing: 0em;
}
.i {
letter-spacing: -0.01em;
}
.j {
letter-spacing: -0.06em;
}
.k {
letter-spacing: 0em;
}
.l {
letter-spacing: -0.02em;
}
.m {
letter-spacing: 0em;
}
.n {
opacity: 0.6;
}
</style>
</defs>
<path class="a" d="M408.84,197.08c-4.74-86-35.9-128.7-35.9-128.7C357.17,47.3,338,40.68,320.73,38.17S298.43,46,298.43,46C270.57,41.81,239,42,239,42s-31.59-.15-59.45,4.07c0,0-5-10.38-22.31-7.86S120.78,47.3,105,68.38c0,0-31.16,42.68-35.9,128.7-2.82,51.08,19.68,55.36,38.42,50.4a60.06,60.06,0,0,0,30.56-19.66c7.51-9,19.64-25.32,34-28,17.27-3.26,33.14-4.77,45.09-4.78L239,195l21.82,0c11.95,0,27.81,1.52,45.09,4.78,14.34,2.71,26.47,19,34,28a60.08,60.08,0,0,0,30.55,19.66C389.16,252.44,411.66,248.16,408.84,197.08Z"/>
<circle class="b" cx="157.41" cy="123.52" r="45.22"/>
<circle class="b" cx="320.54" cy="123.52" r="45.22"/>
<circle class="c" cx="320.54" cy="123.52" r="13.8"/>
<circle class="c" cx="157.41" cy="149.89" r="13.8"/>
<g class="d">
<g>
<line class="e" x1="157.41" y1="149.89" x2="157.41" y2="49.87"/>
<polygon class="f" points="180.74 56.7 157.41 16.29 134.07 56.7 180.74 56.7"/>
</g>
</g>
<text class="g" transform="translate(38.38 25.91)">Th<tspan class="h" x="34.25" y="0">r</tspan><tspan x="44.91" y="0">o</tspan><tspan class="i" x="61.2" y="0">t</tspan><tspan x="71" y="0">tle</tspan></text>
<g class="d">
<g>
<line class="e" x1="157.41" y1="149.89" x2="82.41" y2="149.89"/>
<polygon class="f" points="89.24 126.56 48.82 149.89 89.24 173.23 89.24 126.56"/>
</g>
</g>
<text class="g" transform="translate(0.18 176.36)"><tspan class="j">Y</tspan><tspan class="h" x="15.37" y="0">a</tspan><tspan x="30.97" y="0">w</tspan></text>
<g class="d">
<g>
<line class="e" x1="320.54" y1="123.52" x2="320.54" y2="50.32"/>
<polygon class="f" points="343.88 57.15 320.54 16.74 297.2 57.15 343.88 57.15"/>
</g>
</g>
<text class="g" transform="translate(336.56 26.36)">P<tspan class="k" x="16.54" y="0">i</tspan><tspan x="23.45" y="0">tch</tspan></text>
<g class="d">
<g>
<line class="e" x1="320.54" y1="123.52" x2="395.54" y2="123.52"/>
<polygon class="f" points="388.71 146.86 429.12 123.52 388.71 100.19 388.71 146.86"/>
</g>
</g>
<text class="g" transform="translate(416.03 160.01)"><tspan class="l">R</tspan><tspan x="18.08" y="0">o</tspan><tspan class="m" x="34.37" y="0">l</tspan><tspan x="41.31" y="0">l</tspan></text>
<g class="d">
<g>
<line class="e" x1="157.41" y1="149.89" x2="213.73" y2="149.89"/>
<polygon class="f" points="206.9 173.23 247.32 149.89 206.9 126.56 206.9 173.23"/>
</g>
</g>
<g class="d">
<g>
<line class="e" x1="320.54" y1="124.52" x2="320.54" y2="197.73"/>
<polygon class="f" points="297.2 190.9 320.54 231.31 343.88 190.9 297.2 190.9"/>
</g>
</g>
<g class="n">
<g>
<line class="e" x1="318.03" y1="123.52" x2="262.32" y2="123.52"/>
<polygon class="f" points="269.14 100.19 228.73 123.52 269.14 146.86 269.14 100.19"/>
</g>
</g>
<g class="d">
<g>
<line class="e" x1="157.41" y1="151.66" x2="157.41" y2="197.73"/>
<polygon class="f" points="134.07 190.9 157.41 231.31 180.74 190.9 134.07 190.9"/>
</g>
</g>
</svg>

Before

Width:  |  Height:  |  Size: 3.9 KiB

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 101 KiB

After

Width:  |  Height:  |  Size: 22 KiB

View File

@@ -1,22 +0,0 @@
<svg xmlns="http://www.w3.org/2000/svg" viewBox="0 0 340.21 211.28">
<defs>
<style>
.a {
fill: #d5d5d5;
}
.b {
fill: #fff;
}
.c {
fill: #636363;
}
</style>
</defs>
<path class="a" d="M340,159.31c-4.74-86-35.9-128.7-35.9-128.7C288.3,9.53,269.17,2.91,251.87.39s-22.31,7.87-22.31,7.87C201.7,4,170.11,4.19,170.11,4.19S138.51,4,110.65,8.26c0,0-5-10.38-22.3-7.87S51.91,9.53,36.14,30.61c0,0-31.16,42.67-35.9,128.7-2.82,51.08,19.68,55.36,38.43,50.4a60.08,60.08,0,0,0,30.55-19.66c7.51-9,19.64-25.32,34-28,17.28-3.26,33.14-4.77,45.09-4.78l21.82,0,21.81,0c12,0,27.82,1.52,45.09,4.78,14.34,2.71,26.47,19,34,28a60.06,60.06,0,0,0,30.56,19.66C320.29,214.67,342.79,210.39,340,159.31Z"/>
<circle class="b" cx="88.54" cy="85.75" r="45.22"/>
<circle class="b" cx="251.67" cy="85.75" r="45.22"/>
<circle class="c" cx="251.67" cy="85.75" r="13.8"/>
<circle class="c" cx="73.28" cy="112.12" r="13.8"/>
</svg>

Before

Width:  |  Height:  |  Size: 971 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 26 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 24 KiB

View File

Before

Width:  |  Height:  |  Size: 36 KiB

After

Width:  |  Height:  |  Size: 36 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 148 KiB

View File

@@ -4,9 +4,8 @@
Do the following: Do the following:
* **Check ESP32 core is installed**. Check if the version matches the one used in the [tutorial](usage.md#firmware). * **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. * **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*.
## The drone doesn't fly ## The drone doesn't fly

View File

@@ -1,249 +0,0 @@
# Usage: build, setup and flight
To use Flix, you need to build the firmware and upload it to the ESP32 board. For simulation, you need to build and run the simulator.
For the start, clone the repository using git:
```bash
git clone https://github.com/okalachev/flix.git
cd flix
```
## Simulation
### Ubuntu
The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you have a newer version, consider using a virtual machine.
1. Install Arduino CLI:
```bash
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
```
2. Install Gazebo 11:
```bash
curl -sSL http://get.gazebosim.org | sh
```
Set up your Gazebo environment variables:
```bash
echo "source /usr/share/gazebo/setup.sh" >> ~/.bashrc
source ~/.bashrc
```
3. Install SDL2 and other dependencies:
```bash
sudo apt-get update && sudo apt-get install build-essential libsdl2-dev
```
4. Add your user to the `input` group to enable joystick support (you need to re-login after this command):
```bash
sudo usermod -a -G input $USER
```
5. Run the simulation:
```bash
make simulator
```
### macOS
1. Install Homebrew package manager, if you don't have it installed:
```bash
/bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/HEAD/install.sh)"
```
2. Install Arduino CLI, Gazebo 11 and SDL2:
```bash
brew tap osrf/simulation
brew install arduino-cli
brew install gazebo11
brew install sdl2
```
Set up your Gazebo environment variables:
```bash
echo "source /opt/homebrew/share/gazebo/setup.sh" >> ~/.zshrc
source ~/.zshrc
```
3. Run the simulation:
```bash
make simulator
```
### Setup
#### 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. For **iOS**, use [QGroundControl build from TAJISOFT](https://apps.apple.com/ru/app/qgc-from-tajisoft/id1618653051).
2. Connect your smartphone to the same Wi-Fi network as the machine running the simulator.
3. If you're using a virtual machine, make sure that its network is set to the **bridged** mode with Wi-Fi adapter selected.
4. Run the simulation.
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.
4. Run the simulation again.
5. Use the USB remote control to fly the drone!
## Firmware
### Arduino IDE (Windows, Linux, macOS)
1. Install [Arduino IDE](https://www.arduino.cc/en/software) (version 2 is recommended).
2. Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).
3. Install ESP32 core, version 3.2.0. See the [official Espressif's instructions](https://docs.espressif.com/projects/arduino-esp32/en/latest/installing.html#installing-using-arduino-ide) on installing ESP32 Core in Arduino IDE.
4. Install the following libraries using [Library Manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library):
* `FlixPeriph`, the latest version.
* `MAVLink`, version 2.0.16.
5. Clone the project using git or [download the source code as a ZIP archive](https://codeload.github.com/okalachev/flix/zip/refs/heads/master).
6. Open the downloaded Arduino sketch `flix/flix.ino` in Arduino IDE.
7. Connect your ESP32 board to the computer and choose correct board type in Arduino IDE (*WEMOS D1 MINI ESP32* for ESP32 Mini) and the port.
8. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
### Command line (Windows, Linux, macOS)
1. [Install Arduino CLI](https://arduino.github.io/arduino-cli/installation/).
On Linux, use:
```bash
curl -fsSL https://raw.githubusercontent.com/arduino/arduino-cli/master/install.sh | BINDIR=~/.local/bin sh
```
2. Windows users might need to install [USB to UART bridge driver from Silicon Labs](https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers).
3. Compile the firmware using `make`. Arduino dependencies will be installed automatically:
```bash
make
```
You can flash the firmware to the board using command:
```bash
make upload
```
You can also compile the firmware, upload it and start serial port monitoring using command:
```bash
make upload monitor
```
See other available Make commands in the [Makefile](../Makefile).
> [!TIP]
> You can test the firmware on a bare ESP32 board without connecting IMU and other peripherals. The Wi-Fi network `flix` should appear and all the basic functionality including CLI and QGroundControl connection should work.
### Setup
Before flight you need to calibrate the accelerometer:
1. Open Serial Monitor in Arduino IDE (or use `make monitor` command in the command line).
2. Type `ca` command there and follow the instructions.
#### Control with smartphone
1. Install [QGroundControl mobile app](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#android) on your smartphone.
2. Power the drone using the battery.
3. Connect your smartphone to the appeared `flix` Wi-Fi network (password: `flixwifi`).
4. Open QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
5. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
6. Use the virtual joystick to fly the drone!
> [!TIP]
> Decrease `TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
#### Control with remote control
Before flight using remote control, you need to calibrate it:
1. Open Serial Monitor in Arduino IDE (or use `make monitor` command in the command line).
2. Type `cr` command there and follow the instructions.
3. Use the remote control to fly the drone!
#### Control with USB remote control (Wi-Fi)
If your drone doesn't have RC receiver installed, you can use USB remote control and QGroundControl app to fly it.
1. Install [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html) app on your computer.
2. Connect your USB remote control to the computer.
3. Power up the drone.
4. Connect your computer to the appeared `flix` Wi-Fi network (password: `flixwifi`).
5. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
6. Go the the QGroundControl menu ⇒ *Vehicle Setup**Joystick*. Calibrate you USB remote control there.
7. Use the USB remote control to fly the drone!
> [!NOTE]
> If something goes wrong, go to the [Troubleshooting](troubleshooting.md) article.
## Flight
For both virtual sticks and a physical joystick, the default control scheme is left stick for throttle and yaw and right stick for pitch and roll:
<img src="img/controls.svg" width="300">
### Arming and disarming
To start the motors, you should **arm** the drone. To do that, move the left stick to the bottom right corner:
<img src="img/arming.svg" width="150">
After that, the motors **will start spinning** at low speed, indicating that the drone is armed and ready to fly.
When finished flying, **disarm** the drone, moving the left stick to the bottom left corner:
<img src="img/disarming.svg" width="150">
### Flight modes
Flight mode is changed using mode switch on the remote control or using the command line.
#### STAB
The default mode is *STAB*. In this mode, the drone stabilizes its attitude (orientation). The left stick controls throttle and yaw rate, the right stick controls pitch and roll angles.
> [!IMPORTANT]
> The drone doesn't stabilize its position, so slight drift is possible. The pilot should compensate it manually.
#### ACRO
In this mode, the pilot controls the angular rates. This control method is difficult to fly and mostly used in FPV racing.
#### MANUAL
Manual mode disables all the stabilization, and the pilot inputs are passed directly to the motors. This mode is intended for testing and demonstration purposes only, and basically the drone **cannot fly in this mode**.
#### AUTO
In this mode, the pilot inputs are ignored (except the mode switch, if configured). The drone can be controlled using [pyflix](../tools/pyflix/) Python library, or by modifying the firmware to implement the needed autonomous behavior.
If the pilot moves the control sticks, the drone will switch back to *STAB* mode.
## Adjusting parameters
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl app. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup**Parameters*.
<img src="img/parameters.png" width="400">
## CLI access
In addition to accessing the drone's command line interface (CLI) using the serial port, you can also access it with QGroundControl using Wi-Fi connection. To do that, go to the QGroundControl menu ⇒ *Vehicle Setup**Analyze Tools**MAVLink Console*.
<img src="img/cli.png" width="400">

View File

@@ -4,25 +4,6 @@ This page contains user-built drones based on the Flix project. Publish your pro
--- ---
## RoboCamp
Author: RoboCamp participants.<br>
Description: 3D-printed and wooden frames, ESP32 Mini, DC-DC buck-boost converters. BetaFPV LiteRadio 3 to control the drones via Wi-Fi connection.<br>
Features: altitude hold, obstacle avoidance, autonomous flight elements.<br>
Some of the designed model files: https://drive.google.com/drive/folders/18YHWGquKeIevzrMH4-OUT-zKXMETTEUu?usp=share_link.
RoboCamp took place in July 2025, Saint Petersburg, where 9 participants designed and built their own drones using the Flix project, and then modified the firmware to complete specific flight tasks.
See the detailed video about the event:
<a href="https://youtu.be/Wd3yaorjTx0"><img width=500 src="https://img.youtube.com/vi/Wd3yaorjTx0/sddefault.jpg"></a>
Built drones:
<img src="img/user/robocamp/1.jpg" width=500>
---
Author: chkroko.<br> Author: chkroko.<br>
Description: the first Flix drone built with **brushless motors** (DShot interface).<br> Description: the first Flix drone built with **brushless motors** (DShot interface).<br>
Features: SpeedyBee BLS 35A Mini V2 ESC, ESP32-S3 board, EMAX ECO 2 2207 1700kv motors, ICM20948V2 IMU, INA226 power monitor and Bluetooth gamepad for control.<br> Features: SpeedyBee BLS 35A Mini V2 ESC, ESP32-S3 board, EMAX ECO 2 2207 1700kv motors, ICM20948V2 IMU, INA226 power monitor and Bluetooth gamepad for control.<br>

View File

@@ -12,7 +12,7 @@ extern const int ACRO, STAB, AUTO;
extern float loopRate, dt; extern float loopRate, dt;
extern double t; extern double t;
extern uint16_t channels[16]; extern uint16_t channels[16];
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode; extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlArmed, controlMode;
extern int mode; extern int mode;
extern bool armed; extern bool armed;
@@ -34,9 +34,9 @@ const char* motd =
"ps - show pitch/roll/yaw\n" "ps - show pitch/roll/yaw\n"
"psq - show attitude quaternion\n" "psq - show attitude quaternion\n"
"imu - show IMU data\n" "imu - show IMU data\n"
"arm - arm the drone\n" "arm - arm the drone (when no armed switch)\n"
"disarm - disarm the drone\n" "disarm - disarm the drone (when no armed switch)\n"
"stab/acro/auto - set mode\n" "stab/acro/auto - set mode (when no mode switch)\n"
"rc - show RC data\n" "rc - show RC data\n"
"mot - show motor output\n" "mot - show motor output\n"
"log - dump in-RAM log\n" "log - dump in-RAM log\n"
@@ -107,10 +107,13 @@ void doCommand(String str, bool echo = false) {
Vector a = attitude.toEuler(); Vector a = attitude.toEuler();
print("roll: %f pitch: %f yaw: %f\n", degrees(a.x), degrees(a.y), degrees(a.z)); print("roll: %f pitch: %f yaw: %f\n", degrees(a.x), degrees(a.y), degrees(a.z));
} else if (command == "psq") { } else if (command == "psq") {
print("qw: %f qx: %f qy: %f qz: %f\n", attitude.w, attitude.x, attitude.y, attitude.z); print("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
} else if (command == "imu") { } else if (command == "imu") {
printIMUInfo(); printIMUInfo();
print("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
print("acc: %f %f %f\n", acc.x, acc.y, acc.z);
printIMUCalibration(); printIMUCalibration();
print("rate: %.0f\n", loopRate);
print("landed: %d\n", landed); print("landed: %d\n", landed);
} else if (command == "arm") { } else if (command == "arm") {
armed = true; armed = true;
@@ -127,8 +130,8 @@ void doCommand(String str, bool echo = false) {
for (int i = 0; i < 16; i++) { for (int i = 0; i < 16; i++) {
print("%u ", channels[i]); print("%u ", channels[i]);
} }
print("\nroll: %g pitch: %g yaw: %g throttle: %g mode: %g\n", print("\nroll: %g pitch: %g yaw: %g throttle: %g armed: %g mode: %g\n",
controlRoll, controlPitch, controlYaw, controlThrottle, controlMode); controlRoll, controlPitch, controlYaw, controlThrottle, controlArmed, controlMode);
print("mode: %s\n", getModeName()); print("mode: %s\n", getModeName());
print("armed: %d\n", armed); print("armed: %d\n", armed);
} else if (command == "mot") { } else if (command == "mot") {

View File

@@ -9,7 +9,6 @@
#include "lpf.h" #include "lpf.h"
#include "util.h" #include "util.h"
#define ARMED_THRUST 0.1 // thrust to indicate armed state
#define PITCHRATE_P 0.05 #define PITCHRATE_P 0.05
#define PITCHRATE_I 0.2 #define PITCHRATE_I 0.2
#define PITCHRATE_D 0.001 #define PITCHRATE_D 0.001
@@ -55,7 +54,7 @@ Vector torqueTarget;
float thrustTarget; 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, controlArmed, controlMode;
void control() { void control() {
interpretControls(); interpretControls();
@@ -69,12 +68,13 @@ void interpretControls() {
// NOTE: put ACRO or MANUAL modes there if you want to use them // NOTE: put ACRO or MANUAL modes there if you want to use them
if (controlMode < 0.25) mode = STAB; if (controlMode < 0.25) mode = STAB;
if (controlMode < 0.75) mode = STAB; if (controlMode < 0.75) mode = STAB;
if (controlMode > 0.75) mode = STAB; if (controlMode > 0.75) mode = AUTO;
if (controlArmed < 0.5) armed = false;
if (mode == AUTO) return; // pilot is not effective in AUTO mode if (mode == AUTO) return; // pilot is not effective in AUTO mode
if (controlThrottle < 0.05 && controlYaw > 0.95) armed = true; // arm gesture if (landed && controlThrottle == 0 && controlYaw > 0.95) armed = true; // arm gesture
if (controlThrottle < 0.05 && controlYaw < -0.95) armed = false; // disarm gesture if (landed && controlThrottle == 0 && controlYaw < -0.95) armed = false; // disarm gesture
thrustTarget = controlThrottle; thrustTarget = controlThrottle;
@@ -86,15 +86,15 @@ void interpretControls() {
} }
if (mode == ACRO) { if (mode == ACRO) {
attitudeTarget.invalidate(); // skip attitude control attitudeTarget.invalidate();
ratesTarget.x = controlRoll * maxRate.x; ratesTarget.x = controlRoll * maxRate.x;
ratesTarget.y = controlPitch * maxRate.y; ratesTarget.y = controlPitch * maxRate.y;
ratesTarget.z = -controlYaw * maxRate.z; // positive yaw stick means clockwise rotation in FLU ratesTarget.z = -controlYaw * maxRate.z; // positive yaw stick means clockwise rotation in FLU
} }
if (mode == MANUAL) { // passthrough mode if (mode == MANUAL) { // passthrough mode
attitudeTarget.invalidate(); // skip attitude control attitudeTarget.invalidate();
ratesTarget.invalidate(); // skip rate control ratesTarget.invalidate();
torqueTarget = Vector(controlRoll, controlPitch, -controlYaw) * 0.01; torqueTarget = Vector(controlRoll, controlPitch, -controlYaw) * 0.01;
} }
} }
@@ -120,7 +120,6 @@ void controlAttitude() {
ratesTarget.z = yawPID.update(yawError, dt) + ratesExtra.z; ratesTarget.z = yawPID.update(yawError, dt) + ratesExtra.z;
} }
void controlRates() { void controlRates() {
if (!armed || ratesTarget.invalid()) { // skip rates control if (!armed || ratesTarget.invalid()) { // skip rates control
rollRatePID.reset(); rollRatePID.reset();
@@ -140,17 +139,8 @@ void controlRates() {
void controlTorque() { void controlTorque() {
if (!torqueTarget.valid()) return; // skip torque control if (!torqueTarget.valid()) return; // skip torque control
if (!armed) { if (!armed || thrustTarget < 0.05) {
memset(motors, 0, sizeof(motors)); // stop motors if disarmed memset(motors, 0, sizeof(motors)); // stop motors if no thrust
return;
}
if (thrustTarget < 0.05) {
// minimal thrust to indicate armed state
motors[0] = ARMED_THRUST;
motors[1] = ARMED_THRUST;
motors[2] = ARMED_THRUST;
motors[3] = ARMED_THRUST;
return; return;
} }

View File

@@ -11,6 +11,8 @@
#define WEIGHT_ACC 0.003 #define WEIGHT_ACC 0.003
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz #define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
void estimate() { void estimate() {
applyGyro(); applyGyro();
applyAcc(); applyAcc();
@@ -18,7 +20,6 @@ void estimate() {
void applyGyro() { void applyGyro() {
// filter gyro to get angular rates // filter gyro to get angular rates
static LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
rates = ratesFilter.update(gyro); rates = ratesFilter.update(gyro);
// apply rates to attitude // apply rates to attitude

View File

@@ -3,6 +3,8 @@
// Fail-safe functions // Fail-safe functions
#include "util.h"
#define RC_LOSS_TIMEOUT 0.5 #define RC_LOSS_TIMEOUT 0.5
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero #define DESCEND_TIME 3.0 // time to descend from full throttle to zero
@@ -23,28 +25,26 @@ void rcLossFailsafe() {
} }
} }
// Smooth descend on RC lost
void descend() {
mode = STAB;
controlRoll = 0;
controlPitch = 0;
controlYaw = 0;
controlThrottle -= dt / DESCEND_TIME;
if (controlThrottle < 0) {
armed = false;
controlThrottle = 0;
}
}
// Allow pilot to interrupt automatic flight // Allow pilot to interrupt automatic flight
void autoFailsafe() { void autoFailsafe() {
static float roll, pitch, yaw, throttle; static float roll, pitch, yaw, throttle;
if (roll != controlRoll || pitch != controlPitch || yaw != controlYaw || abs(throttle - controlThrottle) > 0.05) { if (roll != controlRoll || pitch != controlPitch || yaw != controlYaw || abs(throttle - controlThrottle) > 0.05) {
// controls changed if (mode == AUTO && invalid(controlMode)) {
if (mode == AUTO) mode = STAB; // regain control by the pilot mode = STAB; // regain control to the pilot
}
} }
roll = controlRoll; roll = controlRoll;
pitch = controlPitch; pitch = controlPitch;
yaw = controlYaw; yaw = controlYaw;
throttle = controlThrottle; throttle = controlThrottle;
} }
// Smooth descend on RC lost
void descend() {
mode = AUTO;
thrustTarget -= dt / DESCEND_TIME;
if (thrustTarget < 0) thrustTarget = 0;
if (thrustTarget == 0) armed = false;
}

View File

@@ -13,7 +13,7 @@
double t = NAN; // current step time, s double t = NAN; // current step time, s
float dt; // time delta from previous step, s float dt; // time delta from previous step, s
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1] float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN; float controlArmed = NAN, controlMode = NAN;
Vector gyro; // gyroscope data Vector gyro; // gyroscope data
Vector acc; // accelerometer data, m/s/s Vector acc; // accelerometer data, m/s/s
Vector rates; // filtered angular rates, rad/s Vector rates; // filtered angular rates, rad/s

View File

@@ -122,12 +122,4 @@ void printIMUInfo() {
IMU.status() ? print("status: ERROR %d\n", IMU.status()) : print("status: OK\n"); IMU.status() ? print("status: ERROR %d\n", IMU.status()) : print("status: OK\n");
print("model: %s\n", IMU.getModel()); print("model: %s\n", IMU.getModel());
print("who am I: 0x%02X\n", IMU.whoAmI()); print("who am I: 0x%02X\n", IMU.whoAmI());
print("rate: %.0f\n", loopRate);
print("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
print("acc: %f %f %f\n", acc.x, acc.y, acc.z);
Vector rawGyro, rawAcc;
IMU.getGyro(rawGyro.x, rawGyro.y, rawGyro.z);
IMU.getAccel(rawAcc.x, rawAcc.y, rawAcc.z);
print("raw gyro: %f %f %f\n", rawGyro.x, rawGyro.y, rawGyro.z);
print("raw acc: %f %f %f\n", rawAcc.x, rawAcc.y, rawAcc.z);
} }

View File

@@ -12,10 +12,11 @@
#define PERIOD_FAST 0.1 #define PERIOD_FAST 0.1
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f #define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
float mavlinkControlScale = 0.7;
String mavlinkPrintBuffer; String mavlinkPrintBuffer;
extern double controlTime; extern double controlTime;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode; extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlArmed, controlMode;
void processMavlink() { void processMavlink() {
sendMavlink(); sendMavlink();
@@ -35,8 +36,8 @@ void sendMavlink() {
lastSlow = t; lastSlow = t;
mavlink_msg_heartbeat_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC, mavlink_msg_heartbeat_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
(armed ? MAV_MODE_FLAG_SAFETY_ARMED : 0) | (armed * MAV_MODE_FLAG_SAFETY_ARMED) |
((mode == STAB) ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0) | (mode == STAB) * MAV_MODE_FLAG_STABILIZE_ENABLED |
((mode == AUTO) ? MAV_MODE_FLAG_AUTO_ENABLED : MAV_MODE_FLAG_MANUAL_INPUT_ENABLED), ((mode == AUTO) ? MAV_MODE_FLAG_AUTO_ENABLED : MAV_MODE_FLAG_MANUAL_INPUT_ENABLED),
mode, MAV_STATE_STANDBY); mode, MAV_STATE_STANDBY);
sendMessage(&msg); sendMessage(&msg);
@@ -100,10 +101,11 @@ void handleMavlink(const void *_msg) {
if (m.target && m.target != SYSTEM_ID) return; // 0 is broadcast if (m.target && m.target != SYSTEM_ID) return; // 0 is broadcast
controlThrottle = m.z / 1000.0f; controlThrottle = m.z / 1000.0f;
controlPitch = m.x / 1000.0f; controlPitch = m.x / 1000.0f * mavlinkControlScale;
controlRoll = m.y / 1000.0f; controlRoll = m.y / 1000.0f * mavlinkControlScale;
controlYaw = m.r / 1000.0f; controlYaw = m.r / 1000.0f * mavlinkControlScale;
controlMode = NAN; controlMode = NAN; // keep mode
controlArmed = NAN;
controlTime = t; controlTime = t;
if (abs(controlYaw) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controlYaw = 0; if (abs(controlYaw) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controlYaw = 0;
@@ -193,6 +195,7 @@ void handleMavlink(const void *_msg) {
ratesExtra = Vector(0, 0, 0); ratesExtra = Vector(0, 0, 0);
if (m.type_mask & ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE) attitudeTarget.invalidate(); if (m.type_mask & ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE) attitudeTarget.invalidate();
armed = m.thrust > 0; armed = m.thrust > 0;
} }
@@ -203,11 +206,7 @@ void handleMavlink(const void *_msg) {
mavlink_msg_set_actuator_control_target_decode(&msg, &m); mavlink_msg_set_actuator_control_target_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return; if (m.target_system && m.target_system != SYSTEM_ID) return;
attitudeTarget.invalidate();
ratesTarget.invalidate();
torqueTarget.invalidate();
memcpy(motors, m.controls, sizeof(motors)); // copy motor thrusts memcpy(motors, m.controls, sizeof(motors)); // copy motor thrusts
armed = motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0;
} }
// Handle commands // Handle commands
@@ -215,32 +214,29 @@ void handleMavlink(const void *_msg) {
mavlink_command_long_t m; mavlink_command_long_t m;
mavlink_msg_command_long_decode(&msg, &m); mavlink_msg_command_long_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return; if (m.target_system && m.target_system != SYSTEM_ID) return;
mavlink_message_t ack;
mavlink_message_t response; mavlink_message_t response;
bool accepted = false;
if (m.command == MAV_CMD_REQUEST_MESSAGE && m.param1 == MAVLINK_MSG_ID_AUTOPILOT_VERSION) { if (m.command == MAV_CMD_REQUEST_MESSAGE && m.param1 == MAVLINK_MSG_ID_AUTOPILOT_VERSION) {
accepted = true; mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
sendMessage(&ack);
mavlink_msg_autopilot_version_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &response, mavlink_msg_autopilot_version_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &response,
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MAVLINK2, 1, 0, 1, 1, 0, 0, 0, 0, 0, 0, 0); MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MAVLINK2, 1, 0, 1, 1, 0, 0, 0, 0, 0, 0, 0);
sendMessage(&response); sendMessage(&response);
} }
if (m.command == MAV_CMD_COMPONENT_ARM_DISARM) {
if (m.param1 && controlThrottle > 0.05) return; // don't arm if throttle is not low
accepted = true;
armed = m.param1 == 1;
}
if (m.command == MAV_CMD_DO_SET_MODE) { if (m.command == MAV_CMD_DO_SET_MODE) {
if (!(m.param2 >= 0 && m.param2 <= AUTO)) return; // incorrect mode if (!(m.param2 >= 0 && m.param2 <= AUTO)) return; // incorrect mode
accepted = true;
mode = m.param2; mode = m.param2;
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
sendMessage(&ack);
} }
// send command ack if (m.command == MAV_CMD_COMPONENT_ARM_DISARM) {
mavlink_message_t ack; armed = m.param1 == 1;
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_UNSUPPORTED, UINT8_MAX, 0, msg.sysid, msg.compid); mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
sendMessage(&ack); sendMessage(&ack);
}
} }
} }

View File

@@ -70,7 +70,12 @@ Parameter parameters[] = {
{"RC_PITCH", &pitchChannel}, {"RC_PITCH", &pitchChannel},
{"RC_THROTTLE", &throttleChannel}, {"RC_THROTTLE", &throttleChannel},
{"RC_YAW", &yawChannel}, {"RC_YAW", &yawChannel},
{"RC_ARMED", &armedChannel},
{"RC_MODE", &modeChannel}, {"RC_MODE", &modeChannel},
#if WIFI_ENABLED
// MAVLink
{"MAV_CTRL_SCALE", &mavlinkControlScale},
#endif
}; };
void setupParameters() { void setupParameters() {

View File

@@ -79,7 +79,6 @@ public:
z = NAN; z = NAN;
} }
float norm() const { float norm() const {
return sqrt(w * w + x * x + y * y + z * z); return sqrt(w * w + x * x + y * y + z * z);
} }
@@ -132,31 +131,29 @@ public:
return euler; return euler;
} }
float getRoll() const {
return toEuler().x;
}
float getPitch() const {
return toEuler().y;
}
float getYaw() const { float getYaw() const {
return toEuler().z; // https://github.com/ros/geometry2/blob/589caf083cae9d8fae7effdb910454b4681b9ec1/tf2/include/tf2/impl/utils.h#L122
} float yaw;
float sqx = x * x;
void setRoll(float roll) { float sqy = y * y;
Vector euler = toEuler(); float sqz = z * z;
*this = Quaternion::fromEuler(Vector(roll, euler.y, euler.z)); float sqw = w * w;
} double sarg = -2 * (x * z - w * y) / (sqx + sqy + sqz + sqw);
if (sarg <= -0.99999) {
void setPitch(float pitch) { yaw = -2 * atan2(y, x);
Vector euler = toEuler(); } else if (sarg >= 0.99999) {
*this = Quaternion::fromEuler(Vector(euler.x, pitch, euler.z)); yaw = 2 * atan2(y, x);
} else {
yaw = atan2(2 * (x * y + w * z), sqw + sqx - sqy - sqz);
}
return yaw;
} }
void setYaw(float yaw) { void setYaw(float yaw) {
// TODO: optimize?
Vector euler = toEuler(); Vector euler = toEuler();
*this = Quaternion::fromEuler(Vector(euler.x, euler.y, yaw)); euler.z = yaw;
(*this) = Quaternion::fromEuler(euler);
} }
Quaternion operator * (const Quaternion& q) const { Quaternion operator * (const Quaternion& q) const {

View File

@@ -14,7 +14,7 @@ float channelZero[16]; // calibration zero values
float channelMax[16]; // calibration max values float channelMax[16]; // calibration max values
// 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, armedChannel = NAN, modeChannel = NAN;
void setupRC() { void setupRC() {
print("Setup RC\n"); print("Setup RC\n");
@@ -42,6 +42,7 @@ void normalizeRC() {
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN; controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : NAN;
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN; controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : NAN;
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN; controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : NAN;
controlArmed = armedChannel >= 0 ? controls[(int)armedChannel] : NAN;
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN; controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN;
} }
@@ -49,15 +50,16 @@ void calibrateRC() {
uint16_t zero[16]; uint16_t zero[16];
uint16_t center[16]; uint16_t center[16];
uint16_t max[16]; uint16_t max[16];
print("1/8 Calibrating RC: put all switches to default positions [3 sec]\n"); print("1/9 Calibrating RC: put all switches to default positions [3 sec]\n");
pause(3); pause(3);
calibrateRCChannel(NULL, zero, zero, "2/8 Move sticks [3 sec]\n... ...\n... .o.\n.o. ...\n"); calibrateRCChannel(NULL, zero, zero, "2/9 Move sticks [3 sec]\n... ...\n... .o.\n.o. ...\n");
calibrateRCChannel(NULL, center, center, "3/8 Move sticks [3 sec]\n... ...\n.o. .o.\n... ...\n"); calibrateRCChannel(NULL, center, center, "3/9 Move sticks [3 sec]\n... ...\n.o. .o.\n... ...\n");
calibrateRCChannel(&throttleChannel, zero, max, "4/8 Move sticks [3 sec]\n.o. ...\n... .o.\n... ...\n"); calibrateRCChannel(&throttleChannel, zero, max, "4/9 Move sticks [3 sec]\n.o. ...\n... .o.\n... ...\n");
calibrateRCChannel(&yawChannel, center, max, "5/8 Move sticks [3 sec]\n... ...\n..o .o.\n... ...\n"); calibrateRCChannel(&yawChannel, center, max, "5/9 Move sticks [3 sec]\n... ...\n..o .o.\n... ...\n");
calibrateRCChannel(&pitchChannel, zero, max, "6/8 Move sticks [3 sec]\n... .o.\n... ...\n.o. ...\n"); calibrateRCChannel(&pitchChannel, zero, max, "6/9 Move sticks [3 sec]\n... .o.\n... ...\n.o. ...\n");
calibrateRCChannel(&rollChannel, zero, max, "7/8 Move sticks [3 sec]\n... ...\n... ..o\n.o. ...\n"); calibrateRCChannel(&rollChannel, zero, max, "7/9 Move sticks [3 sec]\n... ...\n... ..o\n.o. ...\n");
calibrateRCChannel(&modeChannel, zero, max, "8/8 Put mode switch to max [3 sec]\n"); calibrateRCChannel(&armedChannel, zero, max, "8/9 Switch to armed [3 sec]\n");
calibrateRCChannel(&modeChannel, zero, max, "9/9 Disarm and switch mode to max [3 sec]\n");
printRCCalibration(); printRCCalibration();
} }
@@ -92,5 +94,6 @@ void printRCCalibration() {
print("Pitch %-7g%-7g%-7g\n", pitchChannel, pitchChannel >= 0 ? channelZero[(int)pitchChannel] : NAN, pitchChannel >= 0 ? channelMax[(int)pitchChannel] : NAN); print("Pitch %-7g%-7g%-7g\n", pitchChannel, pitchChannel >= 0 ? channelZero[(int)pitchChannel] : NAN, pitchChannel >= 0 ? channelMax[(int)pitchChannel] : NAN);
print("Yaw %-7g%-7g%-7g\n", yawChannel, yawChannel >= 0 ? channelZero[(int)yawChannel] : NAN, yawChannel >= 0 ? channelMax[(int)yawChannel] : NAN); print("Yaw %-7g%-7g%-7g\n", yawChannel, yawChannel >= 0 ? channelZero[(int)yawChannel] : NAN, yawChannel >= 0 ? channelMax[(int)yawChannel] : NAN);
print("Throttle %-7g%-7g%-7g\n", throttleChannel, throttleChannel >= 0 ? channelZero[(int)throttleChannel] : NAN, throttleChannel >= 0 ? channelMax[(int)throttleChannel] : NAN); print("Throttle %-7g%-7g%-7g\n", throttleChannel, throttleChannel >= 0 ? channelZero[(int)throttleChannel] : NAN, throttleChannel >= 0 ? channelMax[(int)throttleChannel] : NAN);
print("Armed %-7g%-7g%-7g\n", armedChannel, armedChannel >= 0 ? channelZero[(int)armedChannel] : NAN, armedChannel >= 0 ? channelMax[(int)armedChannel] : NAN);
print("Mode %-7g%-7g%-7g\n", modeChannel, modeChannel >= 0 ? channelZero[(int)modeChannel] : NAN, modeChannel >= 0 ? channelMax[(int)modeChannel] : NAN); print("Mode %-7g%-7g%-7g\n", modeChannel, modeChannel >= 0 ? channelZero[(int)modeChannel] : NAN, modeChannel >= 0 ? channelMax[(int)modeChannel] : NAN);
} }

View File

@@ -35,7 +35,6 @@ 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);
} }

View File

@@ -13,7 +13,6 @@
#define WIFI_PASSWORD "flixwifi" #define WIFI_PASSWORD "flixwifi"
#define WIFI_UDP_PORT 14550 #define WIFI_UDP_PORT 14550
#define WIFI_UDP_REMOTE_PORT 14550 #define WIFI_UDP_REMOTE_PORT 14550
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
WiFiUDP udp; WiFiUDP udp;
@@ -25,7 +24,7 @@ void setupWiFi() {
void sendWiFi(const uint8_t *buf, int len) { void sendWiFi(const uint8_t *buf, int len) {
if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return; if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return;
udp.beginPacket(udp.remoteIP() ? udp.remoteIP() : WIFI_UDP_REMOTE_ADDR, WIFI_UDP_REMOTE_PORT); udp.beginPacket(WiFi.softAPBroadcastIP(), WIFI_UDP_REMOTE_PORT);
udp.write(buf, len); udp.write(buf, len);
udp.endPacket(); udp.endPacket();
} }

View File

@@ -4,7 +4,7 @@
## Building and running ## Building and running
See [building and running instructions](../docs/usage.md#simulation). See [building and running instructions](../docs/build.md#simulation).
## Code structure ## Code structure

View File

@@ -16,7 +16,7 @@ double t = NAN;
float dt; float dt;
float motors[4]; float motors[4];
float controlRoll, controlPitch, controlYaw, controlThrottle = NAN; float controlRoll, controlPitch, controlYaw, controlThrottle = NAN;
float controlMode = NAN; float controlArmed = NAN, controlMode = NAN;
Vector acc; Vector acc;
Vector gyro; Vector gyro;
Vector rates; Vector rates;
@@ -56,8 +56,8 @@ void sendMavlinkPrint();
inline Quaternion fluToFrd(const Quaternion &q); inline Quaternion fluToFrd(const Quaternion &q);
void failsafe(); void failsafe();
void rcLossFailsafe(); void rcLossFailsafe();
void descend();
void autoFailsafe(); void autoFailsafe();
void descend();
int parametersCount(); int parametersCount();
const char *getParameterName(int index); const char *getParameterName(int index);
float getParameter(int index); float getParameter(int index);

View File

@@ -13,7 +13,6 @@
#define WIFI_UDP_PORT 14580 #define WIFI_UDP_PORT 14580
#define WIFI_UDP_REMOTE_PORT 14550 #define WIFI_UDP_REMOTE_PORT 14550
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
int wifiSocket; int wifiSocket;
@@ -36,7 +35,7 @@ void sendWiFi(const uint8_t *buf, int len) {
if (wifiSocket == 0) setupWiFi(); if (wifiSocket == 0) setupWiFi();
sockaddr_in addr; // remote address sockaddr_in addr; // remote address
addr.sin_family = AF_INET; addr.sin_family = AF_INET;
addr.sin_addr.s_addr = inet_addr(WIFI_UDP_REMOTE_ADDR); addr.sin_addr.s_addr = INADDR_BROADCAST; // send UDP broadcast
addr.sin_port = htons(WIFI_UDP_REMOTE_PORT); addr.sin_port = htons(WIFI_UDP_REMOTE_PORT);
sendto(wifiSocket, buf, len, 0, (sockaddr *)&addr, sizeof(addr)); sendto(wifiSocket, buf, len, 0, (sockaddr *)&addr, sizeof(addr));
} }

View File

@@ -66,14 +66,13 @@ gyro = flix.wait('gyro') # wait for gyroscope update
attitude = flix.wait('attitude', timeout=3) # wait for attitude update, raise TimeoutError after 3 seconds attitude = flix.wait('attitude', timeout=3) # wait for attitude update, raise TimeoutError after 3 seconds
``` ```
The second argument (`value`) specifies a condition for filtering events. It can be either an expected value or a callable: The `value` argument specifies a condition for filtering events. It can be either an expected value or a callable:
```python ```python
flix.wait('armed', True) # wait until armed flix.wait('armed', value=True) # wait until armed
flix.wait('armed', False) # wait until disarmed flix.wait('armed', value=False) # wait until disarmed
flix.wait('mode', 'AUTO') # wait until flight mode is switched to AUTO flix.wait('motors', value=lambda motors: not any(motors)) # wait until all motors stop
flix.wait('motors', lambda motors: not any(motors)) # wait until all motors stop flix.wait('attitude_euler', value=lambda att: att[0] > 0) # wait until roll angle is positive
flix.wait('attitude_euler', lambda att: att[0] > 0) # wait until roll angle is positive
``` ```
Full list of events: Full list of events:
@@ -108,7 +107,7 @@ Get and set firmware parameters using `get_param` and `set_param` methods:
```python ```python
pitch_p = flix.get_param('PITCH_P') # get parameter value pitch_p = flix.get_param('PITCH_P') # get parameter value
flix.set_param('PITCH_P', 5) # set parameter value flix.set_param('PITCH_P', 5) # set parameter value
``` ```
Execute CLI commands using `cli` method. This method returns command response: Execute CLI commands using `cli` method. This method returns command response:
@@ -122,54 +121,17 @@ flix.cli('reboot') # reboot the drone
> [!TIP] > [!TIP]
> Use `help` command to get the list of available commands. > Use `help` command to get the list of available commands.
You can imitate pilot's controls using `set_controls` method:
```python
flix.set_controls(roll=0, pitch=0, yaw=0, throttle=0.6)
```
> [!WARNING]
> This method **is not intended for automatic flights**, only for adding support for a custom pilot input device.
### Automatic flight ### Automatic flight
To perform automatic flight, switch the mode to *AUTO*, either from the remote control, or from the code: The flight control feature is in development. List of methods intended for automatic flight control:
```python * `set_position`
flix.set_mode('AUTO') * `set_velocity`
``` * `set_attitude`
* `set_rates`
In this mode you can set flight control targets. Setting attitude target: * `set_motors`
* `set_controls`
```python * `set_mode`
flix.set_attitude([0.1, 0.2, 0.3], 0.6) # set target roll, pitch, yaw and thrust
flix.set_attitude([1, 0, 0, 0], 0.6) # set target attitude quaternion and thrust
```
Setting angular rates target:
```python
flix.set_rates([0.1, 0.2, 0.3], 0.6) # set target roll rate, pitch rate, yaw rate and thrust
```
You also can control raw motors outputs directly:
```python
flix.set_motors([0.5, 0.5, 0.5, 0.5]) # set motors outputs in range [0, 1]
```
In *AUTO* mode, the drone will arm automatically if the thrust is greater than zero, and disarm if thrust is zero. Therefore, to disarm the drone, set thrust to zero:
```python
flix.set_attitude([0, 0, 0], 0) # disarm the drone
```
The following methods are in development and are not functional yet:
* `set_position` — set target position.
* `set_velocity` — set target velocity.
To exit from *AUTO* mode move control sticks and the drone will switch to *STAB* mode.
## Usage alongside QGroundControl ## Usage alongside QGroundControl
@@ -189,8 +151,6 @@ You can use the Flix library alongside the QGroundControl app, using a proxy mod
* *Port*: 14560 * *Port*: 14560
4. Restart QGroundControl. 4. Restart QGroundControl.
<img src="../../docs/img/qgc-proxy.png" width="300">
Now you can run `pyflix` scripts and QGroundControl simultaneously. Now you can run `pyflix` scripts and QGroundControl simultaneously.
## Tools ## Tools

View File

@@ -176,7 +176,6 @@ class Flix:
# TODO: to be removed: the old way of passing motor outputs # TODO: to be removed: the old way of passing motor outputs
if isinstance(msg, mavlink.MAVLink_actuator_output_status_message): if isinstance(msg, mavlink.MAVLink_actuator_output_status_message):
self.motors = msg.actuator[:4] # type: ignore self.motors = msg.actuator[:4] # type: ignore
self._trigger('motors', self.motors)
if isinstance(msg, mavlink.MAVLink_scaled_imu_message): if isinstance(msg, mavlink.MAVLink_scaled_imu_message):
self.acc = self._mavlink_to_flu([msg.xacc / 1000, msg.yacc / 1000, msg.zacc / 1000]) self.acc = self._mavlink_to_flu([msg.xacc / 1000, msg.yacc / 1000, msg.zacc / 1000])
@@ -336,7 +335,7 @@ class Flix:
if not all(0 <= m <= 1 for m in motors): if not all(0 <= m <= 1 for m in motors):
raise ValueError('motors must be in range [0, 1]') raise ValueError('motors must be in range [0, 1]')
for _ in range(2): # duplicate to ensure delivery for _ in range(2): # duplicate to ensure delivery
self.mavlink.set_actuator_control_target_send(int(time.time() * 1000000), 0, self.system_id, 0, motors + [0] * 4) # type: ignore self.mavlink.set_actuator_control_target_send(time.time() * 1000, 0, self.system_id, 0, motors + [0] * 4) # type: ignore
def set_controls(self, roll: float, pitch: float, yaw: float, throttle: float): def set_controls(self, roll: float, pitch: float, yaw: float, throttle: float):
"""Send pilot's controls. Warning: not intended for automatic control""" """Send pilot's controls. Warning: not intended for automatic control"""
@@ -344,7 +343,7 @@ class Flix:
raise ValueError('roll, pitch, yaw must be in range [-1, 1]') raise ValueError('roll, pitch, yaw must be in range [-1, 1]')
if not 0 <= throttle <= 1: if not 0 <= throttle <= 1:
raise ValueError('throttle must be in range [0, 1]') raise ValueError('throttle must be in range [0, 1]')
self.mavlink.manual_control_send(self.system_id, int(roll * 1000), int(pitch * 1000), int(yaw * 1000), int(throttle * 1000), 0) # type: ignore self.mavlink.manual_control_send(self.system_id, roll * 1000, pitch * 1000, yaw * 1000, throttle * 1000, 0) # type: ignore
def cli(self, cmd: str, wait_response: bool = True) -> str: def cli(self, cmd: str, wait_response: bool = True) -> str:
cmd = cmd.strip() cmd = cmd.strip()

View File

@@ -1,6 +1,6 @@
[project] [project]
name = "pyflix" name = "pyflix"
version = "0.7" version = "0.5"
description = "Python API for Flix drone" description = "Python API for Flix drone"
authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }] authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }]
license = "MIT" license = "MIT"