mirror of
https://github.com/okalachev/flix.git
synced 2026-03-30 03:54:20 +00:00
Compare commits
2 Commits
7d74f3d5cd
...
esp32-c3
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
2308bd4d8f | ||
|
|
8153644578 |
2
.github/workflows/build.yml
vendored
2
.github/workflows/build.yml
vendored
@@ -25,6 +25,8 @@ 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 for ESP32-C3
|
||||||
|
run: make BOARD=esp32:esp32:esp32c3
|
||||||
- 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
|
||||||
|
|
||||||
|
|||||||
@@ -138,10 +138,10 @@ You can see a user-contributed [variant of complete circuit diagram](https://mir
|
|||||||
|
|
||||||
|Motor|Position|Direction|Prop type|Motor wires|GPIO|
|
|Motor|Position|Direction|Prop type|Motor wires|GPIO|
|
||||||
|-|-|-|-|-|-|
|
|-|-|-|-|-|-|
|
||||||
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 *(TDI)*|
|
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 (*TDI*)|
|
||||||
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 *(TCK)*|
|
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 (*TCK*)|
|
||||||
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 *(TMS)*|
|
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 (*TMS*)|
|
||||||
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 *(TD0)*|
|
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 (*TD0*)|
|
||||||
|
|
||||||
Clockwise motors have blue & red wires and correspond to propeller type A (marked on the propeller).
|
Clockwise motors have blue & red wires and correspond to propeller type A (marked on the propeller).
|
||||||
Counter-clockwise motors have black & white wires correspond to propeller type B.
|
Counter-clockwise motors have black & white wires correspond to propeller type B.
|
||||||
|
|||||||
@@ -41,10 +41,10 @@ Motors connection table:
|
|||||||
|
|
||||||
|Motor|Position|Direction|Prop type|Motor wires|GPIO|
|
|Motor|Position|Direction|Prop type|Motor wires|GPIO|
|
||||||
|-|-|-|-|-|-|
|
|-|-|-|-|-|-|
|
||||||
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 *(TDI)*|
|
|Motor 0|Rear left|Counter-clockwise|B|Black & White|GPIO12 (*TDI*)|
|
||||||
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 *(TCK)*|
|
|Motor 1|Rear right|Clockwise|A|Blue & Red|GPIO13 (*TCK*)|
|
||||||
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 *(TMS)*|
|
|Motor 2|Front right|Counter-clockwise|B|Black & White|GPIO14 (*TMS*)|
|
||||||
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 *(TD0)*|
|
|Motor 3|Front left|Clockwise|A|Blue & Red|GPIO15 (*TD0*)|
|
||||||
|
|
||||||
## Motors tightening
|
## Motors tightening
|
||||||
|
|
||||||
|
|||||||
@@ -110,7 +110,7 @@ float angle = Vector::angleBetween(a, b); // 1.57 (90 градусов)
|
|||||||
|
|
||||||
#### Скалярное произведение
|
#### Скалярное произведение
|
||||||
|
|
||||||
Скалярное произведение векторов *(dot product)* — это произведение длин двух векторов на косинус угла между ними. В математике оно обозначается знаком `·` или слитным написанием векторов. Интуитивно, результат скалярного произведения показывает, насколько два вектора *сонаправлены*.
|
Скалярное произведение векторов (*dot product*) — это произведение длин двух векторов на косинус угла между ними. В математике оно обозначается знаком `·` или слитным написанием векторов. Интуитивно, результат скалярного произведения показывает, насколько два вектора *сонаправлены*.
|
||||||
|
|
||||||
В Flix используется статический метод `Vector::dot()`:
|
В Flix используется статический метод `Vector::dot()`:
|
||||||
|
|
||||||
@@ -124,7 +124,7 @@ float dotProduct = Vector::dot(a, b); // 32
|
|||||||
|
|
||||||
#### Векторное произведение
|
#### Векторное произведение
|
||||||
|
|
||||||
Векторное произведение *(cross product)* позволяет найти вектор, перпендикулярный двум другим векторам. В математике оно обозначается знаком `×`, а в прошивке используется статический метод `Vector::cross()`:
|
Векторное произведение (*cross product*) позволяет найти вектор, перпендикулярный двум другим векторам. В математике оно обозначается знаком `×`, а в прошивке используется статический метод `Vector::cross()`:
|
||||||
|
|
||||||
```cpp
|
```cpp
|
||||||
Vector a(1, 2, 3);
|
Vector a(1, 2, 3);
|
||||||
@@ -144,9 +144,9 @@ Vector crossProduct = Vector::cross(a, b); // -3, 6, -3
|
|||||||
|
|
||||||
В прошивке углы Эйлера сохраняются в обычный объект `Vector` (хоть и, строго говоря, не являются вектором):
|
В прошивке углы Эйлера сохраняются в обычный объект `Vector` (хоть и, строго говоря, не являются вектором):
|
||||||
|
|
||||||
* Угол по крену *(roll)* — `vector.x`.
|
* Угол по крену (*roll*) — `vector.x`.
|
||||||
* Угол по тангажу *(pitch)* — `vector.y`.
|
* Угол по тангажу (*pitch*) — `vector.y`.
|
||||||
* Угол по рысканию *(yaw)* — `vector.z`.
|
* Угол по рысканию (*yaw*) — `vector.z`.
|
||||||
|
|
||||||
Особенности углов Эйлера:
|
Особенности углов Эйлера:
|
||||||
|
|
||||||
@@ -162,8 +162,8 @@ Vector crossProduct = Vector::cross(a, b); // -3, 6, -3
|
|||||||
|
|
||||||
Помимо углов Эйлера, любую ориентацию в трехмерном пространстве можно представить в виде вращения вокруг некоторой оси на некоторый угол. В геометрии это доказывается, как **теорема вращения Эйлера**. В таком представлении ориентация задается двумя величинами:
|
Помимо углов Эйлера, любую ориентацию в трехмерном пространстве можно представить в виде вращения вокруг некоторой оси на некоторый угол. В геометрии это доказывается, как **теорема вращения Эйлера**. В таком представлении ориентация задается двумя величинами:
|
||||||
|
|
||||||
* **Ось вращения** *(axis)* — единичный вектор, определяющий ось вращения.
|
* **Ось вращения** (*axis*) — единичный вектор, определяющий ось вращения.
|
||||||
* **Угол поворота** *(angle* или *θ)* — угол, на который нужно повернуть объект вокруг этой оси.
|
* **Угол поворота** (*angle* или *θ*) — угол, на который нужно повернуть объект вокруг этой оси.
|
||||||
|
|
||||||
В Flix ось вращения задается объектом `Vector`, а угол поворота — числом типа `float` в радианах:
|
В Flix ось вращения задается объектом `Vector`, а угол поворота — числом типа `float` в радианах:
|
||||||
|
|
||||||
@@ -177,7 +177,7 @@ float angle = radians(45);
|
|||||||
|
|
||||||
### Вектор вращения
|
### Вектор вращения
|
||||||
|
|
||||||
Если умножить вектор *axis* на угол поворота *θ*, то получится **вектор вращения** *(rotation vector)*. Этот вектор играет важную роль в алгоритмах управления ориентацией летательного аппарата.
|
Если умножить вектор *axis* на угол поворота *θ*, то получится **вектор вращения** (*rotation vector*). Этот вектор играет важную роль в алгоритмах управления ориентацией летательного аппарата.
|
||||||
|
|
||||||
Вектор вращения обладает замечательным свойством: если угловые скорости объекта (в собственной системе координат) в каждый момент времени совпадают с компонентами этого вектора, то за единичное время объект придет к заданной этим вектором ориентации. Это свойство позволяет использовать вектор вращения для управления ориентацией объекта посредством управления угловыми скоростями.
|
Вектор вращения обладает замечательным свойством: если угловые скорости объекта (в собственной системе координат) в каждый момент времени совпадают с компонентами этого вектора, то за единичное время объект придет к заданной этим вектором ориентации. Это свойство позволяет использовать вектор вращения для управления ориентацией объекта посредством управления угловыми скоростями.
|
||||||
|
|
||||||
@@ -198,7 +198,7 @@ Vector rotation = radians(45) * Vector(1, 2, 3);
|
|||||||
<a href="https://github.com/okalachev/flix/blob/master/flix/quaternion.h"><code>quaternion.h</code></a>.<br>
|
<a href="https://github.com/okalachev/flix/blob/master/flix/quaternion.h"><code>quaternion.h</code></a>.<br>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
Вектор вращения удобен, но еще удобнее использовать **кватернион**. В Flix кватернионы задаются объектами `Quaternion` из библиотеки `quaternion.h`. Кватернион состоит из четырех значений: *w*, *x*, *y*, *z* и рассчитывается из вектора оси вращения *(axis)* и угла поворота *(θ)* по формуле:
|
Вектор вращения удобен, но еще удобнее использовать **кватернион**. В Flix кватернионы задаются объектами `Quaternion` из библиотеки `quaternion.h`. Кватернион состоит из четырех значений: *w*, *x*, *y*, *z* и рассчитывается из вектора оси вращения (*axis*) и угла поворота (*θ*) по формуле:
|
||||||
|
|
||||||
\\[ q = \left( \begin{array}{c} w \\\\ x \\\\ y \\\\ z \end{array} \right) = \left( \begin{array}{c} \cos\left(\frac{\theta}{2}\right) \\\\ axis\_x \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_y \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_z \cdot \sin\left(\frac{\theta}{2}\right) \end{array} \right) \\]
|
\\[ q = \left( \begin{array}{c} w \\\\ x \\\\ y \\\\ z \end{array} \right) = \left( \begin{array}{c} \cos\left(\frac{\theta}{2}\right) \\\\ axis\_x \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_y \cdot \sin\left(\frac{\theta}{2}\right) \\\\ axis\_z \cdot \sin\left(\frac{\theta}{2}\right) \end{array} \right) \\]
|
||||||
|
|
||||||
|
|||||||
@@ -177,7 +177,7 @@ imu.setDLPF(imu.DLPF_MAX);
|
|||||||
|
|
||||||
## Калибровка гироскопа
|
## Калибровка гироскопа
|
||||||
|
|
||||||
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения *(bias)* и случайный шум *(noise)*:
|
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения (*bias*) и случайный шум (*noise*):
|
||||||
|
|
||||||
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]
|
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]
|
||||||
|
|
||||||
|
|||||||
@@ -13,10 +13,10 @@ Do the following:
|
|||||||
Do the following:
|
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 startup 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/MPU-6050 board, change `MPU9250` to `ICM20948`/`MPU6050` 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 console is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the console 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.
|
||||||
* **Check the IMU is working**. Perform `imu` command and check its output:
|
* **Check the IMU is working**. Perform `imu` command and check its output:
|
||||||
|
|||||||
@@ -250,8 +250,8 @@ 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:
|
The Wi-Fi mode is chosen using `WIFI_MODE` parameter in QGroundControl or in the console:
|
||||||
|
|
||||||
* `0` — Wi-Fi is disabled.
|
* `0` — Wi-Fi is disabled.
|
||||||
* `1` — Access Point mode *(AP)* — the drone creates a Wi-Fi network.
|
* `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.
|
* `2` — Client mode (*STA*) — the drone connects to an existing Wi-Fi network.
|
||||||
* `3` — *ESP-NOW (not implemented yet)*.
|
* `3` — *ESP-NOW (not implemented yet)*.
|
||||||
|
|
||||||
> [!WARNING]
|
> [!WARNING]
|
||||||
|
|||||||
@@ -6,7 +6,6 @@
|
|||||||
#include "pid.h"
|
#include "pid.h"
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
#include "lpf.h"
|
|
||||||
|
|
||||||
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 RAW, ACRO, STAB, AUTO;
|
extern const int RAW, ACRO, STAB, AUTO;
|
||||||
@@ -15,7 +14,6 @@ extern uint16_t channels[16];
|
|||||||
extern float controlTime;
|
extern float controlTime;
|
||||||
extern int mode;
|
extern int mode;
|
||||||
extern bool armed;
|
extern bool armed;
|
||||||
extern LowPassFilter<Vector> gyroBiasFilter;
|
|
||||||
|
|
||||||
const char* motd =
|
const char* motd =
|
||||||
"\nWelcome to\n"
|
"\nWelcome to\n"
|
||||||
@@ -180,7 +178,6 @@ void doCommand(String str, bool echo = false) {
|
|||||||
#endif
|
#endif
|
||||||
} else if (command == "reset") {
|
} else if (command == "reset") {
|
||||||
attitude = Quaternion();
|
attitude = Quaternion();
|
||||||
gyroBiasFilter.reset();
|
|
||||||
} else if (command == "reboot") {
|
} else if (command == "reboot") {
|
||||||
ESP.restart();
|
ESP.restart();
|
||||||
} else {
|
} else {
|
||||||
|
|||||||
@@ -7,6 +7,7 @@
|
|||||||
#include "quaternion.h"
|
#include "quaternion.h"
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
|
|
||||||
extern float t, dt;
|
extern float t, dt;
|
||||||
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
|
||||||
extern Vector gyro, acc;
|
extern Vector gyro, acc;
|
||||||
|
|||||||
@@ -19,8 +19,6 @@ Vector acc; // accelerometer output, m/s/s
|
|||||||
Vector accBias;
|
Vector accBias;
|
||||||
Vector accScale(1, 1, 1);
|
Vector accScale(1, 1, 1);
|
||||||
|
|
||||||
LowPassFilter<Vector> gyroBiasFilter(0.001);
|
|
||||||
|
|
||||||
void setupIMU() {
|
void setupIMU() {
|
||||||
print("Setup IMU\n");
|
print("Setup IMU\n");
|
||||||
imu.begin();
|
imu.begin();
|
||||||
@@ -52,6 +50,8 @@ void readIMU() {
|
|||||||
void calibrateGyroOnce() {
|
void calibrateGyroOnce() {
|
||||||
static Delay landedDelay(2);
|
static Delay landedDelay(2);
|
||||||
if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary
|
if (!landedDelay.update(landed)) return; // calibrate only if definitely stationary
|
||||||
|
|
||||||
|
static LowPassFilter<Vector> gyroBiasFilter(0.001);
|
||||||
gyroBias = gyroBiasFilter.update(gyro);
|
gyroBias = gyroBiasFilter.update(gyro);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
14
flix/lpf.h
14
flix/lpf.h
@@ -14,6 +14,15 @@ public:
|
|||||||
LowPassFilter(float alpha): alpha(alpha) {};
|
LowPassFilter(float alpha): alpha(alpha) {};
|
||||||
|
|
||||||
T update(const T input) {
|
T update(const T input) {
|
||||||
|
if (alpha == 1) { // filter disabled
|
||||||
|
return input;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!initialized) {
|
||||||
|
output = input;
|
||||||
|
initialized = true;
|
||||||
|
}
|
||||||
|
|
||||||
return output += alpha * (input - output);
|
return output += alpha * (input - output);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -22,6 +31,9 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
void reset() {
|
void reset() {
|
||||||
output = T(); // set to zero
|
initialized = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
bool initialized = false;
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -142,7 +142,7 @@ void handleMavlink(const void *_msg) {
|
|||||||
// send ack
|
// send ack
|
||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
mavlink_msg_param_value_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
mavlink_msg_param_value_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
|
||||||
m.param_id, getParameter(name), 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);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -59,7 +59,6 @@ Parameter parameters[] = {
|
|||||||
{"IMU_ACC_SCALE_X", &accScale.x},
|
{"IMU_ACC_SCALE_X", &accScale.x},
|
||||||
{"IMU_ACC_SCALE_Y", &accScale.y},
|
{"IMU_ACC_SCALE_Y", &accScale.y},
|
||||||
{"IMU_ACC_SCALE_Z", &accScale.z},
|
{"IMU_ACC_SCALE_Z", &accScale.z},
|
||||||
{"IMU_GYRO_BIAS_A", &gyroBiasFilter.alpha},
|
|
||||||
// estimate
|
// estimate
|
||||||
{"EST_ACC_WEIGHT", &accWeight},
|
{"EST_ACC_WEIGHT", &accWeight},
|
||||||
{"EST_RATES_LPF_A", &ratesFilter.alpha},
|
{"EST_RATES_LPF_A", &ratesFilter.alpha},
|
||||||
|
|||||||
@@ -6,7 +6,11 @@
|
|||||||
#include <SBUS.h>
|
#include <SBUS.h>
|
||||||
#include "util.h"
|
#include "util.h"
|
||||||
|
|
||||||
|
#ifdef ESP32C3
|
||||||
|
SBUS rc(Serial1);
|
||||||
|
#else
|
||||||
SBUS rc(Serial2);
|
SBUS rc(Serial2);
|
||||||
|
#endif
|
||||||
|
|
||||||
uint16_t channels[16]; // raw rc channels
|
uint16_t channels[16]; // raw rc channels
|
||||||
float channelZero[16]; // calibration zero values
|
float channelZero[16]; // calibration zero values
|
||||||
|
|||||||
@@ -13,7 +13,7 @@ lines = []
|
|||||||
|
|
||||||
print('Downloading log...')
|
print('Downloading log...')
|
||||||
count = 0
|
count = 0
|
||||||
dev.write('log dump\n'.encode())
|
dev.write('log\n'.encode())
|
||||||
while True:
|
while True:
|
||||||
line = dev.readline()
|
line = dev.readline()
|
||||||
if not line:
|
if not line:
|
||||||
|
|||||||
@@ -92,17 +92,17 @@ Full list of events:
|
|||||||
|-----|-----------|----------------|
|
|-----|-----------|----------------|
|
||||||
|`connected`|Connected to the drone||
|
|`connected`|Connected to the drone||
|
||||||
|`disconnected`|Connection is lost||
|
|`disconnected`|Connection is lost||
|
||||||
|`armed`|Armed state update|Armed state *(bool)*|
|
|`armed`|Armed state update|Armed state (*bool*)|
|
||||||
|`mode`|Flight mode update|Flight mode *(str)*|
|
|`mode`|Flight mode update|Flight mode (*str*)|
|
||||||
|`landed`|Landed state update|Landed state *(bool)*|
|
|`landed`|Landed state update|Landed state (*bool*)|
|
||||||
|`print`|The drone prints text to the console|Text|
|
|`print`|The drone prints text to the console|Text|
|
||||||
|`attitude`|Attitude update|Attitude quaternion *(list)*|
|
|`attitude`|Attitude update|Attitude quaternion (*list*)|
|
||||||
|`attitude_euler`|Attitude update|Euler angles *(list)*|
|
|`attitude_euler`|Attitude update|Euler angles (*list*)|
|
||||||
|`rates`|Angular rates update|Angular rates *(list)*|
|
|`rates`|Angular rates update|Angular rates (*list*)|
|
||||||
|`channels`|Raw RC channels update|Raw RC channels *(list)*|
|
|`channels`|Raw RC channels update|Raw RC channels (*list*)|
|
||||||
|`motors`|Motor outputs update|Motor outputs *(list)*|
|
|`motors`|Motor outputs update|Motor outputs (*list*)|
|
||||||
|`acc`|Accelerometer update|Accelerometer output *(list)*|
|
|`acc`|Accelerometer update|Accelerometer output (*list*)|
|
||||||
|`gyro`|Gyroscope update|Gyroscope output *(list)*|
|
|`gyro`|Gyroscope update|Gyroscope output (*list*)|
|
||||||
|`mavlink`|Received MAVLink message|Message object|
|
|`mavlink`|Received MAVLink message|Message object|
|
||||||
|`mavlink.<message_name>`|Received specific MAVLink message|Message object|
|
|`mavlink.<message_name>`|Received specific MAVLink message|Message object|
|
||||||
|`mavlink.<message_id>`|Received specific MAVLink message|Message object|
|
|`mavlink.<message_id>`|Received specific MAVLink message|Message object|
|
||||||
@@ -277,3 +277,7 @@ logger = logging.getLogger('flix')
|
|||||||
logger.setLevel(logging.DEBUG) # be more verbose
|
logger.setLevel(logging.DEBUG) # be more verbose
|
||||||
logger.setLevel(logging.WARNING) # be less verbose
|
logger.setLevel(logging.WARNING) # be less verbose
|
||||||
```
|
```
|
||||||
|
|
||||||
|
## Stability
|
||||||
|
|
||||||
|
The library is in development stage. The API is not stable.
|
||||||
|
|||||||
Reference in New Issue
Block a user