mirror of
https://github.com/okalachev/flix.git
synced 2026-01-13 14:36:45 +00:00
Documentation and book updates
Improve the main list of features. Use lowercase imu variable for consistency with the firmware code. Minor fixes.
This commit is contained in:
@@ -21,15 +21,13 @@
|
|||||||
* Dedicated for education and research.
|
* Dedicated for education and research.
|
||||||
* Made from general-purpose components.
|
* Made from general-purpose components.
|
||||||
* Simple and clean source code in Arduino (<2k lines firmware).
|
* Simple and clean source code in Arduino (<2k lines firmware).
|
||||||
|
* Connectivity using Wi-Fi and MAVLink protocol.
|
||||||
* Control using USB gamepad, remote control or smartphone.
|
* Control using USB gamepad, remote control or smartphone.
|
||||||
* Wi-Fi and MAVLink support.
|
|
||||||
* Wireless command line interface and analyzing.
|
* Wireless command line interface and analyzing.
|
||||||
* Precise simulation with Gazebo.
|
* Precise simulation with Gazebo.
|
||||||
* Python library.
|
* Python library for scripting and automatic flights.
|
||||||
* Textbook on flight control theory and practice ([in development](https://quadcopter.dev)).
|
* Textbook on flight control theory and practice ([in development](https://quadcopter.dev)).
|
||||||
* *Position control (using external camera) and autonomous flights¹*.
|
* *Position control (planned)*.
|
||||||
|
|
||||||
*¹ — planned.*
|
|
||||||
|
|
||||||
## It actually flies
|
## It actually flies
|
||||||
|
|
||||||
|
|||||||
@@ -87,13 +87,13 @@ Flix поддерживает следующие модели IMU:
|
|||||||
#include <FlixPeriph.h>
|
#include <FlixPeriph.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
|
||||||
MPU9250 IMU(SPI);
|
MPU9250 imu(SPI);
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
bool success = IMU.begin();
|
bool success = imu.begin();
|
||||||
if (!success) {
|
if (!success) {
|
||||||
Serial.println("Failed to initialize IMU");
|
Serial.println("Failed to initialize the IMU");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
```
|
```
|
||||||
@@ -108,21 +108,21 @@ void setup() {
|
|||||||
#include <FlixPeriph.h>
|
#include <FlixPeriph.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
|
||||||
MPU9250 IMU(SPI);
|
MPU9250 imu(SPI);
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
bool success = IMU.begin();
|
bool success = imu.begin();
|
||||||
if (!success) {
|
if (!success) {
|
||||||
Serial.println("Failed to initialize IMU");
|
Serial.println("Failed to initialize the IMU");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
IMU.waitForData();
|
imu.waitForData();
|
||||||
|
|
||||||
float gx, gy, gz;
|
float gx, gy, gz;
|
||||||
IMU.getGyro(gx, gy, gz);
|
imu.getGyro(gx, gy, gz);
|
||||||
|
|
||||||
Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
|
Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
|
||||||
delay(50); // замедление вывода
|
delay(50); // замедление вывода
|
||||||
@@ -135,36 +135,36 @@ void loop() {
|
|||||||
|
|
||||||
## Конфигурация гироскопа
|
## Конфигурация гироскопа
|
||||||
|
|
||||||
В коде Flix настройка IMU происходит в функции `configureIMU`. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплов и частота LPF-фильтра.
|
В коде Flix настройка IMU происходит в функции `configureIMU`. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплирования и частота LPF-фильтра.
|
||||||
|
|
||||||
### Частота сэмплов
|
### Частота сэмплирования
|
||||||
|
|
||||||
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер.
|
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота, тем выше точность управления полетом, но и тем больше нагрузка на микроконтроллер.
|
||||||
|
|
||||||
Частота сэмплов устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
|
Частота сэмплирования устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
|
||||||
|
|
||||||
```cpp
|
```cpp
|
||||||
IMU.setRate(IMU.RATE_1KHZ_APPROX);
|
IMU.setRate(IMU.RATE_1KHZ_APPROX);
|
||||||
```
|
```
|
||||||
|
|
||||||
Поскольку не все поддерживаемые IMU могут работать строго на частоте 1 кГц, в библиотеке FlixPeriph существует возможность приближенной настройки частоты сэмплов. Например, у IMU ICM-20948 при такой настройке реальная частота сэмплирования будет равна 1125 Гц.
|
Поскольку не все поддерживаемые IMU могут работать строго на частоте 1 кГц, в библиотеке FlixPeriph существует возможность приближенной настройки частоты сэмплирования. Например, у IMU ICM-20948 при такой настройке реальная частота сэмплирования будет равна 1125 Гц.
|
||||||
|
|
||||||
Другие доступные для установки в библиотеке FlixPeriph частоты сэмплирования:
|
Другие доступные для установки в библиотеке FlixPeriph частоты сэмплирования:
|
||||||
|
|
||||||
* `RATE_MIN` — минимальная частота сэмплов для конкретного IMU.
|
* `RATE_MIN` — минимальная частота для конкретного IMU.
|
||||||
* `RATE_50HZ_APPROX` — значение, близкое к 50 Гц.
|
* `RATE_50HZ_APPROX` — значение, близкое к 50 Гц.
|
||||||
* `RATE_1KHZ_APPROX` — значение, близкое к 1 кГц.
|
* `RATE_1KHZ_APPROX` — значение, близкое к 1 кГц.
|
||||||
* `RATE_8KHZ_APPROX` — значение, близкое к 8 кГц.
|
* `RATE_8KHZ_APPROX` — значение, близкое к 8 кГц.
|
||||||
* `RATE_MAX` — максимальная частота сэмплов для конкретного IMU.
|
* `RATE_MAX` — максимальная частота для конкретного IMU.
|
||||||
|
|
||||||
#### Диапазон измерений
|
#### Диапазон измерений
|
||||||
|
|
||||||
Большинство MEMS-гироскопов поддерживают несколько диапазонов измерений угловой скорости. Главное преимущество выбора меньшего диапазона — бо́льшая чувствительность. В полетных контроллерах обычно выбирается максимальный диапазон измерений от –2000 до 2000 градусов в секунду, чтобы обеспечить возможность динамичных маневров.
|
Большинство MEMS-гироскопов поддерживают несколько диапазонов измерений угловой скорости. Главное преимущество выбора меньшего диапазона — бо́льшая чувствительность. В полетных контроллерах обычно выбирается максимальный диапазон измерений от –2000 до 2000 градусов в секунду, чтобы обеспечить возможность быстрых маневров.
|
||||||
|
|
||||||
В библиотеке FlixPeriph диапазон измерений гироскопа устанавливается методом `setGyroRange()`:
|
В библиотеке FlixPeriph диапазон измерений гироскопа устанавливается методом `setGyroRange()`:
|
||||||
|
|
||||||
```cpp
|
```cpp
|
||||||
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
|
imu.setGyroRange(imu.GYRO_RANGE_2000DPS);
|
||||||
```
|
```
|
||||||
|
|
||||||
### LPF-фильтр
|
### LPF-фильтр
|
||||||
@@ -172,7 +172,7 @@ IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
|
|||||||
IMU InvenSense могут фильтровать измерения на аппаратном уровне при помощи фильтра нижних частот (LPF). Flix реализует собственный фильтр для гироскопа, чтобы иметь больше гибкости при поддержке разных IMU. Поэтому для встроенного LPF устанавливается максимальная частота среза:
|
IMU InvenSense могут фильтровать измерения на аппаратном уровне при помощи фильтра нижних частот (LPF). Flix реализует собственный фильтр для гироскопа, чтобы иметь больше гибкости при поддержке разных IMU. Поэтому для встроенного LPF устанавливается максимальная частота среза:
|
||||||
|
|
||||||
```cpp
|
```cpp
|
||||||
IMU.setDLPF(IMU.DLPF_MAX);
|
imu.setDLPF(imu.DLPF_MAX);
|
||||||
```
|
```
|
||||||
|
|
||||||
## Калибровка гироскопа
|
## Калибровка гироскопа
|
||||||
@@ -181,7 +181,7 @@ IMU.setDLPF(IMU.DLPF_MAX);
|
|||||||
|
|
||||||
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]
|
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]
|
||||||
|
|
||||||
Для качественной работы подсистемы оценки ориентации и управления дроном необходимо оценить *bias* гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции `calibrateGyro()`. Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются *bias* гироскопа и в дальнейшем вычитаются из измерений.
|
Для точной работы подсистемы оценки ориентации и управления дроном необходимо оценить *bias* гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции `calibrateGyro()`. Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются *bias* гироскопа и в дальнейшем вычитаются из измерений.
|
||||||
|
|
||||||
Программа для вывода данных с гироскопа с калибровкой:
|
Программа для вывода данных с гироскопа с калибровкой:
|
||||||
|
|
||||||
@@ -189,23 +189,23 @@ IMU.setDLPF(IMU.DLPF_MAX);
|
|||||||
#include <FlixPeriph.h>
|
#include <FlixPeriph.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
|
||||||
MPU9250 IMU(SPI);
|
MPU9250 imu(SPI);
|
||||||
|
|
||||||
float gyroBiasX, gyroBiasY, gyroBiasZ; // bias гироскопа
|
float gyroBiasX, gyroBiasY, gyroBiasZ; // bias гироскопа
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
bool success = IMU.begin();
|
bool success = imu.begin();
|
||||||
if (!success) {
|
if (!success) {
|
||||||
Serial.println("Failed to initialize IMU");
|
Serial.println("Failed to initialize the IMU");
|
||||||
}
|
}
|
||||||
calibrateGyro();
|
calibrateGyro();
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
float gx, gy, gz;
|
float gx, gy, gz;
|
||||||
IMU.waitForData();
|
imu.waitForData();
|
||||||
IMU.getGyro(gx, gy, gz);
|
imu.getGyro(gx, gy, gz);
|
||||||
|
|
||||||
// Устранение bias гироскопа
|
// Устранение bias гироскопа
|
||||||
gx -= gyroBiasX;
|
gx -= gyroBiasX;
|
||||||
@@ -226,9 +226,9 @@ void calibrateGyro() {
|
|||||||
|
|
||||||
// Получение 1000 измерений гироскопа
|
// Получение 1000 измерений гироскопа
|
||||||
for (int i = 0; i < samples; i++) {
|
for (int i = 0; i < samples; i++) {
|
||||||
IMU.waitForData();
|
imu.waitForData();
|
||||||
float gx, gy, gz;
|
float gx, gy, gz;
|
||||||
IMU.getGyro(gx, gy, gz);
|
imu.getGyro(gx, gy, gz);
|
||||||
gyroBiasX += gx;
|
gyroBiasX += gx;
|
||||||
gyroBiasY += gy;
|
gyroBiasY += gy;
|
||||||
gyroBiasZ += gz;
|
gyroBiasZ += gz;
|
||||||
|
|||||||
@@ -42,7 +42,7 @@ Pilot inputs are interpreted in `interpretControls()`, and then converted to the
|
|||||||
|
|
||||||
* `attitudeTarget` *(Quaternion)* — target attitude of the drone.
|
* `attitudeTarget` *(Quaternion)* — target attitude of the drone.
|
||||||
* `ratesTarget` *(Vector)* — target angular rates, *rad/s*.
|
* `ratesTarget` *(Vector)* — target angular rates, *rad/s*.
|
||||||
* `ratesExtra` *(Vector)* — additional (feed-forward) angular rates , used for yaw rate control in STAB mode, *rad/s*.
|
* `ratesExtra` *(Vector)* — additional (feed-forward) angular rates, used for yaw rate control in STAB mode, *rad/s*.
|
||||||
* `torqueTarget` *(Vector)* — target torque, range [-1, 1].
|
* `torqueTarget` *(Vector)* — target torque, range [-1, 1].
|
||||||
* `thrustTarget` *(float)* — collective motor thrust target, range [0, 1].
|
* `thrustTarget` *(float)* — collective motor thrust target, range [0, 1].
|
||||||
|
|
||||||
|
|||||||
@@ -143,7 +143,7 @@ Before flight you need to calibrate the accelerometer:
|
|||||||
* The `accel` and `gyro` fields should change as you move the drone.
|
* The `accel` and `gyro` fields should change as you move the drone.
|
||||||
* The `landed` field should be `1` when the drone is still on the ground and `0` when you lift it up.
|
* The `landed` field should be `1` when the drone is still on the ground and `0` when you lift it up.
|
||||||
|
|
||||||
2. Check the attitude estimation: connect to the drone using QGroundControl, rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. Attitude indicator in QGroundControl is shown below:
|
2. Check the attitude estimation: connect to the drone using QGroundControl, rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. Attitude indicator (in *large vertical* mode) in QGroundControl is shown below:
|
||||||
|
|
||||||
<img src="img/qgc-attitude.png" height="200">
|
<img src="img/qgc-attitude.png" height="200">
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user