# Гироскоп
Поддержание стабильного полета квадрокоптера невозможно без датчиков обратной связи. Важнейший из них — это **MEMS-гироскоп**. MEMS-гироскоп это микроэлектромеханический аналог классического механического гироскопа. Механический гироскоп состоит из вращающегося диска, который сохраняет свою ориентацию в пространстве. Благодаря этому эффекту возможно определить ориентацию объекта в пространстве. В MEMS-гироскопе нет вращающихся частей, и он помещается в крошечную микросхему. Он может измерять только текущую угловую скорость вращения объекта вокруг трех осей: X, Y и Z. |Механический гироскоп|MEMS-гироскоп| |-|-| |
|
|
MEMS-гироскоп обычно интегрирован в инерциальный модуль (IMU), в котором также находятся акселерометр и магнитометр. Модуль IMU часто называют 9-осевым датчиком, потому что он измеряет:
* Угловую скорость вращения по трем осям (гироскоп).
* Ускорение по трем осям (акселерометр).
* Магнитное поле по трем осям (магнитометр).
Flix поддерживает следующие модели IMU:
* InvenSense MPU-9250.
* InvenSense MPU-6500.
* InvenSense ICM-20948.
> [!NOTE]
> MEMS-гироскоп измеряет угловую скорость вращения объекта.
## Интерфейс подключения
Большинство модулей IMU подключаются к микроконтроллеру через интерфейсы I²C и SPI. Оба этих интерфейса являются *шинами данных*, то есть позволяют подключить к одному микроконтроллеру несколько устройств.
**Интерфейс I²C** использует два провода для передачи данных и тактового сигнала. Выбор устройства для коммуникации происходит при помощи передачи адреса устройства на шину. Разные устройства имеют разные адреса, и микроконтроллер может последовательно общаться с несколькими устройствами.
**Интерфейс SPI** использует два провода для передачи данных, еще один для тактового сигнала и еще один для выбора устройства. При этом для каждого устройства на шине выделяется отдельный GPIO-пин для выбора. В разных реализациях этот пин называется CS/NCS (Chip Select) или SS (Slave Select). Когда CS-пин устройства активен (напряжение на нем низкое), устройство выбрано для общения.
В полетных контроллерах IMU обычно подключают через SPI, потому что он обеспечивает значительно бо́льшую скорость передачи данных и меньшую задержку. Подключение IMU через интерфейс I²C (например, в случае нехватки пинов микроконтроллера) возможно, но не рекомендуется.
Подключение IMU к микроконтроллеру ESP32 через интерфейс SPI выглядит так:
|Пин платы IMU|Пин ESP32|
|-|-|
|VCC/3V3|3V3|
|GND|GND|
|SCL|IO18|
|SDA *(MOSI)*|IO23|
|SAO/AD0 *(MISO)*|IO19|
|NCS|IO5|
Кроме того, многие IMU могут «будить» микроконтроллер при наличии новых данных. Для этого используется пин INT, который подключается к любому GPIO-пину микроконтроллера. При такой конфигурации можно использовать прерывания для обработки новых данных с IMU, вместо периодического опроса датчика. Это позволяет снизить нагрузку на микроконтроллер в сложных алгоритмах управления.
> [!WARNING]
> На некоторых платах IMU, например, на ICM-20948, отсутствует стабилизатор напряжения, поэтому их нельзя подключать к пину VIN ESP32, который подает напряжение 5 В. Допустимо питание только от пина 3V3.
## Работа с гироскопом
Для взаимодействия с IMU, включая работу с гироскопом, в Flix используется библиотека *FlixPeriph*. Библиотека устанавливается через менеджер библиотек Arduino IDE:
Чтобы работать с IMU, используется класс, соответствующий модели IMU: `MPU9250`, `MPU6500` или `ICM20948`. Классы для работы с разными IMU имеют единообразный интерфейс для основных операций, поэтому возможно легко переключаться между разными моделями IMU. Датчик MPU-6500 практически полностью совместим с MPU-9250, поэтому фактически класс `MPU9250` поддерживает обе модели.
## Ориентация осей гироскопа
Данные с гироскопа представляют собой угловую скорость вокруг трех осей: X, Y и Z. Ориентацию этих осей у IMU InvenSense можно легко определить по небольшой точке в углу чипа. Оси координат и направление вращения для измерений гироскопа обозначены на диаграмме:
## Конфигурация гироскопа
В коде Flix настройка IMU происходит в функции `configureIMU`. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплов и частота LPF-фильтра.
### Частота сэмплов
Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер.
Частота сэмплов устанавливается методом `setSampleRate()`. В Flix используется частота 1 кГц:
```cpp
IMU.setRate(IMU.RATE_1KHZ_APPROX);
```
Поскольку не все поддерживаемые IMU могут работать строго на частоте 1 кГц, в библиотеке FlixPeriph существует возможность приближенной настройки частоты сэмплов. Например, у IMU ICM-20948 при такой настройке реальная частота сэмплирования будет равна 1125 Гц.
Другие доступные для установки в библиотеке FlixPeriph частоты сэмплирования:
* `RATE_MIN` — минимальная частота сэмплов для конкретного IMU.
* `RATE_50HZ_APPROX` — значение, близкое к 50 Гц.
* `RATE_1KHZ_APPROX` — значение, близкое к 1 кГц.
* `RATE_8KHZ_APPROX` — значение, близкое к 8 кГц.
* `RATE_MAX` — максимальная частота сэмплов для конкретного IMU.
#### Диапазон измерений
Большинство MEMS-гироскопов поддерживают несколько диапазонов измерений угловой скорости. Главное преимущество выбора меньшего диапазона — бо́льшая чувствительность. В полетных контроллерах обычно выбирается максимальный диапазон измерений от –2000 до 2000 градусов в секунду, чтобы обеспечить возможность динамичных маневров.
В библиотеке FlixPeriph диапазон измерений гироскопа устанавливается методом `setGyroRange()`:
```cpp
IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);
```
### LPF-фильтр
IMU InvenSense могут фильтровать измерения на аппаратном уровне при помощи фильтра нижних частот (LPF). Flix реализует собственный фильтр для гироскопа, чтобы иметь больше гибкости при поддержке разных IMU. Поэтому для встроенного LPF устанавливается максимальная частота среза:
```cpp
IMU.setDLPF(IMU.DLPF_MAX);
```
## Калибровка гироскопа
Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения (*bias*) и случайный шум (*noise*):
\\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \\]
Для качественной работы подсистемы оценки ориентации и управления дроном необходимо оценить *bias* гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции `calibrateGyro()`. Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются *bias* гироскопа и в дальнейшем вычитаются из измерений.
Программа для вывода данных с гироскопа с калибровкой:
```cpp
#include
График данных с гироскопа в состоянии покоя после калибровки:
Откалиброванные данные с гироскопа вместе с данными с акселерометра поступают в *подсистему оценки состояния*.
## Дополнительные материалы
* [MPU-9250 datasheet](https://invensense.tdk.com/wp-content/uploads/2015/02/PS-MPU-9250A-01-v1.1.pdf).
* [MPU-6500 datasheet](https://invensense.tdk.com/wp-content/uploads/2020/06/PS-MPU-6500A-01-v1.3.pdf).
* [ICM-20948 datasheet](https://invensense.tdk.com/wp-content/uploads/2016/06/DS-000189-ICM-20948-v1.3.pdf).