Compare commits
34 Commits
4d70018d73
...
school-548
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
3104410bb9 | ||
|
|
1551d096fc | ||
|
|
80f23ab016 | ||
|
|
e6fb264499 | ||
|
|
4d0871b00b | ||
|
|
f1b993d719 | ||
|
|
2e7330d2f5 | ||
|
|
e22df3ab01 | ||
|
|
8484854576 | ||
|
|
b9d5624f30 | ||
|
|
205270b8ec | ||
|
|
f1bedb2b10 | ||
|
|
46d1749a8c | ||
|
|
66fb7a13c3 | ||
|
|
cfef3b9c36 | ||
|
|
1338a9ea79 | ||
|
|
b60757ec1d | ||
|
|
491e054534 | ||
|
|
3eaf24f89d | ||
|
|
dc09459613 | ||
|
|
59c9ea8cb3 | ||
|
|
5bdd46c6ad | ||
|
|
5b37c87166 | ||
|
|
48ba55aa7e | ||
|
|
2708c1eafd | ||
|
|
b2c9dfe6ef | ||
|
|
0579118dd5 | ||
|
|
05818349d8 | ||
|
|
6c1d651caa | ||
|
|
49a0aa7036 | ||
|
|
bf9eeb90a4 | ||
|
|
96836b2e3e | ||
|
|
82d9d3570d | ||
|
|
d7f8c8d934 |
11
.github/workflows/tools.yml
vendored
@@ -46,3 +46,14 @@ jobs:
|
||||
echo -e "t,x,y,z\n0,1,2,3\n1,4,5,6" > log.csv
|
||||
./csv_to_mcap.py log.csv
|
||||
test $(stat -c %s log.mcap) -eq 883
|
||||
|
||||
sloc:
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
- name: Install cloc
|
||||
run: sudo apt-get install -y cloc
|
||||
- name: Firmware source lines count
|
||||
run: cloc --by-file-by-lang flix
|
||||
- name: Overall source lines count
|
||||
run: cloc --by-file-by-lang --exclude-ext=svg,dae,css,hbs,md,json,yaml,yml,toml .
|
||||
|
||||
@@ -7,7 +7,6 @@
|
||||
"MD024": false,
|
||||
"MD033": false,
|
||||
"MD034": false,
|
||||
"MD059": false,
|
||||
"MD044": {
|
||||
"html_elements": false,
|
||||
"code_blocks": false,
|
||||
@@ -65,6 +64,5 @@
|
||||
"PX4"
|
||||
]
|
||||
},
|
||||
"MD045": false,
|
||||
"MD060": false
|
||||
"MD045": false
|
||||
}
|
||||
|
||||
|
Before Width: | Height: | Size: 23 KiB |
|
Before Width: | Height: | Size: 18 KiB |
|
Before Width: | Height: | Size: 18 KiB |
|
Before Width: | Height: | Size: 17 KiB |
|
Before Width: | Height: | Size: 17 KiB |
|
Before Width: | Height: | Size: 10 KiB |
|
Before Width: | Height: | Size: 9.6 KiB |
|
Before Width: | Height: | Size: 10 KiB |
|
Before Width: | Height: | Size: 10 KiB |
|
Before Width: | Height: | Size: 68 KiB |
|
Before Width: | Height: | Size: 35 KiB |
|
Before Width: | Height: | Size: 32 KiB |
|
Before Width: | Height: | Size: 108 KiB |
|
Before Width: | Height: | Size: 93 KiB |
|
Before Width: | Height: | Size: 65 KiB |
|
Before Width: | Height: | Size: 28 KiB |
|
Before Width: | Height: | Size: 31 KiB |
|
Before Width: | Height: | Size: 42 KiB |
|
Before Width: | Height: | Size: 43 KiB |
|
Before Width: | Height: | Size: 76 KiB |
|
Before Width: | Height: | Size: 28 KiB |
|
Before Width: | Height: | Size: 44 KiB |
|
Before Width: | Height: | Size: 32 KiB |
@@ -12,7 +12,7 @@ Beginners can [download the source code as a ZIP archive](https://github.com/oka
|
||||
|
||||
## Building the firmware
|
||||
|
||||
You can build and upload the firmware using either **Arduino IDE** (easier for beginners) or **command line**.
|
||||
You can build and upload the firmware using either **Arduino IDE** (easier for beginners) or a **command line**.
|
||||
|
||||
### Arduino IDE (Windows, Linux, macOS)
|
||||
|
||||
@@ -73,6 +73,14 @@ ICM20948 imu(SPI); // For ICM-20948
|
||||
MPU6050 imu(Wire); // For MPU-6050
|
||||
```
|
||||
|
||||
### Setup the IMU orientation
|
||||
|
||||
The IMU orientation is defined in `rotateIMU` function in the `imu.ino` file. Change it so it converts the IMU axes to the drone's axes correctly. **Drone axes are X forward, Y left, Z up**:
|
||||
|
||||
<img src="img/drone-axes.svg" width="200">
|
||||
|
||||
See various [IMU boards axes orientations table](https://github.com/okalachev/flixperiph/?tab=readme-ov-file#imu-axes-orientation) to help you set up the correct orientation.
|
||||
|
||||
### Connect using QGroundControl
|
||||
|
||||
QGroundControl is a ground control station software that can be used to monitor and control the drone.
|
||||
@@ -96,35 +104,11 @@ To access the console using QGroundControl:
|
||||
|
||||
1. Connect to the drone using QGroundControl app.
|
||||
2. Go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*.
|
||||
|
||||
<img src="img/cli.png" width="400">
|
||||
|
||||
> [!TIP]
|
||||
> Use `help` command to see the list of available commands.
|
||||
|
||||
### Access parameters
|
||||
|
||||
The drone is configured using parameters. To access and modify them, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*:
|
||||
|
||||
<img src="img/parameters.png" width="400">
|
||||
|
||||
### Define IMU orientation
|
||||
|
||||
Use parameters, to define the IMU board axes orientation relative to the drone's axes: `IMU_ROT_ROLL`, `IMU_ROT_PITCH`, and `IMU_ROT_YAW`.
|
||||
|
||||
The drone has *X* axis pointing forward, *Y* axis pointing left, and *Z* axis pointing up, and the supported IMU boards have *X* axis pointing to the pins side and *Z* axis pointing up from the side with the components:
|
||||
|
||||
<img src="img/imu-axes.png" width="200">
|
||||
|
||||
Use the following table to set the parameters for common IMU orientations:
|
||||
|
||||
|Orientation|Parameters|Orientation|Parameters|
|
||||
|:-:|-|-|-|
|
||||
|<img src="img/imu-rot-1.png" width="200">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0 |<img src="img/imu-rot-5.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0|
|
||||
|<img src="img/imu-rot-2.png" width="200">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|<img src="img/imu-rot-6.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|
|
||||
|<img src="img/imu-rot-3.png" width="200">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|<img src="img/imu-rot-7.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|
|
||||
|<img src="img/imu-rot-4.png" width="200"><br>☑️ **Default**|<br>`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|<img src="img/imu-rot-8.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|
|
||||
|
||||
### Calibrate accelerometer
|
||||
|
||||
Before flight you need to calibrate the accelerometer:
|
||||
@@ -169,7 +153,7 @@ There are several ways to control the drone's flight: using **smartphone** (Wi-F
|
||||
6. Use the virtual joystick to fly the drone!
|
||||
|
||||
> [!TIP]
|
||||
> Decrease `CTL_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
|
||||
> Decrease `CNT_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
|
||||
|
||||
### Control with remote control
|
||||
|
||||
@@ -227,9 +211,9 @@ The default mode is *STAB*. In this mode, the drone stabilizes its attitude (ori
|
||||
|
||||
In this mode, the pilot controls the angular rates. This control method is difficult to fly and mostly used in FPV racing.
|
||||
|
||||
#### RAW
|
||||
#### MANUAL
|
||||
|
||||
*RAW* mode disables all the stabilization, and the pilot inputs are mixed directly to the motors. The IMU sensor is not involved. This mode is intended for testing and demonstration purposes only, and basically the drone **cannot fly in this mode**.
|
||||
Manual mode disables all the stabilization, and the pilot inputs are passed directly to the motors. This mode is intended for testing and demonstration purposes only, and basically the drone **cannot fly in this mode**.
|
||||
|
||||
#### AUTO
|
||||
|
||||
@@ -237,6 +221,10 @@ 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.
|
||||
|
||||
## Adjusting parameters
|
||||
|
||||
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*.
|
||||
|
||||
<img src="img/parameters.png" width="400">
|
||||
|
||||
## Flight log
|
||||
|
||||
57
docs/user.md
@@ -4,67 +4,12 @@ This page contains user-built drones based on the Flix project. Publish your pro
|
||||
|
||||
---
|
||||
|
||||
Author: [goldarte](https://t.me/goldarte).<br>
|
||||
|
||||
<img src="img/user/goldarte/1.jpg" height=150> <img src="img/user/goldarte/2.jpg" height=150>
|
||||
|
||||
**Flight video:**
|
||||
|
||||
<a href="https://drive.google.com/file/d/1nQtFjEcGGLx-l4xkL5ko9ZpOTVU-WDjL/view?usp=sharing"><img height=200 src="img/user/goldarte/video.jpg"></a>
|
||||
|
||||
---
|
||||
|
||||
## School 548 course
|
||||
|
||||
Special quadcopter design and engineering course took place in october-november 2025 in School 548, Moscow. Course included UAV control theory, electronics, and practical drone assembly and setup using the Flix project.
|
||||
|
||||
<img height=200 src="img/user/school548/1.jpg"> <img height=200 src="img/user/school548/2.jpg"> <img height=200 src="img/user/school548/3.jpg">
|
||||
|
||||
STL files and other materials: see [here](https://drive.google.com/drive/folders/1wTUzj087LjKQQl3Lz5CjHCuobxoykhyp?usp=share_link).
|
||||
|
||||
### Selected works
|
||||
|
||||
Author: [KiraFlux](https://t.me/@kiraflux_0XC0000005).<br>
|
||||
Description: **custom ESPNOW remote control** is implemented, firmware modified to support ESPNOW protocol.<br>
|
||||
Telegram posts: [1](https://t.me/opensourcequadcopter/106), [2](https://t.me/opensourcequadcopter/114).<br>
|
||||
Modified Flix firmware: https://github.com/KiraFlux/flix/tree/klyax.<br>
|
||||
Remote control project: https://github.com/KiraFlux/ESP32-DJC.<br>
|
||||
Drone design: https://github.com/KiraFlux/Klyax.<br>
|
||||
|
||||
<img src="img/user/school548/kiraflux1.jpg" height=150> <img src="img/user/school548/kiraflux2.jpg" height=150>
|
||||
|
||||
**ESPNOW remote control demonstration**:
|
||||
|
||||
<img height=200 src="img/user/school548/kiraflux-video.jpg"><a href="https://drive.google.com/file/d/1soHDAeHQWnm97Y4dg4nWevJuMiTdJJXW/view?usp=sharing"></a>
|
||||
|
||||
Author: [tolyan4krut](https://t.me/tolyan4krut).<br>
|
||||
Description: the first drone based on ESP32-S3-CAM board **with a camera**, implementing Wi-Fi video streaming. Runs HTTP server and HTTP video stream.<br>
|
||||
Modified Flix firmware: https://github.com/CatRey/Flix-Camera-Streaming.<br>
|
||||
[Telegram post](https://t.me/opensourcequadcopter/117).
|
||||
|
||||
<img src="img/user/school548/tolyan4krut.jpg" height=150>
|
||||
|
||||
**Video streaming and flight demonstration**:
|
||||
|
||||
<a href="https://drive.google.com/file/d/1KuOBsujLsk7q8FoqKD8u7uoq4ptS5onp/view?usp=sharing"><img height=200 src="img/user/school548/tolyan4krut-video.jpg"></a>
|
||||
|
||||
Author: [Vlad Tolshinov](https://t.me/Vlad_Tolshinov).<br>
|
||||
Description: custom frame with enlarged arm length, which provides very high flight stability, 65 mm props.
|
||||
|
||||
<img src="img/user/school548/vlad_tolshinov1.jpg" height=150> <img src="img/user/school548/vlad_tolshinov2.jpg" height=150>
|
||||
|
||||
**Flight video**:
|
||||
|
||||
<a href="https://drive.google.com/file/d/1zu00DZxhC7DJ9Z2mYjtxdNQqOOLAyYbp/view?usp=sharing"><img height=200 src="img/user/school548/vlad_tolshinov-video.jpg"></a>
|
||||
|
||||
---
|
||||
|
||||
## RoboCamp
|
||||
|
||||
Author: RoboCamp participants.<br>
|
||||
Description: 3D-printed and wooden frames, ESP32 Mini, DC-DC buck-boost converters. BetaFPV LiteRadio 3 to control the drones via Wi-Fi connection.<br>
|
||||
Features: altitude hold, obstacle avoidance, autonomous flight elements.<br>
|
||||
Some of the designed model files: see [here](https://drive.google.com/drive/folders/18YHWGquKeIevzrMH4-OUT-zKXMETTEUu?usp=share_link).
|
||||
Some of the designed model files: https://drive.google.com/drive/folders/18YHWGquKeIevzrMH4-OUT-zKXMETTEUu?usp=share_link.
|
||||
|
||||
RoboCamp took place in July 2025, Saint Petersburg, where 9 participants designed and built their own drones using the Flix project, and then modified the firmware to complete specific flight tasks.
|
||||
|
||||
|
||||
12
flix/cli.ino
@@ -8,7 +8,7 @@
|
||||
#include "util.h"
|
||||
|
||||
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
|
||||
extern const int RAW, ACRO, STAB, AUTO;
|
||||
extern const int ACRO, STAB, AUTO;
|
||||
extern float t, dt, loopRate;
|
||||
extern uint16_t channels[16];
|
||||
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
|
||||
@@ -35,14 +35,12 @@ const char* motd =
|
||||
"imu - show IMU data\n"
|
||||
"arm - arm the drone\n"
|
||||
"disarm - disarm the drone\n"
|
||||
"raw/stab/acro/auto - set mode\n"
|
||||
"stab/acro/auto - set mode\n"
|
||||
"rc - show RC data\n"
|
||||
"wifi - show Wi-Fi info\n"
|
||||
"mot - show motor output\n"
|
||||
"log [dump] - print log header [and data]\n"
|
||||
"cr - calibrate RC\n"
|
||||
"ca - calibrate accel\n"
|
||||
"cl - calibrate level\n"
|
||||
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
|
||||
"sys - show system info\n"
|
||||
"reset - reset drone's state\n"
|
||||
@@ -118,8 +116,6 @@ void doCommand(String str, bool echo = false) {
|
||||
armed = true;
|
||||
} else if (command == "disarm") {
|
||||
armed = false;
|
||||
} else if (command == "raw") {
|
||||
mode = RAW;
|
||||
} else if (command == "stab") {
|
||||
mode = STAB;
|
||||
} else if (command == "acro") {
|
||||
@@ -135,10 +131,6 @@ void doCommand(String str, bool echo = false) {
|
||||
controlRoll, controlPitch, controlYaw, controlThrottle, controlMode);
|
||||
print("mode: %s\n", getModeName());
|
||||
print("armed: %d\n", armed);
|
||||
} else if (command == "wifi") {
|
||||
#if WIFI_ENABLED
|
||||
printWiFiInfo();
|
||||
#endif
|
||||
} else if (command == "mot") {
|
||||
print("front-right %g front-left %g rear-right %g rear-left %g\n",
|
||||
motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]);
|
||||
|
||||
@@ -34,7 +34,7 @@
|
||||
#define TILT_MAX radians(30)
|
||||
#define RATES_D_LPF_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||
|
||||
const int RAW = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
|
||||
const int MANUAL = 0, ACRO = 1, STAB = 2, AUTO = 3; // flight modes
|
||||
int mode = STAB;
|
||||
bool armed = false;
|
||||
|
||||
@@ -65,6 +65,7 @@ void control() {
|
||||
}
|
||||
|
||||
void interpretControls() {
|
||||
// NOTE: put ACRO or MANUAL modes there if you want to use them
|
||||
if (controlMode < 0.25) mode = STAB;
|
||||
if (controlMode < 0.75) mode = STAB;
|
||||
if (controlMode > 0.75) mode = STAB;
|
||||
@@ -74,8 +75,6 @@ void interpretControls() {
|
||||
if (controlThrottle < 0.05 && controlYaw > 0.95) armed = true; // arm gesture
|
||||
if (controlThrottle < 0.05 && controlYaw < -0.95) armed = false; // disarm gesture
|
||||
|
||||
if (abs(controlYaw) < 0.1) controlYaw = 0; // yaw dead zone
|
||||
|
||||
thrustTarget = controlThrottle;
|
||||
|
||||
if (mode == STAB) {
|
||||
@@ -92,10 +91,10 @@ void interpretControls() {
|
||||
ratesTarget.z = -controlYaw * maxRate.z; // positive yaw stick means clockwise rotation in FLU
|
||||
}
|
||||
|
||||
if (mode == RAW) { // direct torque control
|
||||
if (mode == MANUAL) { // passthrough mode
|
||||
attitudeTarget.invalidate(); // skip attitude control
|
||||
ratesTarget.invalidate(); // skip rate control
|
||||
torqueTarget = Vector(controlRoll, controlPitch, -controlYaw) * 0.1;
|
||||
torqueTarget = Vector(controlRoll, controlPitch, -controlYaw) * 0.01;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -156,7 +155,7 @@ void controlTorque() {
|
||||
|
||||
const char* getModeName() {
|
||||
switch (mode) {
|
||||
case RAW: return "RAW";
|
||||
case MANUAL: return "MANUAL";
|
||||
case ACRO: return "ACRO";
|
||||
case STAB: return "STAB";
|
||||
case AUTO: return "AUTO";
|
||||
|
||||
@@ -8,8 +8,8 @@
|
||||
#include "lpf.h"
|
||||
#include "util.h"
|
||||
|
||||
float accWeight = 0.003;
|
||||
LowPassFilter<Vector> ratesFilter(0.2); // cutoff frequency ~ 40 Hz
|
||||
#define WEIGHT_ACC 0.003
|
||||
#define RATES_LFP_ALPHA 0.2 // cutoff frequency ~ 40 Hz
|
||||
|
||||
void estimate() {
|
||||
applyGyro();
|
||||
@@ -18,6 +18,7 @@ void estimate() {
|
||||
|
||||
void applyGyro() {
|
||||
// filter gyro to get angular rates
|
||||
static LowPassFilter<Vector> ratesFilter(RATES_LFP_ALPHA);
|
||||
rates = ratesFilter.update(gyro);
|
||||
|
||||
// apply rates to attitude
|
||||
@@ -33,7 +34,7 @@ void applyAcc() {
|
||||
|
||||
// calculate accelerometer correction
|
||||
Vector up = Quaternion::rotateVector(Vector(0, 0, 1), attitude);
|
||||
Vector correction = Vector::rotationVectorBetween(acc, up) * accWeight;
|
||||
Vector correction = Vector::rotationVectorBetween(acc, up) * WEIGHT_ACC;
|
||||
|
||||
// apply correction
|
||||
attitude = Quaternion::rotate(attitude, Quaternion::fromRotationVector(correction));
|
||||
|
||||
23
flix/imu.ino
@@ -10,7 +10,6 @@
|
||||
#include "util.h"
|
||||
|
||||
MPU9250 imu(SPI);
|
||||
Vector imuRotation(0, 0, -PI / 2); // imu orientation as Euler angles
|
||||
|
||||
Vector accBias;
|
||||
Vector accScale(1, 1, 1);
|
||||
@@ -38,26 +37,24 @@ void readIMU() {
|
||||
// apply scale and bias
|
||||
acc = (acc - accBias) / accScale;
|
||||
gyro = gyro - gyroBias;
|
||||
// rotate to body frame
|
||||
Quaternion rotation = Quaternion::fromEuler(imuRotation);
|
||||
acc = Quaternion::rotateVector(acc, rotation.inversed());
|
||||
gyro = Quaternion::rotateVector(gyro, rotation.inversed());
|
||||
// rotate
|
||||
rotateIMU(acc);
|
||||
rotateIMU(gyro);
|
||||
}
|
||||
|
||||
void calibrateLevel() {
|
||||
print("Place perfectly level [1 sec]\n");
|
||||
pause(1);
|
||||
Quaternion correction = Quaternion::fromBetweenVectors(Quaternion::rotateVector(Vector(0, 0, 1), attitude), Vector(0, 0, 1));
|
||||
imuRotation = Quaternion::rotate(correction, Quaternion::fromEuler(imuRotation)).toEuler();
|
||||
print("✓ Done: %.3f %.3f %.3f\n", degrees(imuRotation.x), degrees(imuRotation.y), degrees(imuRotation.z));
|
||||
void rotateIMU(Vector& data) {
|
||||
// Rotate from LFD to FLU
|
||||
// NOTE: In case of using other IMU orientation, change this line:
|
||||
data = Vector(data.y, data.x, -data.z);
|
||||
// Axes orientation for various boards: https://github.com/okalachev/flixperiph#imu-axes-orientation
|
||||
}
|
||||
|
||||
void calibrateGyroOnce() {
|
||||
static Delay landedDelay(2);
|
||||
if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary
|
||||
|
||||
static LowPassFilter<Vector> gyroBiasFilter(0.001);
|
||||
gyroBias = gyroBiasFilter.update(gyro);
|
||||
static LowPassFilter<Vector> gyroCalibrationFilter(0.001);
|
||||
gyroBias = gyroCalibrationFilter.update(gyro);
|
||||
}
|
||||
|
||||
void calibrateAccel() {
|
||||
|
||||
@@ -11,6 +11,7 @@
|
||||
#define SYSTEM_ID 1
|
||||
#define MAVLINK_RATE_SLOW 1
|
||||
#define MAVLINK_RATE_FAST 10
|
||||
#define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f
|
||||
|
||||
bool mavlinkConnected = false;
|
||||
String mavlinkPrintBuffer;
|
||||
@@ -104,6 +105,8 @@ void handleMavlink(const void *_msg) {
|
||||
controlYaw = m.r / 1000.0f;
|
||||
controlMode = NAN;
|
||||
controlTime = t;
|
||||
|
||||
if (abs(controlYaw) < MAVLINK_CONTROL_YAW_DEAD_ZONE) controlYaw = 0;
|
||||
}
|
||||
|
||||
if (msg.msgid == MAVLINK_MSG_ID_PARAM_REQUEST_LIST) {
|
||||
|
||||
@@ -43,18 +43,12 @@ Parameter parameters[] = {
|
||||
{"CTL_Y_RATE_MAX", &maxRate.z},
|
||||
{"CTL_TILT_MAX", &tiltMax},
|
||||
// imu
|
||||
{"IMU_ROT_ROLL", &imuRotation.x},
|
||||
{"IMU_ROT_PITCH", &imuRotation.y},
|
||||
{"IMU_ROT_YAW", &imuRotation.z},
|
||||
{"IMU_ACC_BIAS_X", &accBias.x},
|
||||
{"IMU_ACC_BIAS_Y", &accBias.y},
|
||||
{"IMU_ACC_BIAS_Z", &accBias.z},
|
||||
{"IMU_ACC_SCALE_X", &accScale.x},
|
||||
{"IMU_ACC_SCALE_Y", &accScale.y},
|
||||
{"IMU_ACC_SCALE_Z", &accScale.z},
|
||||
// estimate
|
||||
{"EST_ACC_WEIGHT", &accWeight},
|
||||
{"EST_RATES_LPF_A", &ratesFilter.alpha},
|
||||
// rc
|
||||
{"RC_ZERO_0", &channelZero[0]},
|
||||
{"RC_ZERO_1", &channelZero[1]},
|
||||
|
||||
@@ -9,8 +9,11 @@
|
||||
#include <WiFiAP.h>
|
||||
#include <WiFiUdp.h>
|
||||
|
||||
#define WIFI_SSID "flix"
|
||||
#define WIFI_PASSWORD "flixwifi"
|
||||
#define WIFI_AP_MODE 1
|
||||
#define WIFI_AP_SSID "flix"
|
||||
#define WIFI_AP_PASSWORD "flixwifi"
|
||||
#define WIFI_SSID ""
|
||||
#define WIFI_PASSWORD ""
|
||||
#define WIFI_UDP_PORT 14550
|
||||
#define WIFI_UDP_REMOTE_PORT 14550
|
||||
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
|
||||
@@ -19,7 +22,11 @@ WiFiUDP udp;
|
||||
|
||||
void setupWiFi() {
|
||||
print("Setup Wi-Fi\n");
|
||||
WiFi.softAP(WIFI_SSID, WIFI_PASSWORD);
|
||||
if (WIFI_AP_MODE) {
|
||||
WiFi.softAP(WIFI_AP_SSID, WIFI_AP_PASSWORD);
|
||||
} else {
|
||||
WiFi.begin(WIFI_SSID, WIFI_PASSWORD);
|
||||
}
|
||||
udp.begin(WIFI_UDP_PORT);
|
||||
}
|
||||
|
||||
@@ -35,15 +42,4 @@ int receiveWiFi(uint8_t *buf, int len) {
|
||||
return udp.read(buf, len);
|
||||
}
|
||||
|
||||
void printWiFiInfo() {
|
||||
print("MAC: %s\n", WiFi.softAPmacAddress().c_str());
|
||||
print("SSID: %s\n", WiFi.softAPSSID().c_str());
|
||||
print("Password: %s\n", WIFI_PASSWORD);
|
||||
print("Clients: %d\n", WiFi.softAPgetStationNum());
|
||||
print("Status: %d\n", WiFi.status());
|
||||
print("IP: %s\n", WiFi.softAPIP().toString().c_str());
|
||||
print("Remote IP: %s\n", udp.remoteIP().toString().c_str());
|
||||
print("MAVLink connected: %d\n", mavlinkConnected);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
@@ -68,9 +68,6 @@ Just like the real drone, the simulator can be controlled using a USB remote con
|
||||
6. Go to the settings and enable *Virtual Joystick*. *Auto-Center Throttle* setting **should be disabled**.
|
||||
7. Use the virtual joystick to fly the drone!
|
||||
|
||||
> [!TIP]
|
||||
> Decrease `CTL_TILT_MAX` parameter when flying using the smartphone to make the controls less sensitive.
|
||||
|
||||
### Control with USB remote control
|
||||
|
||||
1. Connect your USB remote control to the machine running the simulator.
|
||||
|
||||
@@ -22,7 +22,6 @@ Vector gyro;
|
||||
Vector rates;
|
||||
Quaternion attitude;
|
||||
bool landed;
|
||||
Vector imuRotation;
|
||||
|
||||
// declarations
|
||||
void step();
|
||||
@@ -74,5 +73,4 @@ void calibrateGyro() { print("Skip gyro calibrating\n"); };
|
||||
void calibrateAccel() { print("Skip accel calibrating\n"); };
|
||||
void printIMUCalibration() { print("cal: N/A\n"); };
|
||||
void printIMUInfo() {};
|
||||
void printWiFiInfo() {};
|
||||
Vector accBias, gyroBias, accScale(1, 1, 1);
|
||||
|
||||
@@ -1,8 +1,8 @@
|
||||
# Flix Python library
|
||||
|
||||
The Flix Python library allows you to remotely connect to a Flix quadcopter. It provides access to telemetry data, supports executing console commands, and controlling the drone's flight.
|
||||
The Flix Python library allows you to remotely connect to a Flix quadcopter. It provides access to telemetry data, supports executing CLI commands, and controlling the drone's flight.
|
||||
|
||||
To use the library, connect to the drone's Wi-Fi. To use it with the simulator, ensure the script runs on the same network as the simulator.
|
||||
To use the library, connect to the drone's Wi-Fi. To use it with the simulator, ensure the script runs on the same local network as the simulator.
|
||||
|
||||
## Installation
|
||||
|
||||
@@ -30,7 +30,7 @@ flix = Flix() # create a Flix object and wait for connection
|
||||
|
||||
### Telemetry
|
||||
|
||||
Basic telemetry is available through object properties. The property names generally match the corresponding variables in the firmware itself:
|
||||
Basic telemetry is available through object properties. The properties names generally match the corresponding variables in the firmware itself:
|
||||
|
||||
```python
|
||||
print(flix.connected) # True if connected to the drone
|
||||
@@ -41,7 +41,7 @@ print(flix.attitude) # attitude quaternion [w, x, y, z]
|
||||
print(flix.attitude_euler) # attitude as Euler angles [roll, pitch, yaw]
|
||||
print(flix.rates) # angular rates [roll_rate, pitch_rate, yaw_rate]
|
||||
print(flix.channels) # raw RC channels (list)
|
||||
print(flix.motors) # motor outputs (list)
|
||||
print(flix.motors) # motors outputs (list)
|
||||
print(flix.acc) # accelerometer output (list)
|
||||
print(flix.gyro) # gyroscope output (list)
|
||||
```
|
||||
@@ -100,17 +100,17 @@ Full list of events:
|
||||
|`attitude_euler`|Attitude update|Euler angles (*list*)|
|
||||
|`rates`|Angular rates update|Angular rates (*list*)|
|
||||
|`channels`|Raw RC channels update|Raw RC channels (*list*)|
|
||||
|`motors`|Motor outputs update|Motor outputs (*list*)|
|
||||
|`motors`|Motors outputs update|Motors outputs (*list*)|
|
||||
|`acc`|Accelerometer update|Accelerometer output (*list*)|
|
||||
|`gyro`|Gyroscope update|Gyroscope output (*list*)|
|
||||
|`mavlink`|Received MAVLink message|Message object|
|
||||
|`mavlink.<message_name>`|Received specific MAVLink message|Message object|
|
||||
|`mavlink.<message_id>`|Received specific MAVLink message|Message object|
|
||||
|`value`|Named value update (see below)|Name, value|
|
||||
|`value.<name>`|Specific named value update (see below)|Value|
|
||||
|`value.<name>`|Specific named value update (see bellow)|Value|
|
||||
|
||||
> [!NOTE]
|
||||
> Update events trigger on every new piece of data from the drone, and do not mean the value has changed.
|
||||
> Update events trigger on every new data from the drone, and do not mean the value has changed.
|
||||
|
||||
### Common methods
|
||||
|
||||
@@ -121,7 +121,7 @@ pitch_p = flix.get_param('PITCH_P') # get parameter value
|
||||
flix.set_param('PITCH_P', 5) # set parameter value
|
||||
```
|
||||
|
||||
Execute console commands using `cli` method. This method returns the command response:
|
||||
Execute console commands using `cli` method. This method returns command response:
|
||||
|
||||
```python
|
||||
imu = flix.cli('imu') # get detailed IMU data
|
||||
@@ -169,10 +169,10 @@ Setting angular rates target:
|
||||
flix.set_rates([0.1, 0.2, 0.3], 0.6) # set target roll rate, pitch rate, yaw rate and thrust
|
||||
```
|
||||
|
||||
You also can control raw motor outputs directly:
|
||||
You also can control raw motors outputs directly:
|
||||
|
||||
```python
|
||||
flix.set_motors([0.5, 0.5, 0.5, 0.5]) # set motor outputs in range [0, 1]
|
||||
flix.set_motors([0.5, 0.5, 0.5, 0.5]) # set motors outputs in range [0, 1]
|
||||
```
|
||||
|
||||
In *AUTO* mode, the drone will arm automatically if the thrust is greater than zero, and disarm if thrust is zero. Therefore, to disarm the drone, set thrust to zero:
|
||||
@@ -186,7 +186,7 @@ The following methods are in development and are not functional yet:
|
||||
* `set_position` — set target position.
|
||||
* `set_velocity` — set target velocity.
|
||||
|
||||
To exit *AUTO* mode move control sticks and the drone will switch to *STAB* mode.
|
||||
To exit from *AUTO* mode move control sticks and the drone will switch to *STAB* mode.
|
||||
|
||||
## Usage alongside QGroundControl
|
||||
|
||||
|
||||
@@ -17,7 +17,7 @@ from pymavlink.dialects.v20 import common as mavlink
|
||||
logger = logging.getLogger('flix')
|
||||
if not logger.hasHandlers():
|
||||
handler = logging.StreamHandler()
|
||||
handler.setFormatter(logging.Formatter('%(name)s: %(message)s'))
|
||||
handler.setFormatter(logging.Formatter('%(name)s - %(levelname)s - %(message)s'))
|
||||
logger.addHandler(handler)
|
||||
logger.setLevel(logging.INFO)
|
||||
|
||||
@@ -40,7 +40,7 @@ class Flix:
|
||||
|
||||
_connection_timeout = 3
|
||||
_print_buffer: str = ''
|
||||
_modes = ['RAW', 'ACRO', 'STAB', 'AUTO']
|
||||
_modes = ['MANUAL', 'ACRO', 'STAB', 'AUTO']
|
||||
|
||||
def __init__(self, system_id: int=1, wait_connection: bool=True):
|
||||
if not (0 <= system_id < 256):
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
[project]
|
||||
name = "pyflix"
|
||||
version = "0.11"
|
||||
version = "0.9"
|
||||
description = "Python API for Flix drone"
|
||||
authors = [{ name="Oleg Kalachev", email="okalachev@gmail.com" }]
|
||||
license = "MIT"
|
||||
|
||||