mirror of
https://github.com/okalachev/flix.git
synced 2026-03-30 20:13:44 +00:00
Compare commits
13 Commits
e7e57d1020
...
esp32-c3
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
2308bd4d8f | ||
|
|
8153644578 | ||
|
|
5b654e4d8e | ||
|
|
cf10ec6161 | ||
|
|
6d01cd2e79 | ||
|
|
0abb18c616 | ||
|
|
30326a5662 | ||
|
|
dd3575174b | ||
|
|
c0f3301da4 | ||
|
|
a6bad3a69b | ||
|
|
9a9bd07251 | ||
|
|
28f5855a57 | ||
|
|
7e24ee30f7 |
4
.github/workflows/build.yml
vendored
4
.github/workflows/build.yml
vendored
@@ -25,8 +25,8 @@ jobs:
|
||||
path: flix/build
|
||||
- name: Build firmware for ESP32-S3
|
||||
run: make BOARD=esp32:esp32:esp32s3
|
||||
- name: Build firmware with WiFi disabled
|
||||
run: sed -i 's/^#define WIFI_ENABLED 1$/#define WIFI_ENABLED 0/' flix/flix.ino && make
|
||||
- name: Build firmware for ESP32-C3
|
||||
run: make BOARD=esp32:esp32:esp32c3
|
||||
- name: Check c_cpp_properties.json
|
||||
run: tools/check_c_cpp_properties.py
|
||||
|
||||
|
||||
@@ -7,6 +7,7 @@
|
||||
"MD024": false,
|
||||
"MD033": false,
|
||||
"MD034": false,
|
||||
"MD040": false,
|
||||
"MD059": false,
|
||||
"MD044": {
|
||||
"html_elements": false,
|
||||
|
||||
87
.vscode/c_cpp_properties.json
vendored
87
.vscode/c_cpp_properties.json
vendored
@@ -6,21 +6,34 @@
|
||||
"${workspaceFolder}/flix",
|
||||
"${workspaceFolder}/gazebo",
|
||||
"${workspaceFolder}/tools/**",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
||||
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**",
|
||||
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32",
|
||||
"~/.arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**",
|
||||
"~/Arduino/libraries/**",
|
||||
"/usr/include/gazebo-11/",
|
||||
"/usr/include/ignition/math6/"
|
||||
],
|
||||
"forcedInclude": [
|
||||
"${workspaceFolder}/.vscode/intellisense.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.3.6/cores/esp32/Arduino.h",
|
||||
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/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",
|
||||
"${workspaceFolder}/flix/safety.ino"
|
||||
],
|
||||
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
|
||||
"compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2511/bin/xtensa-esp32-elf-g++",
|
||||
"cStandard": "c11",
|
||||
"cppStandard": "c++17",
|
||||
"defines": [
|
||||
@@ -40,21 +53,34 @@
|
||||
"name": "Mac",
|
||||
"includePath": [
|
||||
"${workspaceFolder}/flix",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/include/**",
|
||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32",
|
||||
"~/Library/Arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**",
|
||||
"~/Documents/Arduino/libraries/**",
|
||||
"/opt/homebrew/include/gazebo-11/",
|
||||
"/opt/homebrew/include/ignition/math6/"
|
||||
],
|
||||
"forcedInclude": [
|
||||
"${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/variants/d1_mini32/pins_arduino.h"
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32/Arduino.h",
|
||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/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",
|
||||
"${workspaceFolder}/flix/safety.ino"
|
||||
],
|
||||
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++",
|
||||
"compilerPath": "~/Library/Arduino15/packages/esp32/tools/esp-x32/2511/bin/xtensa-esp32-elf-g++",
|
||||
"cStandard": "c11",
|
||||
"cppStandard": "c++17",
|
||||
"defines": [
|
||||
@@ -77,19 +103,32 @@
|
||||
"${workspaceFolder}/flix",
|
||||
"${workspaceFolder}/gazebo",
|
||||
"${workspaceFolder}/tools/**",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**",
|
||||
"~/Documents/Arduino/libraries/**"
|
||||
],
|
||||
"forcedInclude": [
|
||||
"${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/variants/d1_mini32/pins_arduino.h"
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32/Arduino.h",
|
||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/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",
|
||||
"${workspaceFolder}/flix/safety.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/2511/bin/xtensa-esp32-elf-g++.exe",
|
||||
"cStandard": "c11",
|
||||
"cppStandard": "c++17",
|
||||
"defines": [
|
||||
|
||||
4
Makefile
4
Makefile
@@ -13,10 +13,10 @@ monitor:
|
||||
|
||||
dependencies .dependencies:
|
||||
arduino-cli core update-index --config-file arduino-cli.yaml
|
||||
arduino-cli core install esp32:esp32@3.2.0 --config-file arduino-cli.yaml
|
||||
arduino-cli core install esp32:esp32@3.3.6 --config-file arduino-cli.yaml
|
||||
arduino-cli lib update-index
|
||||
arduino-cli lib install "FlixPeriph"
|
||||
arduino-cli lib install "MAVLink"@2.0.16
|
||||
arduino-cli lib install "MAVLink"@2.0.25
|
||||
touch .dependencies
|
||||
|
||||
gazebo/build cmake: gazebo/CMakeLists.txt
|
||||
|
||||
@@ -21,15 +21,13 @@
|
||||
* Dedicated for education and research.
|
||||
* Made from general-purpose components.
|
||||
* Simple and clean source code in Arduino (<2k lines firmware).
|
||||
* Connectivity using Wi-Fi and MAVLink protocol.
|
||||
* Control using USB gamepad, remote control or smartphone.
|
||||
* Wi-Fi and MAVLink support.
|
||||
* Wireless command line interface and analyzing.
|
||||
* Precise simulation with Gazebo.
|
||||
* Python library.
|
||||
* Python library for scripting and automatic flights.
|
||||
* Textbook on flight control theory and practice ([in development](https://quadcopter.dev)).
|
||||
* *Position control (using external camera) and autonomous flights¹*.
|
||||
|
||||
*¹ — planned.*
|
||||
* *Position control (planned)*.
|
||||
|
||||
## It actually flies
|
||||
|
||||
|
||||
@@ -87,13 +87,13 @@ Flix поддерживает следующие модели IMU:
|
||||
#include <FlixPeriph.h>
|
||||
#include <SPI.h>
|
||||
|
||||
MPU9250 IMU(SPI);
|
||||
MPU9250 imu(SPI);
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
bool success = IMU.begin();
|
||||
bool success = imu.begin();
|
||||
if (!success) {
|
||||
Serial.println("Failed to initialize IMU");
|
||||
Serial.println("Failed to initialize the IMU");
|
||||
}
|
||||
}
|
||||
```
|
||||
@@ -108,21 +108,21 @@ void setup() {
|
||||
#include <FlixPeriph.h>
|
||||
#include <SPI.h>
|
||||
|
||||
MPU9250 IMU(SPI);
|
||||
MPU9250 imu(SPI);
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
bool success = IMU.begin();
|
||||
bool success = imu.begin();
|
||||
if (!success) {
|
||||
Serial.println("Failed to initialize IMU");
|
||||
Serial.println("Failed to initialize the IMU");
|
||||
}
|
||||
}
|
||||
|
||||
void loop() {
|
||||
IMU.waitForData();
|
||||
imu.waitForData();
|
||||
|
||||
float gx, gy, gz;
|
||||
IMU.getGyro(gx, gy, gz);
|
||||
imu.getGyro(gx, gy, gz);
|
||||
|
||||
Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
|
||||
delay(50); // замедление вывода
|
||||
@@ -135,36 +135,36 @@ void loop() {
|
||||
|
||||
## Конфигурация гироскопа
|
||||
|
||||
В коде Flix настройка IMU происходит в функции `configureIMU`. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплов и частота LPF-фильтра.
|
||||
В коде Flix настройка IMU происходит в функции `configureIMU`. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплирования и частота LPF-фильтра.
|
||||
|
||||
### Частота сэмплов
|
||||
### Частота сэмплирования
|
||||
|
||||
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер.
|
||||
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота, тем выше точность управления полетом, но и тем больше нагрузка на микроконтроллер.
|
||||
|
||||
Частота сэмплов устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
|
||||
Частота сэмплирования устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
|
||||
|
||||
```cpp
|
||||
IMU.setRate(IMU.RATE_1KHZ_APPROX);
|
||||
```
|
||||
|
||||
Поскольку не все поддерживаемые IMU могут работать строго на частоте 1 кГц, в библиотеке FlixPeriph существует возможность приближенной настройки частоты сэмплов. Например, у IMU ICM-20948 при такой настройке реальная частота сэмплирования будет равна 1125 Гц.
|
||||
Поскольку не все поддерживаемые IMU могут работать строго на частоте 1 кГц, в библиотеке FlixPeriph существует возможность приближенной настройки частоты сэмплирования. Например, у IMU ICM-20948 при такой настройке реальная частота сэмплирования будет равна 1125 Гц.
|
||||
|
||||
Другие доступные для установки в библиотеке FlixPeriph частоты сэмплирования:
|
||||
|
||||
* `RATE_MIN` — минимальная частота сэмплов для конкретного IMU.
|
||||
* `RATE_MIN` — минимальная частота для конкретного IMU.
|
||||
* `RATE_50HZ_APPROX` — значение, близкое к 50 Гц.
|
||||
* `RATE_1KHZ_APPROX` — значение, близкое к 1 кГц.
|
||||
* `RATE_8KHZ_APPROX` — значение, близкое к 8 кГц.
|
||||
* `RATE_MAX` — максимальная частота сэмплов для конкретного IMU.
|
||||
* `RATE_MAX` — максимальная частота для конкретного IMU.
|
||||
|
||||
#### Диапазон измерений
|
||||
|
||||
Большинство MEMS-гироскопов поддерживают несколько диапазонов измерений угловой скорости. Главное преимущество выбора меньшего диапазона — бо́льшая чувствительность. В полетных контроллерах обычно выбирается максимальный диапазон измерений от –2000 до 2000 градусов в секунду, чтобы обеспечить возможность динамичных маневров.
|
||||
Большинство MEMS-гироскопов поддерживают несколько диапазонов измерений угловой скорости. Главное преимущество выбора меньшего диапазона — бо́льшая чувствительность. В полетных контроллерах обычно выбирается максимальный диапазон измерений от –2000 до 2000 градусов в секунду, чтобы обеспечить возможность быстрых маневров.
|
||||
|
||||
В библиотеке FlixPeriph диапазон измерений гироскопа устанавливается методом `setGyroRange()`:
|
||||
|
||||
```cpp
|
||||
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
|
||||
imu.setGyroRange(imu.GYRO_RANGE_2000DPS);
|
||||
```
|
||||
|
||||
### LPF-фильтр
|
||||
@@ -172,7 +172,7 @@ IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
|
||||
IMU InvenSense могут фильтровать измерения на аппаратном уровне при помощи фильтра нижних частот (LPF). Flix реализует собственный фильтр для гироскопа, чтобы иметь больше гибкости при поддержке разных IMU. Поэтому для встроенного LPF устанавливается максимальная частота среза:
|
||||
|
||||
```cpp
|
||||
IMU.setDLPF(IMU.DLPF_MAX);
|
||||
imu.setDLPF(imu.DLPF_MAX);
|
||||
```
|
||||
|
||||
## Калибровка гироскопа
|
||||
@@ -181,7 +181,7 @@ IMU.setDLPF(IMU.DLPF_MAX);
|
||||
|
||||
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]
|
||||
|
||||
Для качественной работы подсистемы оценки ориентации и управления дроном необходимо оценить *bias* гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции `calibrateGyro()`. Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются *bias* гироскопа и в дальнейшем вычитаются из измерений.
|
||||
Для точной работы подсистемы оценки ориентации и управления дроном необходимо оценить *bias* гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции `calibrateGyro()`. Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются *bias* гироскопа и в дальнейшем вычитаются из измерений.
|
||||
|
||||
Программа для вывода данных с гироскопа с калибровкой:
|
||||
|
||||
@@ -189,23 +189,23 @@ IMU.setDLPF(IMU.DLPF_MAX);
|
||||
#include <FlixPeriph.h>
|
||||
#include <SPI.h>
|
||||
|
||||
MPU9250 IMU(SPI);
|
||||
MPU9250 imu(SPI);
|
||||
|
||||
float gyroBiasX, gyroBiasY, gyroBiasZ; // bias гироскопа
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
bool success = IMU.begin();
|
||||
bool success = imu.begin();
|
||||
if (!success) {
|
||||
Serial.println("Failed to initialize IMU");
|
||||
Serial.println("Failed to initialize the IMU");
|
||||
}
|
||||
calibrateGyro();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
float gx, gy, gz;
|
||||
IMU.waitForData();
|
||||
IMU.getGyro(gx, gy, gz);
|
||||
imu.waitForData();
|
||||
imu.getGyro(gx, gy, gz);
|
||||
|
||||
// Устранение bias гироскопа
|
||||
gx -= gyroBiasX;
|
||||
@@ -226,9 +226,9 @@ void calibrateGyro() {
|
||||
|
||||
// Получение 1000 измерений гироскопа
|
||||
for (int i = 0; i < samples; i++) {
|
||||
IMU.waitForData();
|
||||
imu.waitForData();
|
||||
float gx, gy, gz;
|
||||
IMU.getGyro(gx, gy, gz);
|
||||
imu.getGyro(gx, gy, gz);
|
||||
gyroBiasX += gx;
|
||||
gyroBiasY += gy;
|
||||
gyroBiasZ += gz;
|
||||
|
||||
@@ -42,7 +42,7 @@ Pilot inputs are interpreted in `interpretControls()`, and then converted to the
|
||||
|
||||
* `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*.
|
||||
* `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 motor thrust target, range [0, 1].
|
||||
|
||||
|
||||
@@ -20,10 +20,10 @@ You can build and upload the firmware using either **Arduino IDE** (easier for b
|
||||
|
||||
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.
|
||||
3. Install ESP32 core, version 3.3.6. 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.
|
||||
* `MAVLink`, version 2.0.25.
|
||||
5. Open the `flix/flix.ino` sketch from downloaded firmware sources in Arduino IDE.
|
||||
6. 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.
|
||||
7. [Build and upload](https://docs.arduino.cc/software/ide-v2/tutorials/getting-started/ide-v2-uploading-a-sketch) the firmware using Arduino IDE.
|
||||
@@ -108,7 +108,7 @@ The drone is configured using parameters. To access and modify them, go to the Q
|
||||
|
||||
<img src="img/parameters.png" width="400">
|
||||
|
||||
You can also work with parameters using `p` command in the console.
|
||||
You can also work with parameters using `p` command in the console. Parameter names are case-insensitive.
|
||||
|
||||
### Define IMU orientation
|
||||
|
||||
@@ -143,9 +143,9 @@ Before flight you need to calibrate the accelerometer:
|
||||
* The `accel` and `gyro` fields should change as you move the drone.
|
||||
* The `landed` field should be `1` when the drone is still on the ground and `0` when you lift it up.
|
||||
|
||||
2. 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. Attitude indicator in QGroundControl is shown below:
|
||||
2. 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. Compare your attitude indicator (in the *large vertical* mode) to the video:
|
||||
|
||||
<img src="img/qgc-attitude.png" height="200">
|
||||
<a href="https://youtu.be/yVRN23-GISU"><img width=300 src="https://i3.ytimg.com/vi/yVRN23-GISU/maxresdefault.jpg"></a>
|
||||
|
||||
3. Perform motor tests in the console. Use the following commands **— remove the propellers before running the tests!**
|
||||
|
||||
@@ -243,9 +243,43 @@ 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.
|
||||
|
||||
## Wi-Fi configuration
|
||||
|
||||
You can configure the Wi-Fi using parameters and console commands.
|
||||
|
||||
The Wi-Fi mode is chosen using `WIFI_MODE` parameter in QGroundControl or in the console:
|
||||
|
||||
* `0` — Wi-Fi is disabled.
|
||||
* `1` — Access Point mode (*AP*) — the drone creates a Wi-Fi network.
|
||||
* `2` — Client mode (*STA*) — the drone connects to an existing Wi-Fi network.
|
||||
* `3` — *ESP-NOW (not implemented yet)*.
|
||||
|
||||
> [!WARNING]
|
||||
> Tests showed that Client mode may cause **additional delays** in remote control (due to retranslations), so it's generally not recommended.
|
||||
|
||||
The SSID and password are configured using the `ap` and `sta` console commands:
|
||||
|
||||
```
|
||||
ap <ssid> <password>
|
||||
sta <ssid> <password>
|
||||
```
|
||||
|
||||
Example of configuring the Access Point mode:
|
||||
|
||||
```
|
||||
ap my-flix-ssid mypassword123
|
||||
p WIFI_MODE 1
|
||||
```
|
||||
|
||||
Disabling Wi-Fi:
|
||||
|
||||
```
|
||||
p WIFI_MODE 0
|
||||
```
|
||||
|
||||
## 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 command on your computer for that:
|
||||
|
||||
```bash
|
||||
make log
|
||||
|
||||
@@ -3,8 +3,6 @@
|
||||
|
||||
// Implementation of command line interface
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "flix.h"
|
||||
#include "pid.h"
|
||||
#include "vector.h"
|
||||
#include "util.h"
|
||||
@@ -40,6 +38,8 @@ const char* motd =
|
||||
"raw/stab/acro/auto - set mode\n"
|
||||
"rc - show RC data\n"
|
||||
"wifi - show Wi-Fi info\n"
|
||||
"ap <ssid> <password> - setup Wi-Fi access point\n"
|
||||
"sta <ssid> <password> - setup Wi-Fi client mode\n"
|
||||
"mot - show motor output\n"
|
||||
"log [dump] - print log header [and data]\n"
|
||||
"cr - calibrate RC\n"
|
||||
@@ -56,9 +56,7 @@ void print(const char* format, ...) {
|
||||
vsnprintf(buf, sizeof(buf), format, args);
|
||||
va_end(args);
|
||||
Serial.print(buf);
|
||||
#if WIFI_ENABLED
|
||||
mavlinkPrint(buf);
|
||||
#endif
|
||||
}
|
||||
|
||||
void pause(float duration) {
|
||||
@@ -66,14 +64,12 @@ void pause(float duration) {
|
||||
while (t - start < duration) {
|
||||
step();
|
||||
handleInput();
|
||||
#if WIFI_ENABLED
|
||||
processMavlink();
|
||||
#endif
|
||||
delay(50);
|
||||
}
|
||||
}
|
||||
|
||||
void doCommand(String str, bool echo) {
|
||||
void doCommand(String str, bool echo = false) {
|
||||
// parse command
|
||||
String command, arg0, arg1;
|
||||
splitString(str, command, arg0, arg1);
|
||||
@@ -138,9 +134,11 @@ void doCommand(String str, bool echo) {
|
||||
print("mode: %s\n", getModeName());
|
||||
print("armed: %d\n", armed);
|
||||
} else if (command == "wifi") {
|
||||
#if WIFI_ENABLED
|
||||
printWiFiInfo();
|
||||
#endif
|
||||
} else if (command == "ap") {
|
||||
configWiFi(true, arg0.c_str(), arg1.c_str());
|
||||
} else if (command == "sta") {
|
||||
configWiFi(false, arg0.c_str(), arg1.c_str());
|
||||
} else if (command == "mot") {
|
||||
print("front-right %g front-left %g rear-right %g rear-left %g\n",
|
||||
motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]);
|
||||
@@ -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
|
||||
@@ -3,16 +3,38 @@
|
||||
|
||||
// Flight control
|
||||
|
||||
#include "config.h"
|
||||
#include "flix.h"
|
||||
#include "vector.h"
|
||||
#include "quaternion.h"
|
||||
#include "pid.h"
|
||||
#include "lpf.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;
|
||||
bool armed = false;
|
||||
|
||||
@@ -3,8 +3,6 @@
|
||||
|
||||
// Attitude estimation from gyro and accelerometer
|
||||
|
||||
#include "config.h"
|
||||
#include "flix.h"
|
||||
#include "quaternion.h"
|
||||
#include "vector.h"
|
||||
#include "lpf.h"
|
||||
90
flix/flix.h
90
flix/flix.h
@@ -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);
|
||||
@@ -3,11 +3,18 @@
|
||||
|
||||
// Main firmware file
|
||||
|
||||
#include "config.h"
|
||||
#include "vector.h"
|
||||
#include "quaternion.h"
|
||||
#include "util.h"
|
||||
#include "flix.h"
|
||||
|
||||
|
||||
extern float t, dt;
|
||||
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
||||
extern Vector gyro, acc;
|
||||
extern Vector rates;
|
||||
extern Quaternion attitude;
|
||||
extern bool landed;
|
||||
extern float motors[4];
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
@@ -17,9 +24,7 @@ void setup() {
|
||||
setupLED();
|
||||
setupMotors();
|
||||
setLED(true);
|
||||
#if WIFI_ENABLED
|
||||
setupWiFi();
|
||||
#endif
|
||||
setupIMU();
|
||||
setupRC();
|
||||
setLED(false);
|
||||
@@ -34,9 +39,7 @@ void loop() {
|
||||
control();
|
||||
sendMotors();
|
||||
handleInput();
|
||||
#if WIFI_ENABLED
|
||||
processMavlink();
|
||||
#endif
|
||||
logData();
|
||||
syncParameters();
|
||||
}
|
||||
|
||||
@@ -3,8 +3,6 @@
|
||||
|
||||
// Board's LED control
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
#define BLINK_PERIOD 500000
|
||||
|
||||
#ifndef LED_BUILTIN
|
||||
@@ -3,7 +3,6 @@
|
||||
|
||||
// In-RAM logging
|
||||
|
||||
#include "flix.h"
|
||||
#include "vector.h"
|
||||
#include "util.h"
|
||||
|
||||
@@ -5,8 +5,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
template <typename T> // Using template to make the filter usable for scalar and vector values
|
||||
class LowPassFilter {
|
||||
public:
|
||||
|
||||
@@ -3,25 +3,16 @@
|
||||
|
||||
// MAVLink communication
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "config.h"
|
||||
#include "flix.h"
|
||||
|
||||
#if WIFI_ENABLED
|
||||
|
||||
#include <MAVLink.h>
|
||||
#include "util.h"
|
||||
|
||||
#define SYSTEM_ID 1
|
||||
#define MAVLINK_RATE_SLOW 1
|
||||
#define MAVLINK_RATE_FAST 10
|
||||
|
||||
extern const int AUTO, STAB;
|
||||
extern uint16_t channels[16];
|
||||
extern float controlTime;
|
||||
|
||||
bool mavlinkConnected = false;
|
||||
String mavlinkPrintBuffer;
|
||||
int mavlinkSysId = 1;
|
||||
Rate telemetryFast(10);
|
||||
Rate telemetrySlow(2);
|
||||
|
||||
void processMavlink() {
|
||||
sendMavlink();
|
||||
@@ -34,10 +25,8 @@ void sendMavlink() {
|
||||
mavlink_message_t msg;
|
||||
uint32_t time = t * 1000;
|
||||
|
||||
static Rate slow(MAVLINK_RATE_SLOW), fast(MAVLINK_RATE_FAST);
|
||||
|
||||
if (slow) {
|
||||
mavlink_msg_heartbeat_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
|
||||
if (telemetrySlow) {
|
||||
mavlink_msg_heartbeat_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
|
||||
(armed ? MAV_MODE_FLAG_SAFETY_ARMED : 0) |
|
||||
((mode == STAB) ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0) |
|
||||
((mode == AUTO) ? MAV_MODE_FLAG_AUTO_ENABLED : MAV_MODE_FLAG_MANUAL_INPUT_ENABLED),
|
||||
@@ -46,27 +35,27 @@ void sendMavlink() {
|
||||
|
||||
if (!mavlinkConnected) return; // send only heartbeat until connected
|
||||
|
||||
mavlink_msg_extended_sys_state_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
mavlink_msg_extended_sys_state_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
MAV_VTOL_STATE_UNDEFINED, landed ? MAV_LANDED_STATE_ON_GROUND : MAV_LANDED_STATE_IN_AIR);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
|
||||
if (fast && mavlinkConnected) {
|
||||
if (telemetryFast && mavlinkConnected) {
|
||||
const float zeroQuat[] = {0, 0, 0, 0};
|
||||
mavlink_msg_attitude_quaternion_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
mavlink_msg_attitude_quaternion_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd
|
||||
sendMessage(&msg);
|
||||
|
||||
mavlink_msg_rc_channels_raw_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,
|
||||
mavlink_msg_rc_channels_raw_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,
|
||||
channels[0], channels[1], channels[2], channels[3], channels[4], channels[5], channels[6], channels[7], UINT8_MAX);
|
||||
if (channels[0] != 0) sendMessage(&msg); // 0 means no RC input
|
||||
|
||||
float controls[8];
|
||||
memcpy(controls, motors, sizeof(motors));
|
||||
mavlink_msg_actuator_control_target_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0, controls);
|
||||
mavlink_msg_actuator_control_target_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0, controls);
|
||||
sendMessage(&msg);
|
||||
|
||||
mavlink_msg_scaled_imu_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time,
|
||||
mavlink_msg_scaled_imu_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, time,
|
||||
acc.x * 1000, -acc.y * 1000, -acc.z * 1000, // convert to frd
|
||||
gyro.x * 1000, -gyro.y * 1000, -gyro.z * 1000,
|
||||
0, 0, 0, 0);
|
||||
@@ -101,7 +90,7 @@ void handleMavlink(const void *_msg) {
|
||||
if (msg.msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
|
||||
mavlink_manual_control_t m;
|
||||
mavlink_msg_manual_control_decode(&msg, &m);
|
||||
if (m.target && m.target != SYSTEM_ID) return; // 0 is broadcast
|
||||
if (m.target && m.target != mavlinkSysId) return; // 0 is broadcast
|
||||
|
||||
controlThrottle = m.z / 1000.0f;
|
||||
controlPitch = m.x / 1000.0f;
|
||||
@@ -114,11 +103,11 @@ void handleMavlink(const void *_msg) {
|
||||
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
|
||||
mavlink_param_request_list_t m;
|
||||
mavlink_msg_param_request_list_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
if (m.target_system && m.target_system != mavlinkSysId) return;
|
||||
|
||||
mavlink_message_t msg;
|
||||
for (int i = 0; i < parametersCount(); i++) {
|
||||
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
mavlink_msg_param_value_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
getParameterName(i), getParameter(i), MAV_PARAM_TYPE_REAL32, parametersCount(), i);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
@@ -127,7 +116,7 @@ void handleMavlink(const void *_msg) {
|
||||
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_READ) {
|
||||
mavlink_param_request_read_t m;
|
||||
mavlink_msg_param_request_read_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
if (m.target_system && m.target_system != mavlinkSysId) return;
|
||||
|
||||
char name[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
|
||||
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
|
||||
@@ -136,7 +125,7 @@ void handleMavlink(const void *_msg) {
|
||||
memcpy(name, getParameterName(m.param_index), 16);
|
||||
}
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
mavlink_msg_param_value_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
name, value, MAV_PARAM_TYPE_REAL32, parametersCount(), m.param_index);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
@@ -144,14 +133,15 @@ void handleMavlink(const void *_msg) {
|
||||
if (msg.msgid == MAVLINK_MSG_ID_PARAM_SET) {
|
||||
mavlink_param_set_t m;
|
||||
mavlink_msg_param_set_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
if (m.target_system && m.target_system != mavlinkSysId) return;
|
||||
|
||||
char name[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN + 1];
|
||||
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
|
||||
setParameter(name, m.param_value);
|
||||
bool success = setParameter(name, m.param_value);
|
||||
if (!success) return;
|
||||
// send ack
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
mavlink_msg_param_value_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
m.param_id, m.param_value, MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
|
||||
sendMessage(&msg);
|
||||
}
|
||||
@@ -159,17 +149,17 @@ void handleMavlink(const void *_msg) {
|
||||
if (msg.msgid == MAVLINK_MSG_ID_MISSION_REQUEST_LIST) { // handle to make qgc happy
|
||||
mavlink_mission_request_list_t m;
|
||||
mavlink_msg_mission_request_list_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
if (m.target_system && m.target_system != mavlinkSysId) return;
|
||||
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_mission_count_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, 0, 0, 0, MAV_MISSION_TYPE_MISSION, 0);
|
||||
mavlink_msg_mission_count_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, 0, 0, 0, MAV_MISSION_TYPE_MISSION, 0);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
|
||||
if (msg.msgid == MAVLINK_MSG_ID_SERIAL_CONTROL) {
|
||||
mavlink_serial_control_t m;
|
||||
mavlink_msg_serial_control_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
if (m.target_system && m.target_system != mavlinkSysId) return;
|
||||
|
||||
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
|
||||
strlcpy(data, (const char *)m.data, m.count); // data might be not null-terminated
|
||||
@@ -181,7 +171,7 @@ void handleMavlink(const void *_msg) {
|
||||
|
||||
mavlink_set_attitude_target_t m;
|
||||
mavlink_msg_set_attitude_target_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
if (m.target_system && m.target_system != mavlinkSysId) return;
|
||||
|
||||
// copy attitude, rates and thrust targets
|
||||
ratesTarget.x = m.body_roll_rate;
|
||||
@@ -203,7 +193,7 @@ void handleMavlink(const void *_msg) {
|
||||
|
||||
mavlink_set_actuator_control_target_t 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 != mavlinkSysId) return;
|
||||
|
||||
attitudeTarget.invalidate();
|
||||
ratesTarget.invalidate();
|
||||
@@ -212,33 +202,31 @@ void handleMavlink(const void *_msg) {
|
||||
armed = motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0;
|
||||
}
|
||||
|
||||
/* TODO:
|
||||
if (msg.msgid == MAVLINK_MSG_ID_LOG_REQUEST_DATA) {
|
||||
mavlink_log_request_data_t m;
|
||||
mavlink_msg_log_request_data_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
if (m.target_system && m.target_system != mavlinkSysId) return;
|
||||
|
||||
// Send all log records
|
||||
for (int i = 0; i < sizeof(logBuffer) / sizeof(logBuffer[0]); i++) {
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_log_data_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, 0, i,
|
||||
mavlink_msg_log_data_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, 0, i,
|
||||
sizeof(logBuffer[0]), (uint8_t *)logBuffer[i]);
|
||||
sendMessage(&msg);
|
||||
}
|
||||
}
|
||||
*/
|
||||
|
||||
// Handle commands
|
||||
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
|
||||
mavlink_command_long_t m;
|
||||
mavlink_msg_command_long_decode(&msg, &m);
|
||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
||||
if (m.target_system && m.target_system != mavlinkSysId) return;
|
||||
mavlink_message_t response;
|
||||
bool accepted = false;
|
||||
|
||||
if (m.command == MAV_CMD_REQUEST_MESSAGE && m.param1 == MAVLINK_MSG_ID_AUTOPILOT_VERSION) {
|
||||
accepted = true;
|
||||
mavlink_msg_autopilot_version_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &response,
|
||||
mavlink_msg_autopilot_version_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &response,
|
||||
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MAVLINK2, 1, 0, 1, 1, 0, 0, 0, 0, 0, 0, 0);
|
||||
sendMessage(&response);
|
||||
}
|
||||
@@ -257,7 +245,7 @@ void handleMavlink(const void *_msg) {
|
||||
|
||||
// send command ack
|
||||
mavlink_message_t ack;
|
||||
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(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_UNSUPPORTED, UINT8_MAX, 0, msg.sysid, msg.compid);
|
||||
sendMessage(&ack);
|
||||
}
|
||||
}
|
||||
@@ -274,7 +262,7 @@ void sendMavlinkPrint() {
|
||||
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
|
||||
strlcpy(data, str + i, sizeof(data));
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_serial_control_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
mavlink_msg_serial_control_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||
SERIAL_CONTROL_DEV_SHELL,
|
||||
i + MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN < strlen(str) ? SERIAL_CONTROL_FLAG_MULTI : 0, // more chunks to go
|
||||
0, 0, strlen(data), (uint8_t *)data, 0, 0);
|
||||
@@ -282,5 +270,3 @@ void sendMavlinkPrint() {
|
||||
}
|
||||
mavlinkPrintBuffer.clear();
|
||||
}
|
||||
|
||||
#endif
|
||||
@@ -4,17 +4,25 @@
|
||||
// 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)
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "config.h"
|
||||
#include "flix.h"
|
||||
#include "util.h"
|
||||
|
||||
#define MOTOR_0_PIN 12 // rear left
|
||||
#define MOTOR_1_PIN 13 // rear right
|
||||
#define MOTOR_2_PIN 14 // front right
|
||||
#define MOTOR_3_PIN 15 // front left
|
||||
|
||||
#define PWM_FREQUENCY 78000
|
||||
#define PWM_RESOLUTION 10
|
||||
#define PWM_STOP 0
|
||||
#define PWM_MIN 0
|
||||
#define PWM_MAX 1000000 / PWM_FREQUENCY
|
||||
|
||||
float motors[4]; // normalized motor thrusts in range [0..1]
|
||||
|
||||
extern const int MOTOR_REAR_LEFT = 0;
|
||||
extern const int MOTOR_REAR_RIGHT = 1;
|
||||
extern const int MOTOR_FRONT_RIGHT = 2;
|
||||
extern const int MOTOR_FRONT_LEFT = 3;
|
||||
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() {
|
||||
print("Setup Motors\n");
|
||||
@@ -4,29 +4,25 @@
|
||||
// Parameters storage in flash memory
|
||||
|
||||
#include <Preferences.h>
|
||||
#include "flix.h"
|
||||
#include "pid.h"
|
||||
#include "lpf.h"
|
||||
#include "util.h"
|
||||
|
||||
extern float channelZero[16];
|
||||
extern float channelMax[16];
|
||||
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;
|
||||
extern int wifiMode, udpLocalPort, udpRemotePort;
|
||||
extern float rcLossTimeout, descendTime;
|
||||
|
||||
Preferences storage;
|
||||
|
||||
struct Parameter {
|
||||
const char *name; // max length is 15 (Preferences key limit)
|
||||
float *variable;
|
||||
float value; // cache
|
||||
bool integer;
|
||||
union { float *f; int *i; }; // pointer to variable
|
||||
float cache; // what's stored in flash
|
||||
Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {};
|
||||
Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {};
|
||||
float getValue() const { return integer ? *i : *f; };
|
||||
void setValue(const float value) { if (integer) *i = value; else *f = value; };
|
||||
};
|
||||
|
||||
Parameter parameters[] = {
|
||||
@@ -88,6 +84,17 @@ Parameter parameters[] = {
|
||||
{"RC_THROTTLE", &throttleChannel},
|
||||
{"RC_YAW", &yawChannel},
|
||||
{"RC_MODE", &modeChannel},
|
||||
// wifi
|
||||
{"WIFI_MODE", &wifiMode},
|
||||
{"WIFI_LOC_PORT", &udpLocalPort},
|
||||
{"WIFI_REM_PORT", &udpRemotePort},
|
||||
// mavlink
|
||||
{"MAV_SYS_ID", &mavlinkSysId},
|
||||
{"MAV_RATE_SLOW", &telemetrySlow.rate},
|
||||
{"MAV_RATE_FAST", &telemetryFast.rate},
|
||||
// safety
|
||||
{"SF_RC_LOSS_TIME", &rcLossTimeout},
|
||||
{"SF_DESCEND_TIME", &descendTime},
|
||||
};
|
||||
|
||||
void setupParameters() {
|
||||
@@ -95,10 +102,10 @@ void setupParameters() {
|
||||
// Read parameters from storage
|
||||
for (auto ¶meter : parameters) {
|
||||
if (!storage.isKey(parameter.name)) {
|
||||
storage.putFloat(parameter.name, *parameter.variable);
|
||||
storage.putFloat(parameter.name, parameter.getValue()); // store default value
|
||||
}
|
||||
*parameter.variable = storage.getFloat(parameter.name, *parameter.variable);
|
||||
parameter.value = *parameter.variable;
|
||||
parameter.setValue(storage.getFloat(parameter.name, 0));
|
||||
parameter.cache = parameter.getValue();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -113,13 +120,13 @@ const char *getParameterName(int index) {
|
||||
|
||||
float getParameter(int index) {
|
||||
if (index < 0 || index >= parametersCount()) return NAN;
|
||||
return *parameters[index].variable;
|
||||
return parameters[index].getValue();
|
||||
}
|
||||
|
||||
float getParameter(const char *name) {
|
||||
for (auto ¶meter : parameters) {
|
||||
if (strcmp(parameter.name, name) == 0) {
|
||||
return *parameter.variable;
|
||||
if (strcasecmp(parameter.name, name) == 0) {
|
||||
return parameter.getValue();
|
||||
}
|
||||
}
|
||||
return NAN;
|
||||
@@ -127,8 +134,9 @@ float getParameter(const char *name) {
|
||||
|
||||
bool setParameter(const char *name, const float value) {
|
||||
for (auto ¶meter : parameters) {
|
||||
if (strcmp(parameter.name, name) == 0) {
|
||||
*parameter.variable = value;
|
||||
if (strcasecmp(parameter.name, name) == 0) {
|
||||
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
|
||||
parameter.setValue(value);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
@@ -141,16 +149,18 @@ void syncParameters() {
|
||||
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
|
||||
|
||||
for (auto ¶meter : parameters) {
|
||||
if (parameter.value == *parameter.variable) continue;
|
||||
if (isnan(parameter.value) && isnan(*parameter.variable)) continue; // handle NAN != NAN
|
||||
storage.putFloat(parameter.name, *parameter.variable);
|
||||
parameter.value = *parameter.variable;
|
||||
if (parameter.getValue() == parameter.cache) continue; // no change
|
||||
if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NaN
|
||||
if (isinf(parameter.getValue()) && isinf(parameter.cache)) continue; // both are Inf
|
||||
|
||||
storage.putFloat(parameter.name, parameter.getValue());
|
||||
parameter.cache = parameter.getValue(); // update cache
|
||||
}
|
||||
}
|
||||
|
||||
void printParameters() {
|
||||
for (auto ¶meter : parameters) {
|
||||
print("%s = %g\n", parameter.name, *parameter.variable);
|
||||
print("%s = %g\n", parameter.name, parameter.getValue());
|
||||
}
|
||||
}
|
||||
|
||||
@@ -5,8 +5,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "flix.h"
|
||||
#include "lpf.h"
|
||||
|
||||
class PID {
|
||||
|
||||
@@ -5,7 +5,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "vector.h"
|
||||
|
||||
class Quaternion : public Printable {
|
||||
|
||||
@@ -6,17 +6,21 @@
|
||||
#include <SBUS.h>
|
||||
#include "util.h"
|
||||
|
||||
#ifdef ESP32C3
|
||||
SBUS rc(Serial1);
|
||||
#else
|
||||
SBUS rc(Serial2);
|
||||
#endif
|
||||
|
||||
uint16_t channels[16]; // raw rc channels
|
||||
float channelZero[16]; // calibration zero 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)
|
||||
float controlMode = NAN;
|
||||
float controlTime = NAN; // time of the last controls update
|
||||
|
||||
// Channels mapping (using float to store in parameters):
|
||||
// Channels mapping (nan means not assigned):
|
||||
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
|
||||
|
||||
void setupRC() {
|
||||
@@ -3,11 +3,11 @@
|
||||
|
||||
// Fail-safe functions
|
||||
|
||||
#include "config.h"
|
||||
#include "flix.h"
|
||||
|
||||
extern float controlTime;
|
||||
extern const int AUTO, STAB;
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
|
||||
|
||||
float rcLossTimeout = 1;
|
||||
float descendTime = 10;
|
||||
|
||||
void failsafe() {
|
||||
rcLossFailsafe();
|
||||
@@ -16,9 +16,8 @@ void failsafe() {
|
||||
|
||||
// RC loss failsafe
|
||||
void rcLossFailsafe() {
|
||||
if (controlTime == 0) return; // no RC at all
|
||||
if (!armed) return;
|
||||
if (t - controlTime > RC_LOSS_TIMEOUT) {
|
||||
if (t - controlTime > rcLossTimeout) {
|
||||
descend();
|
||||
}
|
||||
}
|
||||
@@ -27,7 +26,7 @@ void rcLossFailsafe() {
|
||||
void descend() {
|
||||
mode = AUTO;
|
||||
attitudeTarget = Quaternion();
|
||||
thrustTarget -= dt / DESCEND_TIME;
|
||||
thrustTarget -= dt / descendTime;
|
||||
if (thrustTarget < 0) {
|
||||
thrustTarget = 0;
|
||||
armed = false;
|
||||
@@ -3,9 +3,6 @@
|
||||
|
||||
// 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
|
||||
14
flix/util.h
14
flix/util.h
@@ -8,24 +8,24 @@
|
||||
#include <math.h>
|
||||
#include <soc/soc.h>
|
||||
#include <soc/rtc_cntl_reg.h>
|
||||
#include "flix.h"
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
inline bool invalid(float x) {
|
||||
bool invalid(float x) {
|
||||
return !isfinite(x);
|
||||
}
|
||||
|
||||
inline bool valid(float x) {
|
||||
bool valid(float x) {
|
||||
return isfinite(x);
|
||||
}
|
||||
|
||||
// Wrap angle to [-PI, PI)
|
||||
inline float wrapAngle(float angle) {
|
||||
float wrapAngle(float angle) {
|
||||
angle = fmodf(angle, 2 * PI);
|
||||
if (angle > PI) {
|
||||
angle -= 2 * PI;
|
||||
@@ -36,12 +36,12 @@ inline float wrapAngle(float angle) {
|
||||
}
|
||||
|
||||
// Disable reset on low voltage
|
||||
inline void disableBrownOut() {
|
||||
void disableBrownOut() {
|
||||
REG_CLR_BIT(RTC_CNTL_BROWN_OUT_REG, RTC_CNTL_BROWN_OUT_ENA);
|
||||
}
|
||||
|
||||
// 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();
|
||||
char chars[str.length() + 1];
|
||||
str.toCharArray(chars, str.length() + 1);
|
||||
|
||||
@@ -5,8 +5,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
class Vector : public Printable {
|
||||
public:
|
||||
float x, y, z;
|
||||
@@ -125,5 +123,5 @@ public:
|
||||
}
|
||||
};
|
||||
|
||||
inline 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; }
|
||||
Vector operator + (const float a, const Vector& b) { return b + a; }
|
||||
|
||||
@@ -1,48 +0,0 @@
|
||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// Wi-Fi support
|
||||
|
||||
#include "config.h"
|
||||
#include "flix.h"
|
||||
|
||||
#if WIFI_ENABLED
|
||||
|
||||
#include <WiFi.h>
|
||||
#include <WiFiAP.h>
|
||||
#include <WiFiUdp.h>
|
||||
|
||||
WiFiUDP udp;
|
||||
|
||||
extern bool mavlinkConnected;
|
||||
|
||||
void setupWiFi() {
|
||||
print("Setup Wi-Fi\n");
|
||||
WiFi.softAP(WIFI_SSID, WIFI_PASSWORD);
|
||||
udp.begin(WIFI_UDP_PORT);
|
||||
}
|
||||
|
||||
void sendWiFi(const uint8_t *buf, int len) {
|
||||
if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return;
|
||||
udp.beginPacket(udp.remoteIP() ? udp.remoteIP() : WIFI_UDP_REMOTE_ADDR, WIFI_UDP_REMOTE_PORT);
|
||||
udp.write(buf, len);
|
||||
udp.endPacket();
|
||||
}
|
||||
|
||||
int receiveWiFi(uint8_t *buf, int len) {
|
||||
udp.parsePacket();
|
||||
return udp.read(buf, len);
|
||||
}
|
||||
|
||||
void printWiFiInfo() {
|
||||
print("MAC: %s\n", WiFi.softAPmacAddress().c_str());
|
||||
print("SSID: %s\n", WiFi.softAPSSID().c_str());
|
||||
print("Password: %s\n", WIFI_PASSWORD);
|
||||
print("Clients: %d\n", WiFi.softAPgetStationNum());
|
||||
print("Status: %d\n", WiFi.status());
|
||||
print("IP: %s\n", WiFi.softAPIP().toString().c_str());
|
||||
print("Remote IP: %s\n", udp.remoteIP().toString().c_str());
|
||||
print("MAVLink connected: %d\n", mavlinkConnected);
|
||||
}
|
||||
|
||||
#endif
|
||||
76
flix/wifi.ino
Normal file
76
flix/wifi.ino
Normal file
@@ -0,0 +1,76 @@
|
||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||
// Repository: https://github.com/okalachev/flix
|
||||
|
||||
// Wi-Fi communication
|
||||
|
||||
#include <WiFi.h>
|
||||
#include <WiFiAP.h>
|
||||
#include <WiFiUdp.h>
|
||||
#include "Preferences.h"
|
||||
|
||||
extern Preferences storage; // use the main preferences storage
|
||||
|
||||
const int W_DISABLED = 0, W_AP = 1, W_STA = 2;
|
||||
int wifiMode = W_AP;
|
||||
int udpLocalPort = 14550;
|
||||
int udpRemotePort = 14550;
|
||||
IPAddress udpRemoteIP = "255.255.255.255";
|
||||
|
||||
WiFiUDP udp;
|
||||
|
||||
void setupWiFi() {
|
||||
print("Setup Wi-Fi\n");
|
||||
if (wifiMode == W_AP) {
|
||||
WiFi.softAP(storage.getString("WIFI_AP_SSID", "flix").c_str(), storage.getString("WIFI_AP_PASS", "flixwifi").c_str());
|
||||
} else if (wifiMode == W_STA) {
|
||||
WiFi.begin(storage.getString("WIFI_STA_SSID", "").c_str(), storage.getString("WIFI_STA_PASS", "").c_str());
|
||||
}
|
||||
udp.begin(udpLocalPort);
|
||||
}
|
||||
|
||||
void sendWiFi(const uint8_t *buf, int len) {
|
||||
if (WiFi.softAPgetStationNum() == 0 && !WiFi.isConnected()) return;
|
||||
udp.beginPacket(udpRemoteIP, udpRemotePort);
|
||||
udp.write(buf, len);
|
||||
udp.endPacket();
|
||||
}
|
||||
|
||||
int receiveWiFi(uint8_t *buf, int len) {
|
||||
udp.parsePacket();
|
||||
if (udp.remoteIP()) udpRemoteIP = udp.remoteIP();
|
||||
return udp.read(buf, len);
|
||||
}
|
||||
|
||||
void printWiFiInfo() {
|
||||
if (WiFi.getMode() == WIFI_MODE_AP) {
|
||||
print("Mode: Access Point (AP)\n");
|
||||
print("MAC: %s\n", WiFi.softAPmacAddress().c_str());
|
||||
print("SSID: %s\n", WiFi.softAPSSID().c_str());
|
||||
print("Password: ***\n");
|
||||
print("Clients: %d\n", WiFi.softAPgetStationNum());
|
||||
print("IP: %s\n", WiFi.softAPIP().toString().c_str());
|
||||
} else if (WiFi.getMode() == WIFI_MODE_STA) {
|
||||
print("Mode: Client (STA)\n");
|
||||
print("Connected: %d\n", WiFi.isConnected());
|
||||
print("MAC: %s\n", WiFi.macAddress().c_str());
|
||||
print("SSID: %s\n", WiFi.SSID().c_str());
|
||||
print("Password: ***\n");
|
||||
print("IP: %s\n", WiFi.localIP().toString().c_str());
|
||||
} else {
|
||||
print("Mode: Disabled\n");
|
||||
return;
|
||||
}
|
||||
print("Remote IP: %s\n", udpRemoteIP.toString().c_str());
|
||||
print("MAVLink connected: %d\n", mavlinkConnected);
|
||||
}
|
||||
|
||||
void configWiFi(bool ap, const char *ssid, const char *password) {
|
||||
if (ap) {
|
||||
storage.putString("WIFI_AP_SSID", ssid);
|
||||
storage.putString("WIFI_AP_PASS", password);
|
||||
} else {
|
||||
storage.putString("WIFI_STA_SSID", ssid);
|
||||
storage.putString("WIFI_STA_PASS", password);
|
||||
}
|
||||
print("✓ Reboot to apply new settings\n");
|
||||
}
|
||||
@@ -10,8 +10,6 @@
|
||||
#include "Arduino.h"
|
||||
#include "wifi.h"
|
||||
|
||||
#define WIFI_ENABLED 1
|
||||
|
||||
extern float t, dt;
|
||||
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
||||
extern Vector rates;
|
||||
@@ -73,3 +71,4 @@ void calibrateAccel() { print("Skip accel calibrating\n"); };
|
||||
void printIMUCalibration() { print("cal: N/A\n"); };
|
||||
void printIMUInfo() {};
|
||||
void printWiFiInfo() {};
|
||||
void configWiFi(bool, const char*, const char*) { print("Skip WiFi config\n"); };
|
||||
|
||||
@@ -43,6 +43,7 @@ records = [record for record in records if record[0] != 0]
|
||||
|
||||
print(f'Received records: {len(records)}')
|
||||
|
||||
os.makedirs(f'{DIR}/log', exist_ok=True)
|
||||
log = open(f'{DIR}/log/{datetime.datetime.now().isoformat()}.csv', 'wb')
|
||||
log.write(header.encode() + b'\n')
|
||||
for record in records:
|
||||
|
||||
Reference in New Issue
Block a user