mirror of
https://github.com/okalachev/flix.git
synced 2026-03-30 03:54:20 +00:00
Compare commits
32 Commits
e88888baeb
...
remove-esp
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
94fe93020d | ||
|
|
7170b20d1d | ||
|
|
dc9aed113b | ||
|
|
08b6123eb7 | ||
|
|
1a8b63ee04 | ||
|
|
8c49a40516 | ||
|
|
ca595edce5 | ||
|
|
d06eb2a1aa | ||
|
|
e50a9d5fea | ||
|
|
ebac78dc0f | ||
|
|
186cf88d84 | ||
|
|
253aae2220 | ||
|
|
6f0964fac4 | ||
|
|
1d034f268d | ||
|
|
1ca7d32862 | ||
|
|
ab941e34fa | ||
|
|
7bee3d1751 | ||
|
|
06ec5f3160 | ||
|
|
c4533e3ac8 | ||
|
|
e673b50f52 | ||
|
|
5151bb9133 | ||
|
|
c08c8ad91c | ||
|
|
e44f32fca7 | ||
|
|
ca03bdb260 | ||
|
|
b3dffe99fb | ||
|
|
6e6a71fa69 | ||
|
|
838fe11f6b | ||
|
|
8b36509932 | ||
|
|
0268c8ebcf | ||
|
|
09bf09e520 | ||
|
|
4c89b10767 | ||
|
|
a79df52959 |
20
.github/workflows/build.yml
vendored
20
.github/workflows/build.yml
vendored
@@ -23,7 +23,9 @@ jobs:
|
|||||||
with:
|
with:
|
||||||
name: firmware-binary
|
name: firmware-binary
|
||||||
path: flix/build
|
path: flix/build
|
||||||
- name: Build firmware without Wi-Fi
|
- 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
|
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
|
||||||
@@ -53,15 +55,25 @@ jobs:
|
|||||||
run: python3 tools/check_c_cpp_properties.py
|
run: python3 tools/check_c_cpp_properties.py
|
||||||
|
|
||||||
build_simulator:
|
build_simulator:
|
||||||
runs-on: ubuntu-22.04
|
runs-on: ubuntu-latest
|
||||||
|
container:
|
||||||
|
image: ubuntu:20.04
|
||||||
steps:
|
steps:
|
||||||
|
- name: Install dependencies
|
||||||
|
run: |
|
||||||
|
apt-get update
|
||||||
|
DEBIAN_FRONTEND=noninteractive apt-get install -y curl wget build-essential cmake g++ pkg-config gnupg2 lsb-release sudo
|
||||||
- name: Install Arduino CLI
|
- name: Install Arduino CLI
|
||||||
uses: arduino/setup-arduino-cli@v1.1.1
|
uses: arduino/setup-arduino-cli@v1.1.1
|
||||||
- uses: actions/checkout@v4
|
- uses: actions/checkout@v4
|
||||||
- name: Install Gazebo
|
- name: Install Gazebo
|
||||||
run: curl -sSL http://get.gazebosim.org | sh
|
run: |
|
||||||
|
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
|
||||||
|
wget https://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
|
||||||
|
sudo apt-get update
|
||||||
|
sudo apt-get install -y gazebo11 libgazebo11-dev
|
||||||
- name: Install SDL2
|
- name: Install SDL2
|
||||||
run: sudo apt-get install libsdl2-dev
|
run: sudo apt-get install -y libsdl2-dev
|
||||||
- name: Build simulator
|
- name: Build simulator
|
||||||
run: make build_simulator
|
run: make build_simulator
|
||||||
- uses: actions/upload-artifact@v4
|
- uses: actions/upload-artifact@v4
|
||||||
|
|||||||
9
.vscode/c_cpp_properties.json
vendored
9
.vscode/c_cpp_properties.json
vendored
@@ -5,13 +5,15 @@
|
|||||||
"includePath": [
|
"includePath": [
|
||||||
"${workspaceFolder}/flix",
|
"${workspaceFolder}/flix",
|
||||||
"${workspaceFolder}/gazebo",
|
"${workspaceFolder}/gazebo",
|
||||||
|
"${workspaceFolder}/tools/**",
|
||||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
"~/.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/libraries/**",
|
||||||
"~/.arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
"~/.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/**",
|
||||||
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
"~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/include",
|
||||||
"~/Arduino/libraries/**",
|
"~/Arduino/libraries/**",
|
||||||
"/usr/include/**"
|
"/usr/include/gazebo-11/",
|
||||||
|
"/usr/include/ignition/math6/"
|
||||||
],
|
],
|
||||||
"forcedInclude": [
|
"forcedInclude": [
|
||||||
"${workspaceFolder}/.vscode/intellisense.h",
|
"${workspaceFolder}/.vscode/intellisense.h",
|
||||||
@@ -51,14 +53,14 @@
|
|||||||
"name": "Mac",
|
"name": "Mac",
|
||||||
"includePath": [
|
"includePath": [
|
||||||
"${workspaceFolder}/flix",
|
"${workspaceFolder}/flix",
|
||||||
// "${workspaceFolder}/gazebo",
|
|
||||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/cores/esp32",
|
"~/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/libraries/**",
|
||||||
"~/Library/Arduino15/packages/esp32/hardware/esp32/3.2.0/variants/d1_mini32",
|
"~/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/include/**",
|
||||||
"~/Library/Arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.4-2f7dcd86-v1/esp32/dio_qspi/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/**"
|
"/opt/homebrew/include/gazebo-11/",
|
||||||
|
"/opt/homebrew/include/ignition/math6/"
|
||||||
],
|
],
|
||||||
"forcedInclude": [
|
"forcedInclude": [
|
||||||
"${workspaceFolder}/.vscode/intellisense.h",
|
"${workspaceFolder}/.vscode/intellisense.h",
|
||||||
@@ -100,6 +102,7 @@
|
|||||||
"includePath": [
|
"includePath": [
|
||||||
"${workspaceFolder}/flix",
|
"${workspaceFolder}/flix",
|
||||||
"${workspaceFolder}/gazebo",
|
"${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/cores/esp32",
|
||||||
"~/AppData/Local/Arduino15/packages/esp32/hardware/esp32/3.2.0/libraries/**",
|
"~/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/hardware/esp32/3.2.0/variants/d1_mini32",
|
||||||
|
|||||||
1
.vscode/settings.json
vendored
1
.vscode/settings.json
vendored
@@ -1,5 +1,6 @@
|
|||||||
{
|
{
|
||||||
"C_Cpp.intelliSenseEngineFallback": "enabled",
|
"C_Cpp.intelliSenseEngineFallback": "enabled",
|
||||||
|
"C_Cpp.errorSquiggles": "disabled",
|
||||||
"files.associations": {
|
"files.associations": {
|
||||||
"*.sdf": "xml",
|
"*.sdf": "xml",
|
||||||
"*.ino": "cpp",
|
"*.ino": "cpp",
|
||||||
|
|||||||
@@ -87,7 +87,7 @@ The simulator is implemented using Gazebo and runs the original Arduino code:
|
|||||||
|Tape, double-sided tape||||
|
|Tape, double-sided tape||||
|
||||||
|
|
||||||
*² — barometer is not used for now.*<br>
|
*² — barometer is not used for now.*<br>
|
||||||
*³ — change `MPU9250` to `ICM20948` in `imu.ino` file if using ICM-20948 board.*<br>
|
*³ — change `MPU9250` to `ICM20948` or `MPU6050` in `imu.ino` file for using the appropriate boards.*<br>
|
||||||
*³⁻¹ — MPU-6050 supports I²C interface only (not recommended). To use it change IMU declaration to `MPU6050 IMU(Wire)`.*<br>
|
*³⁻¹ — MPU-6050 supports I²C interface only (not recommended). To use it change IMU declaration to `MPU6050 IMU(Wire)`.*<br>
|
||||||
*⁴ — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*<br>
|
*⁴ — this frame is optimized for GY-91 board, if using other, the board mount holes positions should be modified.*<br>
|
||||||
*⁵ — you also may use any transmitter-receiver pair with SBUS interface.*
|
*⁵ — you also may use any transmitter-receiver pair with SBUS interface.*
|
||||||
@@ -106,7 +106,9 @@ Feel free to modify the design and or code, and create your own improved version
|
|||||||
|
|
||||||
### Simplified connection diagram
|
### Simplified connection diagram
|
||||||
|
|
||||||
<img src="docs/img/schematics1.svg" width=800 alt="Flix version 1 schematics">
|
<img src="docs/img/schematics1.svg" width=700 alt="Flix version 1 schematics">
|
||||||
|
|
||||||
|
*(Dashed is optional).*
|
||||||
|
|
||||||
Motor connection scheme:
|
Motor connection scheme:
|
||||||
|
|
||||||
|
|||||||
@@ -1,5 +1,2 @@
|
|||||||
board_manager:
|
|
||||||
additional_urls:
|
|
||||||
- https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json
|
|
||||||
network:
|
network:
|
||||||
connection_timeout: 1h
|
connection_timeout: 1h
|
||||||
|
|||||||
@@ -8,7 +8,7 @@ The firmware is a regular Arduino sketch, and it follows the classic Arduino one
|
|||||||
|
|
||||||
The main loop is running at 1000 Hz. All the dataflow goes through global variables (for simplicity):
|
The main loop is running at 1000 Hz. All the dataflow goes through global variables (for simplicity):
|
||||||
|
|
||||||
* `t` *(double)* — current step time, *s*.
|
* `t` *(float)* — current step time, *s*.
|
||||||
* `dt` *(float)* — time delta between the current and previous steps, *s*.
|
* `dt` *(float)* — time delta between the current and previous steps, *s*.
|
||||||
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
|
* `gyro` *(Vector)* — data from the gyroscope, *rad/s*.
|
||||||
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*.
|
* `acc` *(Vector)* — acceleration data from the accelerometer, *m/s<sup>2</sup>*.
|
||||||
|
|||||||
File diff suppressed because one or more lines are too long
|
Before Width: | Height: | Size: 17 KiB After Width: | Height: | Size: 18 KiB |
@@ -15,7 +15,7 @@ Do the following:
|
|||||||
* **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V.
|
* **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V.
|
||||||
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button to make sure you see the whole ESP32 output.
|
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button to make sure you see the whole ESP32 output.
|
||||||
* **Check the baudrate is correct**. If you see garbage characters in the Serial Monitor, make sure the baudrate is set to 115200.
|
* **Check the baudrate is correct**. If you see garbage characters in the Serial Monitor, make sure the baudrate is set to 115200.
|
||||||
* **Make sure correct IMU model is chosen**. If using ICM-20948 board, change `MPU9250` to `ICM20948` everywhere in the `imu.ino` file.
|
* **Make sure correct IMU model is chosen**. If using ICM-20948/MPU-6050 board, change `MPU9250` to `ICM20948`/`MPU6050` in the `imu.ino` file.
|
||||||
* **Check if the CLI is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the CLI using QGroundControl (*Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*).
|
* **Check if the CLI is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the CLI using QGroundControl (*Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*).
|
||||||
* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
|
* **Configure QGroundControl correctly before connecting to the drone** if you use it to control the drone. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
|
||||||
* **If QGroundControl doesn't connect**, you might need to disable the firewall and/or VPN on your computer.
|
* **If QGroundControl doesn't connect**, you might need to disable the firewall and/or VPN on your computer.
|
||||||
@@ -32,7 +32,6 @@ Do the following:
|
|||||||
* `mfl` — should rotate front left motor (clockwise).
|
* `mfl` — should rotate front left motor (clockwise).
|
||||||
* `mrl` — should rotate rear left motor (counter-clockwise).
|
* `mrl` — should rotate rear left motor (counter-clockwise).
|
||||||
* `mrr` — should rotate rear right motor (clockwise).
|
* `mrr` — should rotate rear right motor (clockwise).
|
||||||
* **Calibrate the RC** if you use it. Type `cr` command in Serial Monitor and follow the instructions.
|
* **Check the remote control**. Using `rc` command, check the control values reflect your sticks movement. All the controls should change between -1 and 1, and throttle between 0 and 1.
|
||||||
* **Check the RC data** if you use it. Use `rc` command, `Control` should show correct values between -1 and 1, and between 0 and 1 for the throttle.
|
* If using SBUS receiver, **calibrate the RC**. Type `cr` command in Serial Monitor and follow the instructions.
|
||||||
* **Check the IMU output using QGroundControl**. Connect to the drone using QGroundControl on your computer. Go to the *Analyze* tab, *MAVLINK Inspector*. Plot the data from the `SCALED_IMU` message. The gyroscope and accelerometer data should change according to the drone movement.
|
* **Check the IMU output using QGroundControl**. Connect to the drone using QGroundControl on your computer. Go to the *Analyze* tab, *MAVLINK Inspector*. Plot the data from the `SCALED_IMU` message. The gyroscope and accelerometer data should change according to the drone movement.
|
||||||
* **Check the gyroscope only attitude estimation**. Comment out `applyAcc();` line in `estimate.ino` and check if the attitude estimation in QGroundControl. It should be stable, but only drift very slowly.
|
|
||||||
|
|||||||
@@ -13,7 +13,7 @@ cd flix
|
|||||||
|
|
||||||
### Ubuntu
|
### Ubuntu
|
||||||
|
|
||||||
The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you have a newer version, consider using a virtual machine.
|
The latest version of Ubuntu supported by Gazebo 11 simulator is 20.04. If you have a newer version, consider using a virtual machine.
|
||||||
|
|
||||||
1. Install Arduino CLI:
|
1. Install Arduino CLI:
|
||||||
|
|
||||||
@@ -24,7 +24,10 @@ The latest version of Ubuntu supported by Gazebo 11 simulator is 22.04. If you h
|
|||||||
2. Install Gazebo 11:
|
2. Install Gazebo 11:
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
curl -sSL http://get.gazebosim.org | sh
|
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
|
||||||
|
wget https://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
|
||||||
|
sudo apt-get update
|
||||||
|
sudo apt-get install -y gazebo11 libgazebo11-dev
|
||||||
```
|
```
|
||||||
|
|
||||||
Set up your Gazebo environment variables:
|
Set up your Gazebo environment variables:
|
||||||
|
|||||||
12
flix/cli.ino
12
flix/cli.ino
@@ -9,8 +9,7 @@
|
|||||||
|
|
||||||
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
||||||
extern const int ACRO, STAB, AUTO;
|
extern const int ACRO, STAB, AUTO;
|
||||||
extern float loopRate, dt;
|
extern float t, dt, loopRate;
|
||||||
extern double t;
|
|
||||||
extern uint16_t channels[16];
|
extern uint16_t channels[16];
|
||||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
||||||
extern int mode;
|
extern int mode;
|
||||||
@@ -60,7 +59,7 @@ void print(const char* format, ...) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void pause(float duration) {
|
void pause(float duration) {
|
||||||
double start = t;
|
float start = t;
|
||||||
while (t - start < duration) {
|
while (t - start < duration) {
|
||||||
step();
|
step();
|
||||||
handleInput();
|
handleInput();
|
||||||
@@ -75,9 +74,10 @@ void doCommand(String str, bool echo = false) {
|
|||||||
// parse command
|
// parse command
|
||||||
String command, arg0, arg1;
|
String command, arg0, arg1;
|
||||||
splitString(str, command, arg0, arg1);
|
splitString(str, command, arg0, arg1);
|
||||||
|
if (command.isEmpty()) return;
|
||||||
|
|
||||||
// echo command
|
// echo command
|
||||||
if (echo && !command.isEmpty()) {
|
if (echo) {
|
||||||
print("> %s\n", str.c_str());
|
print("> %s\n", str.c_str());
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -107,7 +107,7 @@ void doCommand(String str, bool echo = false) {
|
|||||||
Vector a = attitude.toEuler();
|
Vector a = attitude.toEuler();
|
||||||
print("roll: %f pitch: %f yaw: %f\n", degrees(a.x), degrees(a.y), degrees(a.z));
|
print("roll: %f pitch: %f yaw: %f\n", degrees(a.x), degrees(a.y), degrees(a.z));
|
||||||
} else if (command == "psq") {
|
} else if (command == "psq") {
|
||||||
print("qx: %f qy: %f qz: %f qw: %f\n", attitude.x, attitude.y, attitude.z, attitude.w);
|
print("qw: %f qx: %f qy: %f qz: %f\n", attitude.w, attitude.x, attitude.y, attitude.z);
|
||||||
} else if (command == "imu") {
|
} else if (command == "imu") {
|
||||||
printIMUInfo();
|
printIMUInfo();
|
||||||
printIMUCalibration();
|
printIMUCalibration();
|
||||||
@@ -171,8 +171,6 @@ void doCommand(String str, bool echo = false) {
|
|||||||
attitude = Quaternion();
|
attitude = Quaternion();
|
||||||
} else if (command == "reboot") {
|
} else if (command == "reboot") {
|
||||||
ESP.restart();
|
ESP.restart();
|
||||||
} else if (command == "") {
|
|
||||||
// do nothing
|
|
||||||
} else {
|
} else {
|
||||||
print("Invalid command: %s\n", command.c_str());
|
print("Invalid command: %s\n", command.c_str());
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -9,7 +9,6 @@
|
|||||||
#include "lpf.h"
|
#include "lpf.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
#define ARMED_THRUST 0.1 // thrust to indicate armed state
|
|
||||||
#define PITCHRATE_P 0.05
|
#define PITCHRATE_P 0.05
|
||||||
#define PITCHRATE_I 0.2
|
#define PITCHRATE_I 0.2
|
||||||
#define PITCHRATE_D 0.001
|
#define PITCHRATE_D 0.001
|
||||||
@@ -80,7 +79,7 @@ void interpretControls() {
|
|||||||
|
|
||||||
if (mode == STAB) {
|
if (mode == STAB) {
|
||||||
float yawTarget = attitudeTarget.getYaw();
|
float yawTarget = attitudeTarget.getYaw();
|
||||||
if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or pilot commands yaw rate
|
if (!armed || invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target
|
||||||
attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget));
|
attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget));
|
||||||
ratesExtra = Vector(0, 0, -controlYaw * maxRate.z); // positive yaw stick means clockwise rotation in FLU
|
ratesExtra = Vector(0, 0, -controlYaw * maxRate.z); // positive yaw stick means clockwise rotation in FLU
|
||||||
}
|
}
|
||||||
@@ -100,12 +99,7 @@ void interpretControls() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void controlAttitude() {
|
void controlAttitude() {
|
||||||
if (!armed || attitudeTarget.invalid()) { // skip attitude control
|
if (!armed || attitudeTarget.invalid() || thrustTarget < 0.1) return; // skip attitude control
|
||||||
rollPID.reset();
|
|
||||||
pitchPID.reset();
|
|
||||||
yawPID.reset();
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
const Vector up(0, 0, 1);
|
const Vector up(0, 0, 1);
|
||||||
Vector upActual = Quaternion::rotateVector(up, attitude);
|
Vector upActual = Quaternion::rotateVector(up, attitude);
|
||||||
@@ -113,28 +107,23 @@ void controlAttitude() {
|
|||||||
|
|
||||||
Vector error = Vector::rotationVectorBetween(upTarget, upActual);
|
Vector error = Vector::rotationVectorBetween(upTarget, upActual);
|
||||||
|
|
||||||
ratesTarget.x = rollPID.update(error.x, dt) + ratesExtra.x;
|
ratesTarget.x = rollPID.update(error.x) + ratesExtra.x;
|
||||||
ratesTarget.y = pitchPID.update(error.y, dt) + ratesExtra.y;
|
ratesTarget.y = pitchPID.update(error.y) + ratesExtra.y;
|
||||||
|
|
||||||
float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw());
|
float yawError = wrapAngle(attitudeTarget.getYaw() - attitude.getYaw());
|
||||||
ratesTarget.z = yawPID.update(yawError, dt) + ratesExtra.z;
|
ratesTarget.z = yawPID.update(yawError) + ratesExtra.z;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void controlRates() {
|
void controlRates() {
|
||||||
if (!armed || ratesTarget.invalid()) { // skip rates control
|
if (!armed || ratesTarget.invalid() || thrustTarget < 0.1) return; // skip rates control
|
||||||
rollRatePID.reset();
|
|
||||||
pitchRatePID.reset();
|
|
||||||
yawRatePID.reset();
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
Vector error = ratesTarget - rates;
|
Vector error = ratesTarget - rates;
|
||||||
|
|
||||||
// Calculate desired torque, where 0 - no torque, 1 - maximum possible torque
|
// Calculate desired torque, where 0 - no torque, 1 - maximum possible torque
|
||||||
torqueTarget.x = rollRatePID.update(error.x, dt);
|
torqueTarget.x = rollRatePID.update(error.x);
|
||||||
torqueTarget.y = pitchRatePID.update(error.y, dt);
|
torqueTarget.y = pitchRatePID.update(error.y);
|
||||||
torqueTarget.z = yawRatePID.update(error.z, dt);
|
torqueTarget.z = yawRatePID.update(error.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
void controlTorque() {
|
void controlTorque() {
|
||||||
@@ -145,12 +134,11 @@ void controlTorque() {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (thrustTarget < 0.05) {
|
if (thrustTarget < 0.1) {
|
||||||
// minimal thrust to indicate armed state
|
motors[0] = 0.1; // idle thrust
|
||||||
motors[0] = ARMED_THRUST;
|
motors[1] = 0.1;
|
||||||
motors[1] = ARMED_THRUST;
|
motors[2] = 0.1;
|
||||||
motors[2] = ARMED_THRUST;
|
motors[3] = 0.1;
|
||||||
motors[3] = ARMED_THRUST;
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -10,7 +10,7 @@
|
|||||||
#define SERIAL_BAUDRATE 115200
|
#define SERIAL_BAUDRATE 115200
|
||||||
#define WIFI_ENABLED 1
|
#define WIFI_ENABLED 1
|
||||||
|
|
||||||
double t = NAN; // current step time, s
|
float t = NAN; // current step time, s
|
||||||
float dt; // time delta from previous step, s
|
float dt; // time delta from previous step, s
|
||||||
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
|
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
|
||||||
float controlMode = NAN;
|
float controlMode = NAN;
|
||||||
|
|||||||
45
flix/imu.ino
45
flix/imu.ino
@@ -4,11 +4,12 @@
|
|||||||
// Work with the IMU sensor
|
// Work with the IMU sensor
|
||||||
|
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#include <MPU9250.h>
|
#include <FlixPeriph.h>
|
||||||
|
#include "vector.h"
|
||||||
#include "lpf.h"
|
#include "lpf.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
MPU9250 IMU(SPI);
|
MPU9250 imu(SPI);
|
||||||
|
|
||||||
Vector accBias;
|
Vector accBias;
|
||||||
Vector accScale(1, 1, 1);
|
Vector accScale(1, 1, 1);
|
||||||
@@ -16,22 +17,22 @@ Vector gyroBias;
|
|||||||
|
|
||||||
void setupIMU() {
|
void setupIMU() {
|
||||||
print("Setup IMU\n");
|
print("Setup IMU\n");
|
||||||
IMU.begin();
|
imu.begin();
|
||||||
configureIMU();
|
configureIMU();
|
||||||
}
|
}
|
||||||
|
|
||||||
void configureIMU() {
|
void configureIMU() {
|
||||||
IMU.setAccelRange(IMU.ACCEL_RANGE_4G);
|
imu.setAccelRange(imu.ACCEL_RANGE_4G);
|
||||||
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
|
imu.setGyroRange(imu.GYRO_RANGE_2000DPS);
|
||||||
IMU.setDLPF(IMU.DLPF_MAX);
|
imu.setDLPF(imu.DLPF_MAX);
|
||||||
IMU.setRate(IMU.RATE_1KHZ_APPROX);
|
imu.setRate(imu.RATE_1KHZ_APPROX);
|
||||||
IMU.setupInterrupt();
|
imu.setupInterrupt();
|
||||||
}
|
}
|
||||||
|
|
||||||
void readIMU() {
|
void readIMU() {
|
||||||
IMU.waitForData();
|
imu.waitForData();
|
||||||
IMU.getGyro(gyro.x, gyro.y, gyro.z);
|
imu.getGyro(gyro.x, gyro.y, gyro.z);
|
||||||
IMU.getAccel(acc.x, acc.y, acc.z);
|
imu.getAccel(acc.x, acc.y, acc.z);
|
||||||
calibrateGyroOnce();
|
calibrateGyroOnce();
|
||||||
// apply scale and bias
|
// apply scale and bias
|
||||||
acc = (acc - accBias) / accScale;
|
acc = (acc - accBias) / accScale;
|
||||||
@@ -49,9 +50,8 @@ void rotateIMU(Vector& data) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void calibrateGyroOnce() {
|
void calibrateGyroOnce() {
|
||||||
static float landedTime = 0;
|
static Delay landedDelay(2);
|
||||||
landedTime = landed ? landedTime + dt : 0;
|
if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary
|
||||||
if (landedTime < 2) return; // calibrate only if definitely stationary
|
|
||||||
|
|
||||||
static LowPassFilter<Vector> gyroCalibrationFilter(0.001);
|
static LowPassFilter<Vector> gyroCalibrationFilter(0.001);
|
||||||
gyroBias = gyroCalibrationFilter.update(gyro);
|
gyroBias = gyroCalibrationFilter.update(gyro);
|
||||||
@@ -59,7 +59,7 @@ void calibrateGyroOnce() {
|
|||||||
|
|
||||||
void calibrateAccel() {
|
void calibrateAccel() {
|
||||||
print("Calibrating accelerometer\n");
|
print("Calibrating accelerometer\n");
|
||||||
IMU.setAccelRange(IMU.ACCEL_RANGE_2G); // the most sensitive mode
|
imu.setAccelRange(imu.ACCEL_RANGE_2G); // the most sensitive mode
|
||||||
|
|
||||||
print("1/6 Place level [8 sec]\n");
|
print("1/6 Place level [8 sec]\n");
|
||||||
pause(8);
|
pause(8);
|
||||||
@@ -93,9 +93,9 @@ void calibrateAccelOnce() {
|
|||||||
// Compute the average of the accelerometer readings
|
// Compute the average of the accelerometer readings
|
||||||
acc = Vector(0, 0, 0);
|
acc = Vector(0, 0, 0);
|
||||||
for (int i = 0; i < samples; i++) {
|
for (int i = 0; i < samples; i++) {
|
||||||
IMU.waitForData();
|
imu.waitForData();
|
||||||
Vector sample;
|
Vector sample;
|
||||||
IMU.getAccel(sample.x, sample.y, sample.z);
|
imu.getAccel(sample.x, sample.y, sample.z);
|
||||||
acc = acc + sample;
|
acc = acc + sample;
|
||||||
}
|
}
|
||||||
acc = acc / samples;
|
acc = acc / samples;
|
||||||
@@ -119,15 +119,16 @@ void printIMUCalibration() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void printIMUInfo() {
|
void printIMUInfo() {
|
||||||
IMU.status() ? print("status: ERROR %d\n", IMU.status()) : print("status: OK\n");
|
imu.status() ? print("status: ERROR %d\n", imu.status()) : print("status: OK\n");
|
||||||
print("model: %s\n", IMU.getModel());
|
print("model: %s\n", imu.getModel());
|
||||||
print("who am I: 0x%02X\n", IMU.whoAmI());
|
print("who am I: 0x%02X\n", imu.whoAmI());
|
||||||
print("rate: %.0f\n", loopRate);
|
print("rate: %.0f\n", loopRate);
|
||||||
print("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
|
print("gyro: %f %f %f\n", rates.x, rates.y, rates.z);
|
||||||
print("acc: %f %f %f\n", acc.x, acc.y, acc.z);
|
print("acc: %f %f %f\n", acc.x, acc.y, acc.z);
|
||||||
|
imu.waitForData();
|
||||||
Vector rawGyro, rawAcc;
|
Vector rawGyro, rawAcc;
|
||||||
IMU.getGyro(rawGyro.x, rawGyro.y, rawGyro.z);
|
imu.getGyro(rawGyro.x, rawGyro.y, rawGyro.z);
|
||||||
IMU.getAccel(rawAcc.x, rawAcc.y, rawAcc.z);
|
imu.getAccel(rawAcc.x, rawAcc.y, rawAcc.z);
|
||||||
print("raw gyro: %f %f %f\n", rawGyro.x, rawGyro.y, rawGyro.z);
|
print("raw gyro: %f %f %f\n", rawGyro.x, rawGyro.y, rawGyro.z);
|
||||||
print("raw acc: %f %f %f\n", rawAcc.x, rawAcc.y, rawAcc.z);
|
print("raw acc: %f %f %f\n", rawAcc.x, rawAcc.y, rawAcc.z);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -10,7 +10,6 @@
|
|||||||
#define LOG_PERIOD 1.0 / LOG_RATE
|
#define LOG_PERIOD 1.0 / LOG_RATE
|
||||||
#define LOG_SIZE LOG_DURATION * LOG_RATE
|
#define LOG_SIZE LOG_DURATION * LOG_RATE
|
||||||
|
|
||||||
float tFloat;
|
|
||||||
Vector attitudeEuler;
|
Vector attitudeEuler;
|
||||||
Vector attitudeTargetEuler;
|
Vector attitudeTargetEuler;
|
||||||
|
|
||||||
@@ -20,7 +19,7 @@ struct LogEntry {
|
|||||||
};
|
};
|
||||||
|
|
||||||
LogEntry logEntries[] = {
|
LogEntry logEntries[] = {
|
||||||
{"t", &tFloat},
|
{"t", &t},
|
||||||
{"rates.x", &rates.x},
|
{"rates.x", &rates.x},
|
||||||
{"rates.y", &rates.y},
|
{"rates.y", &rates.y},
|
||||||
{"rates.z", &rates.z},
|
{"rates.z", &rates.z},
|
||||||
@@ -40,7 +39,6 @@ const int logColumns = sizeof(logEntries) / sizeof(logEntries[0]);
|
|||||||
float logBuffer[LOG_SIZE][logColumns];
|
float logBuffer[LOG_SIZE][logColumns];
|
||||||
|
|
||||||
void prepareLogData() {
|
void prepareLogData() {
|
||||||
tFloat = t;
|
|
||||||
attitudeEuler = attitude.toEuler();
|
attitudeEuler = attitude.toEuler();
|
||||||
attitudeTargetEuler = attitudeTarget.toEuler();
|
attitudeTargetEuler = attitudeTarget.toEuler();
|
||||||
}
|
}
|
||||||
@@ -48,7 +46,7 @@ void prepareLogData() {
|
|||||||
void logData() {
|
void logData() {
|
||||||
if (!armed) return;
|
if (!armed) return;
|
||||||
static int logPointer = 0;
|
static int logPointer = 0;
|
||||||
static double logTime = 0;
|
static float logTime = 0;
|
||||||
if (t - logTime < LOG_PERIOD) return;
|
if (t - logTime < LOG_PERIOD) return;
|
||||||
logTime = t;
|
logTime = t;
|
||||||
|
|
||||||
|
|||||||
@@ -12,9 +12,10 @@
|
|||||||
#define PERIOD_FAST 0.1
|
#define PERIOD_FAST 0.1
|
||||||
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
||||||
|
|
||||||
|
bool mavlinkConnected = false;
|
||||||
String mavlinkPrintBuffer;
|
String mavlinkPrintBuffer;
|
||||||
|
|
||||||
extern double controlTime;
|
extern float controlTime;
|
||||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
||||||
|
|
||||||
void processMavlink() {
|
void processMavlink() {
|
||||||
@@ -25,8 +26,8 @@ void processMavlink() {
|
|||||||
void sendMavlink() {
|
void sendMavlink() {
|
||||||
sendMavlinkPrint();
|
sendMavlinkPrint();
|
||||||
|
|
||||||
static double lastSlow = 0;
|
static float lastSlow = 0;
|
||||||
static double lastFast = 0;
|
static float lastFast = 0;
|
||||||
|
|
||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
uint32_t time = t * 1000;
|
uint32_t time = t * 1000;
|
||||||
@@ -41,12 +42,14 @@ void sendMavlink() {
|
|||||||
mode, MAV_STATE_STANDBY);
|
mode, MAV_STATE_STANDBY);
|
||||||
sendMessage(&msg);
|
sendMessage(&msg);
|
||||||
|
|
||||||
|
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(SYSTEM_ID, 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 (t - lastFast >= PERIOD_FAST) {
|
if (t - lastFast >= PERIOD_FAST && mavlinkConnected) {
|
||||||
lastFast = t;
|
lastFast = t;
|
||||||
|
|
||||||
const float zeroQuat[] = {0, 0, 0, 0};
|
const float zeroQuat[] = {0, 0, 0, 0};
|
||||||
@@ -80,6 +83,7 @@ void sendMessage(const void *msg) {
|
|||||||
void receiveMavlink() {
|
void receiveMavlink() {
|
||||||
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
|
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
|
||||||
int len = receiveWiFi(buf, MAVLINK_MAX_PACKET_LEN);
|
int len = receiveWiFi(buf, MAVLINK_MAX_PACKET_LEN);
|
||||||
|
if (len) mavlinkConnected = true;
|
||||||
|
|
||||||
// New packet, parse it
|
// New packet, parse it
|
||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
@@ -232,7 +236,7 @@ void handleMavlink(const void *_msg) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (m.command == MAV_CMD_DO_SET_MODE) {
|
if (m.command == MAV_CMD_DO_SET_MODE) {
|
||||||
if (!(m.param2 >= 0 && m.param2 <= AUTO)) return; // incorrect mode
|
if (m.param2 < 0 || m.param2 > AUTO) return; // incorrect mode
|
||||||
accepted = true;
|
accepted = true;
|
||||||
mode = m.param2;
|
mode = m.param2;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -8,7 +8,6 @@
|
|||||||
extern float channelZero[16];
|
extern float channelZero[16];
|
||||||
extern float channelMax[16];
|
extern float channelMax[16];
|
||||||
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
|
||||||
extern float mavlinkControlScale;
|
|
||||||
|
|
||||||
Preferences storage;
|
Preferences storage;
|
||||||
|
|
||||||
@@ -119,7 +118,7 @@ bool setParameter(const char *name, const float value) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void syncParameters() {
|
void syncParameters() {
|
||||||
static double lastSync = 0;
|
static float lastSync = 0;
|
||||||
if (t - lastSync < 1) return; // sync once per second
|
if (t - lastSync < 1) return; // sync once per second
|
||||||
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
|
||||||
lastSync = t;
|
lastSync = t;
|
||||||
|
|||||||
30
flix/pid.h
30
flix/pid.h
@@ -9,40 +9,44 @@
|
|||||||
|
|
||||||
class PID {
|
class PID {
|
||||||
public:
|
public:
|
||||||
float p = 0;
|
float p, i, d;
|
||||||
float i = 0;
|
float windup;
|
||||||
float d = 0;
|
float dtMax;
|
||||||
float windup = 0;
|
|
||||||
|
|
||||||
float derivative = 0;
|
float derivative = 0;
|
||||||
float integral = 0;
|
float integral = 0;
|
||||||
|
|
||||||
LowPassFilter<float> lpf; // low pass filter for derivative term
|
LowPassFilter<float> lpf; // low pass filter for derivative term
|
||||||
|
|
||||||
PID(float p, float i, float d, float windup = 0, float dAlpha = 1) : p(p), i(i), d(d), windup(windup), lpf(dAlpha) {};
|
PID(float p, float i, float d, float windup = 0, float dAlpha = 1, float dtMax = 0.1) :
|
||||||
|
p(p), i(i), d(d), windup(windup), lpf(dAlpha), dtMax(dtMax) {}
|
||||||
|
|
||||||
float update(float error, float dt) {
|
float update(float error) {
|
||||||
|
float dt = t - prevTime;
|
||||||
|
|
||||||
|
if (dt > 0 && dt < dtMax) {
|
||||||
integral += error * dt;
|
integral += error * dt;
|
||||||
|
derivative = lpf.update((error - prevError) / dt); // compute derivative and apply low-pass filter
|
||||||
if (isfinite(prevError) && dt > 0) {
|
} else {
|
||||||
// calculate derivative if both dt and prevError are valid
|
integral = 0;
|
||||||
derivative = (error - prevError) / dt;
|
derivative = 0;
|
||||||
|
|
||||||
// apply low pass filter to derivative
|
|
||||||
derivative = lpf.update(derivative);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
prevError = error;
|
prevError = error;
|
||||||
|
prevTime = t;
|
||||||
|
|
||||||
return p * error + constrain(i * integral, -windup, windup) + d * derivative; // PID
|
return p * error + constrain(i * integral, -windup, windup) + d * derivative; // PID
|
||||||
}
|
}
|
||||||
|
|
||||||
void reset() {
|
void reset() {
|
||||||
prevError = NAN;
|
prevError = NAN;
|
||||||
|
prevTime = NAN;
|
||||||
integral = 0;
|
integral = 0;
|
||||||
derivative = 0;
|
derivative = 0;
|
||||||
|
lpf.reset();
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
float prevError = NAN;
|
float prevError = NAN;
|
||||||
|
float prevTime = NAN;
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -45,7 +45,7 @@ public:
|
|||||||
cx * cy * sz - sx * sy * cz);
|
cx * cy * sz - sx * sy * cz);
|
||||||
}
|
}
|
||||||
|
|
||||||
static Quaternion fromBetweenVectors(Vector u, Vector v) {
|
static Quaternion fromBetweenVectors(const Vector& u, const Vector& v) {
|
||||||
float dot = u.x * v.x + u.y * v.y + u.z * v.z;
|
float dot = u.x * v.x + u.y * v.y + u.z * v.z;
|
||||||
float w1 = u.y * v.z - u.z * v.y;
|
float w1 = u.y * v.z - u.z * v.y;
|
||||||
float w2 = u.z * v.x - u.x * v.z;
|
float w2 = u.z * v.x - u.x * v.z;
|
||||||
|
|||||||
10
flix/rc.ino
10
flix/rc.ino
@@ -6,10 +6,10 @@
|
|||||||
#include <SBUS.h>
|
#include <SBUS.h>
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
SBUS RC(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
|
SBUS rc(Serial2); // NOTE: Use RC(Serial2, 16, 17) if you use the old UART2 pins
|
||||||
|
|
||||||
uint16_t channels[16]; // raw rc channels
|
uint16_t channels[16]; // raw rc channels
|
||||||
double controlTime; // time of the last controls update
|
float controlTime; // time of the last controls update
|
||||||
float channelZero[16]; // calibration zero values
|
float channelZero[16]; // calibration zero values
|
||||||
float channelMax[16]; // calibration max values
|
float channelMax[16]; // calibration max values
|
||||||
|
|
||||||
@@ -18,12 +18,12 @@ float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel =
|
|||||||
|
|
||||||
void setupRC() {
|
void setupRC() {
|
||||||
print("Setup RC\n");
|
print("Setup RC\n");
|
||||||
RC.begin();
|
rc.begin();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool readRC() {
|
bool readRC() {
|
||||||
if (RC.read()) {
|
if (rc.read()) {
|
||||||
SBUSData data = RC.data();
|
SBUSData data = rc.data();
|
||||||
for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data
|
for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data
|
||||||
normalizeRC();
|
normalizeRC();
|
||||||
controlTime = t;
|
controlTime = t;
|
||||||
|
|||||||
@@ -3,10 +3,10 @@
|
|||||||
|
|
||||||
// Fail-safe functions
|
// Fail-safe functions
|
||||||
|
|
||||||
#define RC_LOSS_TIMEOUT 0.5
|
#define RC_LOSS_TIMEOUT 1
|
||||||
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
|
#define DESCEND_TIME 10
|
||||||
|
|
||||||
extern double controlTime;
|
extern float controlTime;
|
||||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
|
extern float controlRoll, controlPitch, controlThrottle, controlYaw;
|
||||||
|
|
||||||
void failsafe() {
|
void failsafe() {
|
||||||
@@ -16,6 +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 (t - controlTime > RC_LOSS_TIMEOUT) {
|
if (t - controlTime > RC_LOSS_TIMEOUT) {
|
||||||
descend();
|
descend();
|
||||||
}
|
}
|
||||||
@@ -23,14 +25,12 @@ void rcLossFailsafe() {
|
|||||||
|
|
||||||
// Smooth descend on RC lost
|
// Smooth descend on RC lost
|
||||||
void descend() {
|
void descend() {
|
||||||
mode = STAB;
|
mode = AUTO;
|
||||||
controlRoll = 0;
|
attitudeTarget = Quaternion();
|
||||||
controlPitch = 0;
|
thrustTarget -= dt / DESCEND_TIME;
|
||||||
controlYaw = 0;
|
if (thrustTarget < 0) {
|
||||||
controlThrottle -= dt / DESCEND_TIME;
|
thrustTarget = 0;
|
||||||
if (controlThrottle < 0) {
|
|
||||||
armed = false;
|
armed = false;
|
||||||
controlThrottle = 0;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -6,7 +6,7 @@
|
|||||||
float loopRate; // Hz
|
float loopRate; // Hz
|
||||||
|
|
||||||
void step() {
|
void step() {
|
||||||
double now = micros() / 1000000.0;
|
float now = micros() / 1000000.0;
|
||||||
dt = now - t;
|
dt = now - t;
|
||||||
t = now;
|
t = now;
|
||||||
|
|
||||||
@@ -18,7 +18,7 @@ void step() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void computeLoopRate() {
|
void computeLoopRate() {
|
||||||
static double windowStart = 0;
|
static float windowStart = 0;
|
||||||
static uint32_t rate = 0;
|
static uint32_t rate = 0;
|
||||||
rate++;
|
rate++;
|
||||||
if (t - windowStart >= 1) { // 1 second window
|
if (t - windowStart >= 1) { // 1 second window
|
||||||
|
|||||||
21
flix/util.h
21
flix/util.h
@@ -10,6 +10,7 @@
|
|||||||
#include <soc/rtc_cntl_reg.h>
|
#include <soc/rtc_cntl_reg.h>
|
||||||
|
|
||||||
const float ONE_G = 9.80665;
|
const float ONE_G = 9.80665;
|
||||||
|
extern float t;
|
||||||
|
|
||||||
float mapf(long x, long in_min, long in_max, float out_min, float out_max) {
|
float mapf(long x, long in_min, long in_max, float out_min, float out_max) {
|
||||||
return (float)(x - in_min) * (out_max - out_min) / (float)(in_max - in_min) + out_min;
|
return (float)(x - in_min) * (out_max - out_min) / (float)(in_max - in_min) + out_min;
|
||||||
@@ -52,3 +53,23 @@ void splitString(String& str, String& token0, String& token1, String& token2) {
|
|||||||
token1 = strtok(NULL, " "); // String(NULL) creates empty string
|
token1 = strtok(NULL, " "); // String(NULL) creates empty string
|
||||||
token2 = strtok(NULL, "");
|
token2 = strtok(NULL, "");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Delay filter for boolean signals - ensures the signal is on for at least 'delay' seconds
|
||||||
|
class Delay {
|
||||||
|
public:
|
||||||
|
float delay;
|
||||||
|
float start = NAN;
|
||||||
|
|
||||||
|
Delay(float delay) : delay(delay) {}
|
||||||
|
|
||||||
|
bool update(bool on) {
|
||||||
|
if (!on) {
|
||||||
|
start = NAN;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (isnan(start)) {
|
||||||
|
start = t;
|
||||||
|
}
|
||||||
|
return t - start >= delay;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|||||||
@@ -1,7 +1,7 @@
|
|||||||
cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
|
cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
|
||||||
project(flix_gazebo)
|
project(flix_gazebo)
|
||||||
|
|
||||||
# === gazebo plugin
|
# Gazebo plugin
|
||||||
find_package(gazebo REQUIRED)
|
find_package(gazebo REQUIRED)
|
||||||
find_package(SDL2 REQUIRED)
|
find_package(SDL2 REQUIRED)
|
||||||
include_directories(${GAZEBO_INCLUDE_DIRS})
|
include_directories(${GAZEBO_INCLUDE_DIRS})
|
||||||
|
|||||||
@@ -12,7 +12,7 @@
|
|||||||
|
|
||||||
#define WIFI_ENABLED 1
|
#define WIFI_ENABLED 1
|
||||||
|
|
||||||
double t = NAN;
|
float t = NAN;
|
||||||
float dt;
|
float dt;
|
||||||
float motors[4];
|
float motors[4];
|
||||||
float controlRoll, controlPitch, controlYaw, controlThrottle = NAN;
|
float controlRoll, controlPitch, controlYaw, controlThrottle = NAN;
|
||||||
|
|||||||
@@ -21,7 +21,7 @@
|
|||||||
#include "cli.ino"
|
#include "cli.ino"
|
||||||
#include "control.ino"
|
#include "control.ino"
|
||||||
#include "estimate.ino"
|
#include "estimate.ino"
|
||||||
#include "failsafe.ino"
|
#include "safety.ino"
|
||||||
#include "log.ino"
|
#include "log.ino"
|
||||||
#include "lpf.h"
|
#include "lpf.h"
|
||||||
#include "mavlink.ino"
|
#include "mavlink.ino"
|
||||||
@@ -59,6 +59,7 @@ public:
|
|||||||
|
|
||||||
void OnReset() {
|
void OnReset() {
|
||||||
attitude = Quaternion(); // reset estimated attitude
|
attitude = Quaternion(); // reset estimated attitude
|
||||||
|
armed = false;
|
||||||
__resetTime += __micros;
|
__resetTime += __micros;
|
||||||
gzmsg << "Flix plugin reset" << endl;
|
gzmsg << "Flix plugin reset" << endl;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -49,6 +49,8 @@ for configuration in props['configurations']:
|
|||||||
print('Check configuration', configuration['name'])
|
print('Check configuration', configuration['name'])
|
||||||
|
|
||||||
for include_path in configuration.get('includePath', []):
|
for include_path in configuration.get('includePath', []):
|
||||||
|
if include_path.startswith('/opt/') or include_path.startswith('/usr/'): # don't check non-Arduino libs
|
||||||
|
continue
|
||||||
check_path(include_path)
|
check_path(include_path)
|
||||||
|
|
||||||
for forced_include in configuration.get('forcedInclude', []):
|
for forced_include in configuration.get('forcedInclude', []):
|
||||||
|
|||||||
@@ -59,6 +59,13 @@ flix.on('disconnected', lambda: print('Disconnected from Flix'))
|
|||||||
flix.on('print', lambda text: print(f'Flix says: {text}'))
|
flix.on('print', lambda text: print(f'Flix says: {text}'))
|
||||||
```
|
```
|
||||||
|
|
||||||
|
Unsubscribe from events using `off` method:
|
||||||
|
|
||||||
|
```python
|
||||||
|
flix.off('print') # unsubscribe from print events
|
||||||
|
flix.off(callback) # unsubscribe specific callback
|
||||||
|
```
|
||||||
|
|
||||||
You can also wait for specific events using `wait` method. This method returns the data associated with the event:
|
You can also wait for specific events using `wait` method. This method returns the data associated with the event:
|
||||||
|
|
||||||
```python
|
```python
|
||||||
@@ -122,6 +129,13 @@ flix.cli('reboot') # reboot the drone
|
|||||||
> [!TIP]
|
> [!TIP]
|
||||||
> Use `help` command to get the list of available commands.
|
> Use `help` command to get the list of available commands.
|
||||||
|
|
||||||
|
You can arm and disarm the drone using `set_armed` method (warning: the drone will fall if disarmed in the air):
|
||||||
|
|
||||||
|
```python
|
||||||
|
flix.set_armed(True) # arm the drone
|
||||||
|
flix.set_armed(False) # disarm the drone
|
||||||
|
```
|
||||||
|
|
||||||
You can imitate pilot's controls using `set_controls` method:
|
You can imitate pilot's controls using `set_controls` method:
|
||||||
|
|
||||||
```python
|
```python
|
||||||
@@ -173,7 +187,7 @@ To exit from *AUTO* mode move control sticks and the drone will switch to *STAB*
|
|||||||
|
|
||||||
## Usage alongside QGroundControl
|
## Usage alongside QGroundControl
|
||||||
|
|
||||||
You can use the Flix library alongside the QGroundControl app, using a proxy mode. To do that:
|
You can use the Flix library alongside the QGroundControl app, using proxy mode. To do that:
|
||||||
|
|
||||||
1. Run proxy for `pyflix` and QGroundControl in background:
|
1. Run proxy for `pyflix` and QGroundControl in background:
|
||||||
|
|
||||||
@@ -241,11 +255,11 @@ You can send values from the firmware like this (`mavlink.ino`):
|
|||||||
|
|
||||||
```cpp
|
```cpp
|
||||||
// Send float named value
|
// Send float named value
|
||||||
mavlink_msg_named_value_float_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, t, "some_value", loopRate);
|
mavlink_msg_named_value_float_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, t, "loop_rate", loopRate);
|
||||||
sendMessage(&msg);
|
sendMessage(&msg);
|
||||||
|
|
||||||
// Send vector named value
|
// Send vector named value
|
||||||
mavlink_msg_debug_vect_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, "some_vector", t, gyroBias.x, gyroBias.y, gyroBias.z);
|
mavlink_msg_debug_vect_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, "gyro_bias", t, gyroBias.x, gyroBias.y, gyroBias.z);
|
||||||
sendMessage(&msg);
|
sendMessage(&msg);
|
||||||
```
|
```
|
||||||
|
|
||||||
|
|||||||
@@ -6,7 +6,7 @@
|
|||||||
import os
|
import os
|
||||||
import time
|
import time
|
||||||
from queue import Queue, Empty
|
from queue import Queue, Empty
|
||||||
from typing import Literal, Optional, Callable, List, Dict, Any, Union, Sequence
|
from typing import Optional, Callable, List, Dict, Any, Union, Sequence
|
||||||
import logging
|
import logging
|
||||||
import errno
|
import errno
|
||||||
from threading import Thread, Timer
|
from threading import Thread, Timer
|
||||||
@@ -36,7 +36,7 @@ class Flix:
|
|||||||
|
|
||||||
system_id: int
|
system_id: int
|
||||||
messages: Dict[str, Dict[str, Any]] # MAVLink messages storage
|
messages: Dict[str, Dict[str, Any]] # MAVLink messages storage
|
||||||
values: Dict[Union[str, int], Union[float, List[float]]] = {} # named values
|
values: Dict[Union[str, int], Union[float, List[float]]] # named values
|
||||||
|
|
||||||
_connection_timeout = 3
|
_connection_timeout = 3
|
||||||
_print_buffer: str = ''
|
_print_buffer: str = ''
|
||||||
@@ -61,7 +61,6 @@ class Flix:
|
|||||||
self.connection.target_system = system_id
|
self.connection.target_system = system_id
|
||||||
self.mavlink: mavlink.MAVLink = self.connection.mav
|
self.mavlink: mavlink.MAVLink = self.connection.mav
|
||||||
self._event_listeners: Dict[str, List[Callable[..., Any]]] = {}
|
self._event_listeners: Dict[str, List[Callable[..., Any]]] = {}
|
||||||
self.messages = {}
|
|
||||||
self._disconnected_timer = Timer(0, self._disconnected)
|
self._disconnected_timer = Timer(0, self._disconnected)
|
||||||
self._reader_thread = Thread(target=self._read_mavlink, daemon=True)
|
self._reader_thread = Thread(target=self._read_mavlink, daemon=True)
|
||||||
self._reader_thread.start()
|
self._reader_thread.start()
|
||||||
@@ -79,6 +78,8 @@ class Flix:
|
|||||||
self.motors = [0, 0, 0, 0]
|
self.motors = [0, 0, 0, 0]
|
||||||
self.acc = [0, 0, 0]
|
self.acc = [0, 0, 0]
|
||||||
self.gyro = [0, 0, 0]
|
self.gyro = [0, 0, 0]
|
||||||
|
self.messages = {}
|
||||||
|
self.values = {}
|
||||||
|
|
||||||
def on(self, event: str, callback: Callable):
|
def on(self, event: str, callback: Callable):
|
||||||
event = event.lower()
|
event = event.lower()
|
||||||
@@ -86,10 +87,15 @@ class Flix:
|
|||||||
self._event_listeners[event] = []
|
self._event_listeners[event] = []
|
||||||
self._event_listeners[event].append(callback)
|
self._event_listeners[event].append(callback)
|
||||||
|
|
||||||
def off(self, callback: Callable):
|
def off(self, event_or_callback: Union[str, Callable]):
|
||||||
|
if isinstance(event_or_callback, str):
|
||||||
|
event = event_or_callback.lower()
|
||||||
|
if event in self._event_listeners:
|
||||||
|
del self._event_listeners[event]
|
||||||
|
else:
|
||||||
for event in self._event_listeners:
|
for event in self._event_listeners:
|
||||||
if callback in self._event_listeners[event]:
|
if event_or_callback in self._event_listeners[event]:
|
||||||
self._event_listeners[event].remove(callback)
|
self._event_listeners[event].remove(event_or_callback)
|
||||||
|
|
||||||
def _trigger(self, event: str, *args):
|
def _trigger(self, event: str, *args):
|
||||||
event = event.lower()
|
event = event.lower()
|
||||||
@@ -148,7 +154,7 @@ class Flix:
|
|||||||
|
|
||||||
def _handle_mavlink_message(self, msg: mavlink.MAVLink_message):
|
def _handle_mavlink_message(self, msg: mavlink.MAVLink_message):
|
||||||
if isinstance(msg, mavlink.MAVLink_heartbeat_message):
|
if isinstance(msg, mavlink.MAVLink_heartbeat_message):
|
||||||
self.mode = self._modes[msg.custom_mode]
|
self.mode = self._modes[msg.custom_mode] if msg.custom_mode < len(self._modes) else f'UNKNOWN({msg.custom_mode})'
|
||||||
self.armed = msg.base_mode & mavlink.MAV_MODE_FLAG_SAFETY_ARMED != 0
|
self.armed = msg.base_mode & mavlink.MAV_MODE_FLAG_SAFETY_ARMED != 0
|
||||||
self._trigger('mode', self.mode)
|
self._trigger('mode', self.mode)
|
||||||
self._trigger('armed', self.armed)
|
self._trigger('armed', self.armed)
|
||||||
@@ -299,6 +305,9 @@ class Flix:
|
|||||||
mode = self._modes.index(mode.upper())
|
mode = self._modes.index(mode.upper())
|
||||||
self._command_send(mavlink.MAV_CMD_DO_SET_MODE, (0, mode, 0, 0, 0, 0, 0))
|
self._command_send(mavlink.MAV_CMD_DO_SET_MODE, (0, mode, 0, 0, 0, 0, 0))
|
||||||
|
|
||||||
|
def set_armed(self, armed: bool):
|
||||||
|
self._command_send(mavlink.MAV_CMD_COMPONENT_ARM_DISARM, (1 if armed else 0, 0, 0, 0, 0, 0, 0))
|
||||||
|
|
||||||
def set_position(self, position: List[float], yaw: Optional[float] = None, wait: bool = False, tolerance: float = 0.1):
|
def set_position(self, position: List[float], yaw: Optional[float] = None, wait: bool = False, tolerance: float = 0.1):
|
||||||
raise NotImplementedError('Position control is not implemented yet')
|
raise NotImplementedError('Position control is not implemented yet')
|
||||||
|
|
||||||
@@ -344,7 +353,7 @@ class Flix:
|
|||||||
raise ValueError('roll, pitch, yaw must be in range [-1, 1]')
|
raise ValueError('roll, pitch, yaw must be in range [-1, 1]')
|
||||||
if not 0 <= throttle <= 1:
|
if not 0 <= throttle <= 1:
|
||||||
raise ValueError('throttle must be in range [0, 1]')
|
raise ValueError('throttle must be in range [0, 1]')
|
||||||
self.mavlink.manual_control_send(self.system_id, int(roll * 1000), int(pitch * 1000), int(yaw * 1000), int(throttle * 1000), 0) # type: ignore
|
self.mavlink.manual_control_send(self.system_id, int(pitch * 1000), int(roll * 1000), int(throttle * 1000), int(yaw * 1000), 0) # type: ignore
|
||||||
|
|
||||||
def cli(self, cmd: str, wait_response: bool = True) -> str:
|
def cli(self, cmd: str, wait_response: bool = True) -> str:
|
||||||
cmd = cmd.strip()
|
cmd = cmd.strip()
|
||||||
@@ -361,7 +370,9 @@ class Flix:
|
|||||||
self.mavlink.serial_control_send(0, 0, 0, 0, len(cmd_bytes), cmd_bytes)
|
self.mavlink.serial_control_send(0, 0, 0, 0, len(cmd_bytes), cmd_bytes)
|
||||||
if not wait_response:
|
if not wait_response:
|
||||||
return ''
|
return ''
|
||||||
response = self.wait('print_full', timeout=0.1, value=lambda text: text.startswith(response_prefix))
|
timeout = 0.1
|
||||||
|
if cmd == 'log': timeout = 10 # log download may take more time
|
||||||
|
response = self.wait('print_full', timeout=timeout, value=lambda text: text.startswith(response_prefix))
|
||||||
return response[len(response_prefix):].strip()
|
return response[len(response_prefix):].strip()
|
||||||
except TimeoutError:
|
except TimeoutError:
|
||||||
continue
|
continue
|
||||||
|
|||||||
@@ -24,13 +24,16 @@ def main():
|
|||||||
if addr in TARGETS: # packet from target
|
if addr in TARGETS: # packet from target
|
||||||
if source_addr is None:
|
if source_addr is None:
|
||||||
continue
|
continue
|
||||||
|
try:
|
||||||
sock.sendto(data, source_addr)
|
sock.sendto(data, source_addr)
|
||||||
|
packets += 1
|
||||||
|
except: pass
|
||||||
else: # packet from source
|
else: # packet from source
|
||||||
source_addr = addr
|
source_addr = addr
|
||||||
for target in TARGETS:
|
for target in TARGETS:
|
||||||
sock.sendto(data, target)
|
sock.sendto(data, target)
|
||||||
|
|
||||||
packets += 1
|
packets += 1
|
||||||
|
|
||||||
print(f'\rPackets: {packets}', end='')
|
print(f'\rPackets: {packets}', end='')
|
||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
[project]
|
[project]
|
||||||
name = "pyflix"
|
name = "pyflix"
|
||||||
version = "0.7"
|
version = "0.9"
|
||||||
description = "Python API for Flix drone"
|
description = "Python API for Flix drone"
|
||||||
authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }]
|
authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }]
|
||||||
license = "MIT"
|
license = "MIT"
|
||||||
|
|||||||
Reference in New Issue
Block a user