Flix

Flix — это проект по созданию открытого квадрокоптера на базе ESP32 с нуля и учебника по разработке полетных контроллеров.
Flix quadcopter

GitHub: github.com/okalachev/flix.

Telegram-канал: @opensourcequadcopter.

Архитектура прошивки

Firmware dataflow diagram

Главный цикл работает на частоте 1000 Гц. Передача данных между подсистемами происходит через глобальные переменные:

  • t (float) — текущее время шага, с.
  • dt (float) — дельта времени между текущим и предыдущим шагами, с.
  • gyro (Vector) — данные с гироскопа, рад/с.
  • acc (Vector) — данные с акселерометра, м/с2.
  • rates (Vector) — отфильтрованные угловые скорости, рад/с.
  • attitude (Quaternion) — оценка ориентации (положения) дрона.
  • controls (float[]) — пользовательские управляющие сигналы с пульта, нормализованные в диапазоне [-1, 1].
  • motors (float[]) — выходные сигналы на моторы, нормализованные в диапазоне [-1, 1] (возможно вращение в обратную сторону).

Исходные файлы

Исходные файлы прошивки находятся в директории flix. Ключевые файлы:

  • flix.ino — основной входной файл, скетч Arduino. Включает определение глобальных переменных и главный цикл.
  • imu.ino — чтение данных с датчика IMU (гироскоп и акселерометр), калибровка IMU.
  • rc.ino — чтение данных с RC-приемника, калибровка RC.
  • mavlink.ino — взаимодействие с QGroundControl через MAVLink.
  • estimate.ino — оценка ориентации дрона, комплементарный фильтр.
  • control.ino — управление ориентацией и угловыми скоростями дрона, трехмерный двухуровневый каскадный PID-регулятор.
  • motors.ino — управление выходными сигналами на моторы через ШИМ.

Вспомогательные файлы включают:

  • vector.h, quaternion.h — реализация библиотек векторов и кватернионов проекта.
  • pid.h — реализация общего ПИД-регулятора.
  • lpf.h — реализация общего фильтра нижних частот.

Гироскоп

Файл прошивки Flix: imu.ino (каноничная версия).
Текущая версия: imu.ino.

Поддержание стабильного полета квадрокоптера невозможно без датчиков обратной связи. Важнейший из них — это MEMS-гироскоп. MEMS-гироскоп это микроэлектромеханический аналог классического механического гироскопа.

Механический гироскоп состоит из вращающегося диска, который сохраняет свою ориентацию в пространстве. Благодаря этому эффекту возможно определить ориентацию объекта в пространстве.

В MEMS-гироскопе нет вращающихся частей, и он помещается в крошечную микросхему. Он может измерять только текущую угловую скорость вращения объекта вокруг трех осей: X, Y и Z.

Механический гироскопMEMS-гироскоп
Механический гироскопMEMS-гироскоп MPU-9250

MEMS-гироскоп обычно интегрирован в инерциальный модуль (IMU), в котором также находятся акселерометр и магнитометр. Модуль IMU часто называют 9-осевым датчиком, потому что он измеряет:

  • Угловую скорость вращения по трем осям (гироскоп).
  • Ускорение по трем осям (акселерометр).
  • Магнитное поле по трем осям (магнитометр).

Flix поддерживает следующие модели IMU:

  • InvenSense MPU-9250.
  • InvenSense MPU-6500.
  • InvenSense ICM-20948.
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/3V33V3
GNDGND
SCLIO18
SDA (MOSI)IO23
SAO/AD0 (MISO)IO19
NCSIO5

Кроме того, многие IMU могут «будить» микроконтроллер при наличии новых данных. Для этого используется пин INT, который подключается к любому GPIO-пину микроконтроллера. При такой конфигурации можно использовать прерывания для обработки новых данных с IMU, вместо периодического опроса датчика. Это позволяет снизить нагрузку на микроконтроллер в сложных алгоритмах управления.

На некоторых платах 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 можно легко определить по небольшой точке в углу чипа. Оси координат и направление вращения для измерений гироскопа обозначены на диаграмме:

Оси координат IMU

Расположение осей координат в популярных платах IMU:

GY-91MPU-92/65ICM-20948
Оси координат платы GY-91Оси координат платы MPU-9265Оси координат платы ICM-20948

Магнитометр IMU InvenSense обычно является отдельным устройством, интегрированным в чип, поэтому его оси координат могут отличаться. Библиотека FlixPeriph скрывает это различие и приводит данные с магнитометра к системе координат гироскопа и акселерометра.

Чтение данных

Интерфейс библиотеки FlixPeriph соответствует стилю, принятому в Arduino. Для начала работы с IMU необходимо создать объект соответствующего класса и вызвать метод begin(). В конструктор класса передается интерфейс, по которому подключен IMU (SPI или I²C):

#include <FlixPeriph.h>
#include <SPI.h>

MPU9250 IMU(SPI);

void setup() {
	Serial.begin(115200);
	bool success = IMU.begin();
	if (!success) {
		Serial.println("Failed to initialize IMU");
	}
}

Для однократного считывания данных используется метод read(). Затем данные с гироскопа получаются при помощи метода getGyro(x, y, z). Этот метод записывает в переменные x, y и z угловые скорости вокруг соответствующих осей в радианах в секунду.

Если нужно гарантировать, что будут считаны новые данные, можно использовать метод waitForData(). Этот метод блокирует выполнение программы до тех пор, пока в IMU не появятся новые данные. Метод waitForData() позволяет привязать частоту главного цикла loop к частоте обновления данных IMU. Это удобно для организации главного цикла управления квадрокоптером.

Программа для чтения данных с гироскопа и вывода их в консоль для построения графиков в Serial Plotter выглядит так:

#include <FlixPeriph.h>
#include <SPI.h>

MPU9250 IMU(SPI);

void setup() {
	Serial.begin(115200);
	bool success = IMU.begin();
	if (!success) {
		Serial.println("Failed to initialize IMU");
	}
}

void loop() {
	IMU.waitForData();

	float gx, gy, gz;
	IMU.getGyro(gx, gy, gz);

	Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
	delay(50); // замедление вывода
}

После запуска программы в Serial Plotter можно увидеть графики угловых скоростей. Например, при вращениях IMU вокруг вертикальной оси Z графики будут выглядеть так:

Конфигурация гироскопа

В коде Flix настройка IMU происходит в функции configureIMU. В этой функции настраиваются три основных параметра гироскопа: диапазон измерений, частота сэмплов и частота LPF-фильтра.

Частота сэмплов

Большинство IMU могут обновлять данные с разной частотой. В полетных контроллерах обычно используется частота обновления от 500 Гц до 8 кГц. Чем выше частота сэмплов, тем выше точность управления полетом, но и больше нагрузка на микроконтроллер. В Flix используется частота сэмплов 1 кГц.

Частота сэмплов устанавливается методом setSampleRate(). В Flix используется частота 1 кГц:

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():

IMU.setGyroRange(IMU.GYRO_RANGE_2000DPS);

LPF-фильтр

IMU InvenSense могут фильтровать измерения на аппаратном уровне при помощи фильтра нижних частот (LPF). Flix реализует собственный фильтр для гироскопа, чтобы иметь больше гибкости при поддержке разных IMU. Поэтому для встроенного LPF устанавливается максимальная частота среза:

IMU.setDLPF(IMU.DLPF_MAX);

Калибровка гироскопа

Как и любое измерительное устройство, гироскоп вносит искажения в измерения. Наиболее простая модель этих искажений делит их на статические смещения (bias) и случайный шум (noise):

\[ gyro_{xyz}=rates_{xyz}+bias_{xyz}+noise \]

Для качественной работы подсистемы оценки ориентации и управления дроном необходимо оценить bias гироскопа и учесть его в вычислениях. Для этого при запуске программы производится калибровка гироскопа, которая реализована в функции calibrateGyro(). Эта функция считывает данные с гироскопа в состоянии покоя 1000 раз и усредняет их. Полученные значения считаются bias гироскопа и в дальнейшем вычитаются из измерений.

Программа для вывода данных с гироскопа с калибровкой:

#include <FlixPeriph.h>
#include <SPI.h>

MPU9250 IMU(SPI);

float gyroBiasX, gyroBiasY, gyroBiasZ; // bias гироскопа

void setup() {
	Serial.begin(115200);
	bool success = IMU.begin();
	if (!success) {
		Serial.println("Failed to initialize IMU");
	}
	calibrateGyro();
}

void loop() {
	float gx, gy, gz;
	IMU.waitForData();
	IMU.getGyro(gx, gy, gz);

	// Устранение bias гироскопа
	gx -= gyroBiasX;
	gy -= gyroBiasY;
	gz -= gyroBiasZ;

	Serial.printf("gx:%f gy:%f gz:%f\n", gx, gy, gz);
	delay(50); // замедление вывода
}

void calibrateGyro() {
	const int samples = 1000;
	Serial.println("Calibrating gyro, stand still");

	gyroBiasX = 0;
	gyroBiasY = 0;
	gyroBiasZ = 0;

	// Получение 1000 измерений гироскопа
	for (int i = 0; i < samples; i++) {
		IMU.waitForData();
		float gx, gy, gz;
		IMU.getGyro(gx, gy, gz);
		gyroBiasX += gx;
		gyroBiasY += gy;
		gyroBiasZ += gz;
	}

	// Усреднение значений
	gyroBiasX = gyroBiasX / samples;
	gyroBiasY = gyroBiasY / samples;
	gyroBiasZ = gyroBiasZ / samples;

	Serial.printf("Gyro bias X: %f\n", gyroBiasX);
	Serial.printf("Gyro bias Y: %f\n", gyroBiasY);
	Serial.printf("Gyro bias Z: %f\n", gyroBiasZ);
}

График данных с гироскопа в состоянии покоя без калибровки. Можно увидеть статическую ошибку каждой из осей:

График данных с гироскопа в состоянии покоя после калибровки:

Откалиброванные данные с гироскопа вместе с данными с акселерометра поступают в подсистему оценки состояния.

Дополнительные материалы