mirror of
https://github.com/okalachev/flix.git
synced 2026-03-29 19:43:31 +00:00
Compare commits
7 Commits
a6bad3a69b
...
5b654e4d8e
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
5b654e4d8e | ||
|
|
cf10ec6161 | ||
|
|
6d01cd2e79 | ||
|
|
0abb18c616 | ||
|
|
30326a5662 | ||
|
|
dd3575174b | ||
|
|
c0f3301da4 |
2
.github/workflows/build.yml
vendored
2
.github/workflows/build.yml
vendored
@@ -25,8 +25,6 @@ jobs:
|
|||||||
path: flix/build
|
path: flix/build
|
||||||
- name: Build firmware for ESP32-S3
|
- name: Build firmware for ESP32-S3
|
||||||
run: make BOARD=esp32:esp32:esp32s3
|
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: Check c_cpp_properties.json
|
- name: Check c_cpp_properties.json
|
||||||
run: tools/check_c_cpp_properties.py
|
run: tools/check_c_cpp_properties.py
|
||||||
|
|
||||||
|
|||||||
@@ -7,6 +7,7 @@
|
|||||||
"MD024": false,
|
"MD024": false,
|
||||||
"MD033": false,
|
"MD033": false,
|
||||||
"MD034": false,
|
"MD034": false,
|
||||||
|
"MD040": false,
|
||||||
"MD059": false,
|
"MD059": false,
|
||||||
"MD044": {
|
"MD044": {
|
||||||
"html_elements": false,
|
"html_elements": false,
|
||||||
|
|||||||
54
.vscode/c_cpp_properties.json
vendored
54
.vscode/c_cpp_properties.json
vendored
@@ -6,19 +6,18 @@
|
|||||||
"${workspaceFolder}/flix",
|
"${workspaceFolder}/flix",
|
||||||
"${workspaceFolder}/gazebo",
|
"${workspaceFolder}/gazebo",
|
||||||
"${workspaceFolder}/tools/**",
|
"${workspaceFolder}/tools/**",
|
||||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
|
||||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
|
||||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/variants/d1_mini32",
|
||||||
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/**",
|
"~/.arduino15/packages/esp32/tools/esp32-libs/3.3.6/include/**",
|
||||||
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
|
||||||
"~/Arduino/libraries/**",
|
"~/Arduino/libraries/**",
|
||||||
"/usr/include/gazebo-11/",
|
"/usr/include/gazebo-11/",
|
||||||
"/usr/include/ignition/math6/"
|
"/usr/include/ignition/math6/"
|
||||||
],
|
],
|
||||||
"forcedInclude": [
|
"forcedInclude": [
|
||||||
"${workspaceFolder}/.vscode/intellisense.h",
|
"${workspaceFolder}/.vscode/intellisense.h",
|
||||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
|
"~/.arduino15/packages/esp32/hardware/esp32/3.3.6/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/variants/d1_mini32/pins_arduino.h",
|
||||||
"${workspaceFolder}/flix/cli.ino",
|
"${workspaceFolder}/flix/cli.ino",
|
||||||
"${workspaceFolder}/flix/control.ino",
|
"${workspaceFolder}/flix/control.ino",
|
||||||
"${workspaceFolder}/flix/estimate.ino",
|
"${workspaceFolder}/flix/estimate.ino",
|
||||||
@@ -31,9 +30,10 @@
|
|||||||
"${workspaceFolder}/flix/rc.ino",
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
"${workspaceFolder}/flix/time.ino",
|
"${workspaceFolder}/flix/time.ino",
|
||||||
"${workspaceFolder}/flix/wifi.ino",
|
"${workspaceFolder}/flix/wifi.ino",
|
||||||
"${workspaceFolder}/flix/parameters.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",
|
"cStandard": "c11",
|
||||||
"cppStandard": "c++17",
|
"cppStandard": "c++17",
|
||||||
"defines": [
|
"defines": [
|
||||||
@@ -53,19 +53,18 @@
|
|||||||
"name": "Mac",
|
"name": "Mac",
|
||||||
"includePath": [
|
"includePath": [
|
||||||
"${workspaceFolder}/flix",
|
"${workspaceFolder}/flix",
|
||||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
|
||||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
|
||||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/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-libs/3.3.6/include/**",
|
||||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
|
||||||
"~/Documents/Arduino/libraries/**",
|
"~/Documents/Arduino/libraries/**",
|
||||||
"/opt/homebrew/include/gazebo-11/",
|
"/opt/homebrew/include/gazebo-11/",
|
||||||
"/opt/homebrew/include/ignition/math6/"
|
"/opt/homebrew/include/ignition/math6/"
|
||||||
],
|
],
|
||||||
"forcedInclude": [
|
"forcedInclude": [
|
||||||
"${workspaceFolder}/.vscode/intellisense.h",
|
"${workspaceFolder}/.vscode/intellisense.h",
|
||||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
|
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.3.6/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/variants/d1_mini32/pins_arduino.h",
|
||||||
"${workspaceFolder}/flix/flix.ino",
|
"${workspaceFolder}/flix/flix.ino",
|
||||||
"${workspaceFolder}/flix/cli.ino",
|
"${workspaceFolder}/flix/cli.ino",
|
||||||
"${workspaceFolder}/flix/control.ino",
|
"${workspaceFolder}/flix/control.ino",
|
||||||
@@ -78,9 +77,10 @@
|
|||||||
"${workspaceFolder}/flix/rc.ino",
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
"${workspaceFolder}/flix/time.ino",
|
"${workspaceFolder}/flix/time.ino",
|
||||||
"${workspaceFolder}/flix/wifi.ino",
|
"${workspaceFolder}/flix/wifi.ino",
|
||||||
"${workspaceFolder}/flix/parameters.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",
|
"cStandard": "c11",
|
||||||
"cppStandard": "c++17",
|
"cppStandard": "c++17",
|
||||||
"defines": [
|
"defines": [
|
||||||
@@ -103,17 +103,16 @@
|
|||||||
"${workspaceFolder}/flix",
|
"${workspaceFolder}/flix",
|
||||||
"${workspaceFolder}/gazebo",
|
"${workspaceFolder}/gazebo",
|
||||||
"${workspaceFolder}/tools/**",
|
"${workspaceFolder}/tools/**",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/cores/esp32",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/libraries/**",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/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-libs/3.3.6/include/**",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
|
||||||
"~/Documents/Arduino/libraries/**"
|
"~/Documents/Arduino/libraries/**"
|
||||||
],
|
],
|
||||||
"forcedInclude": [
|
"forcedInclude": [
|
||||||
"${workspaceFolder}/.vscode/intellisense.h",
|
"${workspaceFolder}/.vscode/intellisense.h",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32/Arduino.h",
|
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.3.6/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/variants/d1_mini32/pins_arduino.h",
|
||||||
"${workspaceFolder}/flix/cli.ino",
|
"${workspaceFolder}/flix/cli.ino",
|
||||||
"${workspaceFolder}/flix/control.ino",
|
"${workspaceFolder}/flix/control.ino",
|
||||||
"${workspaceFolder}/flix/estimate.ino",
|
"${workspaceFolder}/flix/estimate.ino",
|
||||||
@@ -126,9 +125,10 @@
|
|||||||
"${workspaceFolder}/flix/rc.ino",
|
"${workspaceFolder}/flix/rc.ino",
|
||||||
"${workspaceFolder}/flix/time.ino",
|
"${workspaceFolder}/flix/time.ino",
|
||||||
"${workspaceFolder}/flix/wifi.ino",
|
"${workspaceFolder}/flix/wifi.ino",
|
||||||
"${workspaceFolder}/flix/parameters.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",
|
"cStandard": "c11",
|
||||||
"cppStandard": "c++17",
|
"cppStandard": "c++17",
|
||||||
"defines": [
|
"defines": [
|
||||||
|
|||||||
4
Makefile
4
Makefile
@@ -13,10 +13,10 @@ monitor:
|
|||||||
|
|
||||||
dependencies .dependencies:
|
dependencies .dependencies:
|
||||||
arduino-cli core update-index --config-file arduino-cli.yaml
|
arduino-cli core update-index --config-file arduino-cli.yaml
|
||||||
arduino-cli core install esp32:esp32@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 update-index
|
||||||
arduino-cli lib install "FlixPeriph"
|
arduino-cli lib install "FlixPeriph"
|
||||||
arduino-cli lib install "MAVLink"@2.0.16
|
arduino-cli lib install "MAVLink"@2.0.25
|
||||||
touch .dependencies
|
touch .dependencies
|
||||||
|
|
||||||
gazebo/build cmake: gazebo/CMakeLists.txt
|
gazebo/build cmake: gazebo/CMakeLists.txt
|
||||||
|
|||||||
@@ -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).
|
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).*
|
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):
|
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.
|
* `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.
|
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.
|
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.
|
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">
|
<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
|
### Define IMU orientation
|
||||||
|
|
||||||
@@ -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.
|
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
|
## 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
|
```bash
|
||||||
make log
|
make log
|
||||||
|
|||||||
12
flix/cli.ino
12
flix/cli.ino
@@ -38,6 +38,8 @@ const char* motd =
|
|||||||
"raw/stab/acro/auto - set mode\n"
|
"raw/stab/acro/auto - set mode\n"
|
||||||
"rc - show RC data\n"
|
"rc - show RC data\n"
|
||||||
"wifi - show Wi-Fi info\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"
|
"mot - show motor output\n"
|
||||||
"log [dump] - print log header [and data]\n"
|
"log [dump] - print log header [and data]\n"
|
||||||
"cr - calibrate RC\n"
|
"cr - calibrate RC\n"
|
||||||
@@ -54,9 +56,7 @@ void print(const char* format, ...) {
|
|||||||
vsnprintf(buf, sizeof(buf), format, args);
|
vsnprintf(buf, sizeof(buf), format, args);
|
||||||
va_end(args);
|
va_end(args);
|
||||||
Serial.print(buf);
|
Serial.print(buf);
|
||||||
#if WIFI_ENABLED
|
|
||||||
mavlinkPrint(buf);
|
mavlinkPrint(buf);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void pause(float duration) {
|
void pause(float duration) {
|
||||||
@@ -64,9 +64,7 @@ void pause(float duration) {
|
|||||||
while (t - start < duration) {
|
while (t - start < duration) {
|
||||||
step();
|
step();
|
||||||
handleInput();
|
handleInput();
|
||||||
#if WIFI_ENABLED
|
|
||||||
processMavlink();
|
processMavlink();
|
||||||
#endif
|
|
||||||
delay(50);
|
delay(50);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -136,9 +134,11 @@ void doCommand(String str, bool echo = false) {
|
|||||||
print("mode: %s\n", getModeName());
|
print("mode: %s\n", getModeName());
|
||||||
print("armed: %d\n", armed);
|
print("armed: %d\n", armed);
|
||||||
} else if (command == "wifi") {
|
} else if (command == "wifi") {
|
||||||
#if WIFI_ENABLED
|
|
||||||
printWiFiInfo();
|
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") {
|
} else if (command == "mot") {
|
||||||
print("front-right %g front-left %g rear-right %g rear-left %g\n",
|
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]);
|
motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]);
|
||||||
|
|||||||
@@ -7,7 +7,6 @@
|
|||||||
#include "quaternion.h"
|
#include "quaternion.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
#define WIFI_ENABLED 1
|
|
||||||
|
|
||||||
extern float t, dt;
|
extern float t, dt;
|
||||||
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
||||||
@@ -25,9 +24,7 @@ void setup() {
|
|||||||
setupLED();
|
setupLED();
|
||||||
setupMotors();
|
setupMotors();
|
||||||
setLED(true);
|
setLED(true);
|
||||||
#if WIFI_ENABLED
|
|
||||||
setupWiFi();
|
setupWiFi();
|
||||||
#endif
|
|
||||||
setupIMU();
|
setupIMU();
|
||||||
setupRC();
|
setupRC();
|
||||||
setLED(false);
|
setLED(false);
|
||||||
@@ -42,9 +39,7 @@ void loop() {
|
|||||||
control();
|
control();
|
||||||
sendMotors();
|
sendMotors();
|
||||||
handleInput();
|
handleInput();
|
||||||
#if WIFI_ENABLED
|
|
||||||
processMavlink();
|
processMavlink();
|
||||||
#endif
|
|
||||||
logData();
|
logData();
|
||||||
syncParameters();
|
syncParameters();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -3,19 +3,16 @@
|
|||||||
|
|
||||||
// MAVLink communication
|
// MAVLink communication
|
||||||
|
|
||||||
#if WIFI_ENABLED
|
|
||||||
|
|
||||||
#include <MAVLink.h>
|
#include <MAVLink.h>
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
#define SYSTEM_ID 1
|
|
||||||
#define MAVLINK_RATE_SLOW 1
|
|
||||||
#define MAVLINK_RATE_FAST 10
|
|
||||||
|
|
||||||
extern float controlTime;
|
extern float controlTime;
|
||||||
|
|
||||||
bool mavlinkConnected = false;
|
bool mavlinkConnected = false;
|
||||||
String mavlinkPrintBuffer;
|
String mavlinkPrintBuffer;
|
||||||
|
int mavlinkSysId = 1;
|
||||||
|
Rate telemetryFast(10);
|
||||||
|
Rate telemetrySlow(2);
|
||||||
|
|
||||||
void processMavlink() {
|
void processMavlink() {
|
||||||
sendMavlink();
|
sendMavlink();
|
||||||
@@ -28,10 +25,8 @@ void sendMavlink() {
|
|||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
uint32_t time = t * 1000;
|
uint32_t time = t * 1000;
|
||||||
|
|
||||||
static Rate slow(MAVLINK_RATE_SLOW), fast(MAVLINK_RATE_FAST);
|
if (telemetrySlow) {
|
||||||
|
mavlink_msg_heartbeat_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC,
|
||||||
if (slow) {
|
|
||||||
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 : 0) |
|
||||||
((mode == STAB) ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0) |
|
((mode == STAB) ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0) |
|
||||||
((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),
|
||||||
@@ -40,27 +35,27 @@ void sendMavlink() {
|
|||||||
|
|
||||||
if (!mavlinkConnected) return; // send only heartbeat until connected
|
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);
|
MAV_VTOL_STATE_UNDEFINED, landed ? MAV_LANDED_STATE_ON_GROUND : MAV_LANDED_STATE_IN_AIR);
|
||||||
sendMessage(&msg);
|
sendMessage(&msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (fast && mavlinkConnected) {
|
if (telemetryFast && mavlinkConnected) {
|
||||||
const float zeroQuat[] = {0, 0, 0, 0};
|
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
|
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd
|
||||||
sendMessage(&msg);
|
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);
|
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
|
if (channels[0] != 0) sendMessage(&msg); // 0 means no RC input
|
||||||
|
|
||||||
float controls[8];
|
float controls[8];
|
||||||
memcpy(controls, motors, sizeof(motors));
|
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);
|
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
|
acc.x * 1000, -acc.y * 1000, -acc.z * 1000, // convert to frd
|
||||||
gyro.x * 1000, -gyro.y * 1000, -gyro.z * 1000,
|
gyro.x * 1000, -gyro.y * 1000, -gyro.z * 1000,
|
||||||
0, 0, 0, 0);
|
0, 0, 0, 0);
|
||||||
@@ -95,7 +90,7 @@ void handleMavlink(const void *_msg) {
|
|||||||
if (msg.msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
|
if (msg.msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
|
||||||
mavlink_manual_control_t m;
|
mavlink_manual_control_t m;
|
||||||
mavlink_msg_manual_control_decode(&msg, &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;
|
controlThrottle = m.z / 1000.0f;
|
||||||
controlPitch = m.x / 1000.0f;
|
controlPitch = m.x / 1000.0f;
|
||||||
@@ -108,11 +103,11 @@ void handleMavlink(const void *_msg) {
|
|||||||
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
|
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
|
||||||
mavlink_param_request_list_t m;
|
mavlink_param_request_list_t m;
|
||||||
mavlink_msg_param_request_list_decode(&msg, &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;
|
mavlink_message_t msg;
|
||||||
for (int i = 0; i < parametersCount(); i++) {
|
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);
|
getParameterName(i), getParameter(i), MAV_PARAM_TYPE_REAL32, parametersCount(), i);
|
||||||
sendMessage(&msg);
|
sendMessage(&msg);
|
||||||
}
|
}
|
||||||
@@ -121,7 +116,7 @@ void handleMavlink(const void *_msg) {
|
|||||||
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_READ) {
|
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_READ) {
|
||||||
mavlink_param_request_read_t m;
|
mavlink_param_request_read_t m;
|
||||||
mavlink_msg_param_request_read_decode(&msg, &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];
|
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
|
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
|
||||||
@@ -130,7 +125,7 @@ void handleMavlink(const void *_msg) {
|
|||||||
memcpy(name, getParameterName(m.param_index), 16);
|
memcpy(name, getParameterName(m.param_index), 16);
|
||||||
}
|
}
|
||||||
mavlink_message_t msg;
|
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);
|
name, value, MAV_PARAM_TYPE_REAL32, parametersCount(), m.param_index);
|
||||||
sendMessage(&msg);
|
sendMessage(&msg);
|
||||||
}
|
}
|
||||||
@@ -138,14 +133,15 @@ void handleMavlink(const void *_msg) {
|
|||||||
if (msg.msgid == MAVLINK_MSG_ID_PARAM_SET) {
|
if (msg.msgid == MAVLINK_MSG_ID_PARAM_SET) {
|
||||||
mavlink_param_set_t m;
|
mavlink_param_set_t m;
|
||||||
mavlink_msg_param_set_decode(&msg, &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];
|
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
|
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
|
// send ack
|
||||||
mavlink_message_t msg;
|
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
|
m.param_id, m.param_value, MAV_PARAM_TYPE_REAL32, parametersCount(), 0); // index is unknown
|
||||||
sendMessage(&msg);
|
sendMessage(&msg);
|
||||||
}
|
}
|
||||||
@@ -153,17 +149,17 @@ void handleMavlink(const void *_msg) {
|
|||||||
if (msg.msgid == MAVLINK_MSG_ID_MISSION_REQUEST_LIST) { // handle to make qgc happy
|
if (msg.msgid == MAVLINK_MSG_ID_MISSION_REQUEST_LIST) { // handle to make qgc happy
|
||||||
mavlink_mission_request_list_t m;
|
mavlink_mission_request_list_t m;
|
||||||
mavlink_msg_mission_request_list_decode(&msg, &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_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);
|
sendMessage(&msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (msg.msgid == MAVLINK_MSG_ID_SERIAL_CONTROL) {
|
if (msg.msgid == MAVLINK_MSG_ID_SERIAL_CONTROL) {
|
||||||
mavlink_serial_control_t m;
|
mavlink_serial_control_t m;
|
||||||
mavlink_msg_serial_control_decode(&msg, &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];
|
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
|
||||||
strlcpy(data, (const char *)m.data, m.count); // data might be not null-terminated
|
strlcpy(data, (const char *)m.data, m.count); // data might be not null-terminated
|
||||||
@@ -175,7 +171,7 @@ void handleMavlink(const void *_msg) {
|
|||||||
|
|
||||||
mavlink_set_attitude_target_t m;
|
mavlink_set_attitude_target_t m;
|
||||||
mavlink_msg_set_attitude_target_decode(&msg, &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
|
// copy attitude, rates and thrust targets
|
||||||
ratesTarget.x = m.body_roll_rate;
|
ratesTarget.x = m.body_roll_rate;
|
||||||
@@ -197,7 +193,7 @@ void handleMavlink(const void *_msg) {
|
|||||||
|
|
||||||
mavlink_set_actuator_control_target_t m;
|
mavlink_set_actuator_control_target_t m;
|
||||||
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 != mavlinkSysId) return;
|
||||||
|
|
||||||
attitudeTarget.invalidate();
|
attitudeTarget.invalidate();
|
||||||
ratesTarget.invalidate();
|
ratesTarget.invalidate();
|
||||||
@@ -209,12 +205,12 @@ void handleMavlink(const void *_msg) {
|
|||||||
if (msg.msgid == MAVLINK_MSG_ID_LOG_REQUEST_DATA) {
|
if (msg.msgid == MAVLINK_MSG_ID_LOG_REQUEST_DATA) {
|
||||||
mavlink_log_request_data_t m;
|
mavlink_log_request_data_t m;
|
||||||
mavlink_msg_log_request_data_decode(&msg, &m);
|
mavlink_msg_log_request_data_decode(&msg, &m);
|
||||||
if (m.target_system && m.target_system != SYSTEM_ID) return;
|
if (m.target_system && m.target_system != mavlinkSysId) return;
|
||||||
|
|
||||||
// Send all log records
|
// Send all log records
|
||||||
for (int i = 0; i < sizeof(logBuffer) / sizeof(logBuffer[0]); i++) {
|
for (int i = 0; i < sizeof(logBuffer) / sizeof(logBuffer[0]); i++) {
|
||||||
mavlink_message_t msg;
|
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]);
|
sizeof(logBuffer[0]), (uint8_t *)logBuffer[i]);
|
||||||
sendMessage(&msg);
|
sendMessage(&msg);
|
||||||
}
|
}
|
||||||
@@ -224,13 +220,13 @@ void handleMavlink(const void *_msg) {
|
|||||||
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
|
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
|
||||||
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 != mavlinkSysId) return;
|
||||||
mavlink_message_t response;
|
mavlink_message_t response;
|
||||||
bool accepted = false;
|
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;
|
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);
|
MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_MAVLINK2, 1, 0, 1, 1, 0, 0, 0, 0, 0, 0, 0);
|
||||||
sendMessage(&response);
|
sendMessage(&response);
|
||||||
}
|
}
|
||||||
@@ -249,7 +245,7 @@ void handleMavlink(const void *_msg) {
|
|||||||
|
|
||||||
// send command ack
|
// send command ack
|
||||||
mavlink_message_t 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);
|
sendMessage(&ack);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -266,7 +262,7 @@ void sendMavlinkPrint() {
|
|||||||
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
|
char data[MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN + 1];
|
||||||
strlcpy(data, str + i, sizeof(data));
|
strlcpy(data, str + i, sizeof(data));
|
||||||
mavlink_message_t msg;
|
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,
|
SERIAL_CONTROL_DEV_SHELL,
|
||||||
i + MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN < strlen(str) ? SERIAL_CONTROL_FLAG_MULTI : 0, // more chunks to go
|
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);
|
0, 0, strlen(data), (uint8_t *)data, 0, 0);
|
||||||
@@ -274,5 +270,3 @@ void sendMavlinkPrint() {
|
|||||||
}
|
}
|
||||||
mavlinkPrintBuffer.clear();
|
mavlinkPrintBuffer.clear();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|||||||
@@ -9,13 +9,20 @@
|
|||||||
extern float channelZero[16];
|
extern float channelZero[16];
|
||||||
extern float channelMax[16];
|
extern float channelMax[16];
|
||||||
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
||||||
|
extern int wifiMode, udpLocalPort, udpRemotePort;
|
||||||
|
extern float rcLossTimeout, descendTime;
|
||||||
|
|
||||||
Preferences storage;
|
Preferences storage;
|
||||||
|
|
||||||
struct Parameter {
|
struct Parameter {
|
||||||
const char *name; // max length is 15 (Preferences key limit)
|
const char *name; // max length is 15 (Preferences key limit)
|
||||||
float *variable;
|
bool integer;
|
||||||
float value; // cache
|
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[] = {
|
Parameter parameters[] = {
|
||||||
@@ -77,6 +84,17 @@ Parameter parameters[] = {
|
|||||||
{"RC_THROTTLE", &throttleChannel},
|
{"RC_THROTTLE", &throttleChannel},
|
||||||
{"RC_YAW", &yawChannel},
|
{"RC_YAW", &yawChannel},
|
||||||
{"RC_MODE", &modeChannel},
|
{"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() {
|
void setupParameters() {
|
||||||
@@ -84,10 +102,10 @@ void setupParameters() {
|
|||||||
// Read parameters from storage
|
// Read parameters from storage
|
||||||
for (auto ¶meter : parameters) {
|
for (auto ¶meter : parameters) {
|
||||||
if (!storage.isKey(parameter.name)) {
|
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.setValue(storage.getFloat(parameter.name, 0));
|
||||||
parameter.value = *parameter.variable;
|
parameter.cache = parameter.getValue();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -102,13 +120,13 @@ const char *getParameterName(int index) {
|
|||||||
|
|
||||||
float getParameter(int index) {
|
float getParameter(int index) {
|
||||||
if (index < 0 || index >= parametersCount()) return NAN;
|
if (index < 0 || index >= parametersCount()) return NAN;
|
||||||
return *parameters[index].variable;
|
return parameters[index].getValue();
|
||||||
}
|
}
|
||||||
|
|
||||||
float getParameter(const char *name) {
|
float getParameter(const char *name) {
|
||||||
for (auto ¶meter : parameters) {
|
for (auto ¶meter : parameters) {
|
||||||
if (strcmp(parameter.name, name) == 0) {
|
if (strcasecmp(parameter.name, name) == 0) {
|
||||||
return *parameter.variable;
|
return parameter.getValue();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return NAN;
|
return NAN;
|
||||||
@@ -116,8 +134,9 @@ float getParameter(const char *name) {
|
|||||||
|
|
||||||
bool setParameter(const char *name, const float value) {
|
bool setParameter(const char *name, const float value) {
|
||||||
for (auto ¶meter : parameters) {
|
for (auto ¶meter : parameters) {
|
||||||
if (strcmp(parameter.name, name) == 0) {
|
if (strcasecmp(parameter.name, name) == 0) {
|
||||||
*parameter.variable = value;
|
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
|
||||||
|
parameter.setValue(value);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -130,16 +149,18 @@ void syncParameters() {
|
|||||||
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
|
if (motorsActive()) return; // don't use flash while flying, it may cause a delay
|
||||||
|
|
||||||
for (auto ¶meter : parameters) {
|
for (auto ¶meter : parameters) {
|
||||||
if (parameter.value == *parameter.variable) continue;
|
if (parameter.getValue() == parameter.cache) continue; // no change
|
||||||
if (isnan(parameter.value) && isnan(*parameter.variable)) continue; // handle NAN != NAN
|
if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NaN
|
||||||
storage.putFloat(parameter.name, *parameter.variable);
|
if (isinf(parameter.getValue()) && isinf(parameter.cache)) continue; // both are Inf
|
||||||
parameter.value = *parameter.variable;
|
|
||||||
|
storage.putFloat(parameter.name, parameter.getValue());
|
||||||
|
parameter.cache = parameter.getValue(); // update cache
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void printParameters() {
|
void printParameters() {
|
||||||
for (auto ¶meter : parameters) {
|
for (auto ¶meter : parameters) {
|
||||||
print("%s = %g\n", parameter.name, *parameter.variable);
|
print("%s = %g\n", parameter.name, parameter.getValue());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -13,10 +13,10 @@ float channelZero[16]; // calibration zero values
|
|||||||
float channelMax[16]; // calibration max values
|
float channelMax[16]; // calibration max values
|
||||||
|
|
||||||
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
|
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
|
||||||
float controlMode = NAN; //
|
float controlMode = NAN;
|
||||||
float controlTime; // time of the last controls update (0 when no RC)
|
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;
|
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
|
||||||
|
|
||||||
void setupRC() {
|
void setupRC() {
|
||||||
|
|||||||
@@ -3,12 +3,12 @@
|
|||||||
|
|
||||||
// Fail-safe functions
|
// Fail-safe functions
|
||||||
|
|
||||||
#define RC_LOSS_TIMEOUT 1
|
|
||||||
#define DESCEND_TIME 10
|
|
||||||
|
|
||||||
extern float controlTime;
|
extern float controlTime;
|
||||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
|
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
|
||||||
|
|
||||||
|
float rcLossTimeout = 1;
|
||||||
|
float descendTime = 10;
|
||||||
|
|
||||||
void failsafe() {
|
void failsafe() {
|
||||||
rcLossFailsafe();
|
rcLossFailsafe();
|
||||||
autoFailsafe();
|
autoFailsafe();
|
||||||
@@ -16,9 +16,8 @@ void failsafe() {
|
|||||||
|
|
||||||
// RC loss failsafe
|
// RC loss failsafe
|
||||||
void rcLossFailsafe() {
|
void rcLossFailsafe() {
|
||||||
if (controlTime == 0) return; // no RC at all
|
|
||||||
if (!armed) return;
|
if (!armed) return;
|
||||||
if (t - controlTime > RC_LOSS_TIMEOUT) {
|
if (t - controlTime > rcLossTimeout) {
|
||||||
descend();
|
descend();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -27,7 +26,7 @@ void rcLossFailsafe() {
|
|||||||
void descend() {
|
void descend() {
|
||||||
mode = AUTO;
|
mode = AUTO;
|
||||||
attitudeTarget = Quaternion();
|
attitudeTarget = Quaternion();
|
||||||
thrustTarget -= dt / DESCEND_TIME;
|
thrustTarget -= dt / descendTime;
|
||||||
if (thrustTarget < 0) {
|
if (thrustTarget < 0) {
|
||||||
thrustTarget = 0;
|
thrustTarget = 0;
|
||||||
armed = false;
|
armed = false;
|
||||||
|
|||||||
@@ -1,49 +1,76 @@
|
|||||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||||
// Repository: https://github.com/okalachev/flix
|
// Repository: https://github.com/okalachev/flix
|
||||||
|
|
||||||
// Wi-Fi support
|
// Wi-Fi communication
|
||||||
|
|
||||||
#if WIFI_ENABLED
|
|
||||||
|
|
||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
#include <WiFiAP.h>
|
#include <WiFiAP.h>
|
||||||
#include <WiFiUdp.h>
|
#include <WiFiUdp.h>
|
||||||
|
#include "Preferences.h"
|
||||||
|
|
||||||
#define WIFI_SSID "flix"
|
extern Preferences storage; // use the main preferences storage
|
||||||
#define WIFI_PASSWORD "flixwifi"
|
|
||||||
#define WIFI_UDP_PORT 14550
|
const int W_DISABLED = 0, W_AP = 1, W_STA = 2;
|
||||||
#define WIFI_UDP_REMOTE_PORT 14550
|
int wifiMode = W_AP;
|
||||||
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
|
int udpLocalPort = 14550;
|
||||||
|
int udpRemotePort = 14550;
|
||||||
|
IPAddress udpRemoteIP = "255.255.255.255";
|
||||||
|
|
||||||
WiFiUDP udp;
|
WiFiUDP udp;
|
||||||
|
|
||||||
void setupWiFi() {
|
void setupWiFi() {
|
||||||
print("Setup Wi-Fi\n");
|
print("Setup Wi-Fi\n");
|
||||||
WiFi.softAP(WIFI_SSID, WIFI_PASSWORD);
|
if (wifiMode == W_AP) {
|
||||||
udp.begin(WIFI_UDP_PORT);
|
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) {
|
void sendWiFi(const uint8_t *buf, int len) {
|
||||||
if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return;
|
if (WiFi.softAPgetStationNum() == 0 && !WiFi.isConnected()) return;
|
||||||
udp.beginPacket(udp.remoteIP() ? udp.remoteIP() : WIFI_UDP_REMOTE_ADDR, WIFI_UDP_REMOTE_PORT);
|
udp.beginPacket(udpRemoteIP, udpRemotePort);
|
||||||
udp.write(buf, len);
|
udp.write(buf, len);
|
||||||
udp.endPacket();
|
udp.endPacket();
|
||||||
}
|
}
|
||||||
|
|
||||||
int receiveWiFi(uint8_t *buf, int len) {
|
int receiveWiFi(uint8_t *buf, int len) {
|
||||||
udp.parsePacket();
|
udp.parsePacket();
|
||||||
|
if (udp.remoteIP()) udpRemoteIP = udp.remoteIP();
|
||||||
return udp.read(buf, len);
|
return udp.read(buf, len);
|
||||||
}
|
}
|
||||||
|
|
||||||
void printWiFiInfo() {
|
void printWiFiInfo() {
|
||||||
print("MAC: %s\n", WiFi.softAPmacAddress().c_str());
|
if (WiFi.getMode() == WIFI_MODE_AP) {
|
||||||
print("SSID: %s\n", WiFi.softAPSSID().c_str());
|
print("Mode: Access Point (AP)\n");
|
||||||
print("Password: %s\n", WIFI_PASSWORD);
|
print("MAC: %s\n", WiFi.softAPmacAddress().c_str());
|
||||||
print("Clients: %d\n", WiFi.softAPgetStationNum());
|
print("SSID: %s\n", WiFi.softAPSSID().c_str());
|
||||||
print("Status: %d\n", WiFi.status());
|
print("Password: ***\n");
|
||||||
print("IP: %s\n", WiFi.softAPIP().toString().c_str());
|
print("Clients: %d\n", WiFi.softAPgetStationNum());
|
||||||
print("Remote IP: %s\n", udp.remoteIP().toString().c_str());
|
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);
|
print("MAVLink connected: %d\n", mavlinkConnected);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
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 "Arduino.h"
|
||||||
#include "wifi.h"
|
#include "wifi.h"
|
||||||
|
|
||||||
#define WIFI_ENABLED 1
|
|
||||||
|
|
||||||
extern float t, dt;
|
extern float t, dt;
|
||||||
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
||||||
extern Vector rates;
|
extern Vector rates;
|
||||||
@@ -73,3 +71,4 @@ void calibrateAccel() { print("Skip accel calibrating\n"); };
|
|||||||
void printIMUCalibration() { print("cal: N/A\n"); };
|
void printIMUCalibration() { print("cal: N/A\n"); };
|
||||||
void printIMUInfo() {};
|
void printIMUInfo() {};
|
||||||
void printWiFiInfo() {};
|
void printWiFiInfo() {};
|
||||||
|
void configWiFi(bool, const char*, const char*) { print("Skip WiFi config\n"); };
|
||||||
|
|||||||
Reference in New Issue
Block a user