Дело было вечером, делать было нечего ©
В данной статье речь пойдёт не о ракете в традиционном понимании, а об электроракете. Я проанализирую ряд гениальных, но в то же время ошибочных решений, которые были применены в процессе разработки, а также опишу, на какие космические препятствия я натолкнулся.
Сам придумываю себе проблемы ставлю задачу
Основной задачей для этого проекта я поставил перед собой взлет с руки на высоту порядка 50-100 метров, выпуск парашюта и безопасную посадку. В процессе полета должна осуществляться стабилизация по углам, минимизируя отклонения от вертикали, а также необходимо вести лог текущего самочувствия. В будущем мне хотелось бы установить камеру, чтобы почувствовать себя полукосмонавтом 👨🚀. Поскольку это испытательная летающая мини-лаборатория, я также намерен оснастить её датчиками, которые смогу отыскать, установить на борт и использовать в процессе экспериментов.
Выбор — самое сложное

Начать, как мне кажется, стоит с компоновки изделия. Этот этап я уже прошёл, рассмотрев несколько вариантов, и теперь готов поделиться своими измышлениями с тобой, мой дорогой читатель.
Сначала я взял листок бумаги и начал выплёскивать на него свои фантазии. Художник из меня, конечно, так себе, но в результате получился настоящий шедевр!

Нарисовал модельку, оценил моменты на рулях и момент винта.

Оказалось, что момент винта настолько велик, а рули — настолько малы, что для компенсации этого момента их необходимо отклонять на безобразно большие углы.

Мне это не очень понравилось, и перспектива борьбы с асимметрией вызывала определённые сомнения. В связи с этим было принято решение установить два винта, расположенных один за другим, для взаимной компенсации моментов. Так родилась новая конструкция.

Собственно, я вдохновился проектом Emil Jacobsen и решил адаптировать идеи под свой стиль, стремясь внести некоторые улучшения.
Конструкция всё ещё оставалась немного асимметричной: при одинаковых оборотах моторов момент одного винта не полностью компенсировался вторым. Однако это меня не остановило. Я отправил модельки на 3D-принтер, с нетерпением ожидая возможности повертеть в руках плоды своего виртуального творчества.
Ссылка, если не работает youtube.
После печати и кропотливой сборки я поместил изделие на весы, чтобы узнать максимальную тягу, на которую способны два сверхмощных моторчика. Оказалось, что они не так уж и мощны и тяга составила всего 450 граммов — этого очень мало. Кроме того, момент, который изменяется с оборотами, требует отдельного управления каждым мотором или компенсации с помощью рулей.
Помимо недостаточной тяги меня остановило и то, что конструкция получилась довольно «жидкой» и хрупкой, так как я старался экономить каждый грамм. К тому же, наличие множества механических частей не добавляло надёжности. Забегая немного вперёд, могу сказать, что это было правильное решение — изделие будет часто падать, и не всегда мягко. На самом деле, падения будут происходить довольно жестко. А 3D-печать не обеспечит необходимой прочности (имеется в виду домашняя FDM печать из АБС пластика), чтобы предотвратить безболезненное отрывание частей изделия при падении.
Зато какая красота получилась! Моторчики крутятся, рули отклоняются, люфтов нет. Если вас заинтересовала модель, можете скачать её по ссылке, которая находится в подписи под картинкой ниже.

Ссылка, если не работает youtube.
Однако даже с двумя винтами асимметрия всё равно имела место, и несовершенство конструкции не давало покоя. В итоге я разобрал это изделие, использовав сервоприводы для сборки метательного планера, а регуляторы оставил для следующей итерации. Всё пошло в дело и почти ничего не оказалось в корзине!
Насладившись экспериментами с тупиковой веткой развития, я решил использовать в качестве носителя базу квадрокоптера. И тут началось самое невероятное!
Прежде чем приступить к работе, я, естественно, полазил по интернету в поисках решений от других авторов и специалистов. В результате на Хабре наткнулся на одну интересную статью, в которой достаточно подробно изложены вопросы управления и математического описания. Поэтому я не буду углубляться в нюансы построения системы управления и методики, а постараюсь дополнить информацию тем, что не было раскрыто в статье. В ней действительно много полезного, и я акцентирую внимание на прикладных решениях и описании различных подходов.
Квадрореактивный НЛО
И тут я понял, что не оказался первооткрывателем. Если ввести в поисковике заветные два слова «rocket drone», то можно найти множество различных проектов. Я, конечно, ознакомился с ними, но ни в одном не увидел парашюта, а это, как мне кажется, крайне важно и необходимо (сарказм: важно только для меня).
Конечно же, первым делом я открыл свой любимый CAD и начал моделировать будущее изделие, основываясь на своих пожеланиях. Важными аспектами стали съёмный аккумулятор, возможность сборки электроники на столе с последующей установкой в корпус, удобная съёмная ручка и лёгкий доступ к электронике. Также я предусмотрел мгновенный доступ к USB-разъёму для прошивки платы без необходимости разборки устройства, а также отдельный отсек для парашюта — это основные элементы, которые должны быть реализованы.
Описывать инструменты CAD совершенно бесполезно, так как у каждой программы свои особенности и немного отличающиеся функции. Однако итоговый результат можно получить практически идентичный. На фото ниже вы можете увидеть получившуюся модель. Если вас заинтересовало, скачать её можно по следующей ссылке.


Основная часть корпуса имеет крестообразную форму и предназначена для установки проводки. В ней размещаются распаянные провода с регуляторами, моторами и необходимыми разъёмами.

Затем устанавливается верхняя крышка, на которой размещены плата управления и датчики и провода. Всё это с помощью разъёмов стыкуется с регуляторами оборотов, которые были установлены ранее вместе с моторами.

Крышка фиксируется изолентой (синей!!!, а иногда и чёрной). Да, я немного ленив и сразу не придумал, как реализовать быстросъём. На крышку также устанавливается отсек с системой спасения.

С противоположной стороны, то есть снизу, прикручивается адаптер-крышка.

В адаптер-крышку вкручивается удлинитель, в нижнюю часть которого устанавливается аккумуляторная батарея, после чего всё закрывается прикручивающейся крышкой.
Я изготовил несколько удлинителей для различных аккумуляторных батарей, так как они имеют разную массу. Это сделано для того, чтобы центр тяжести находился в районе моторов.
Система спасения
Система спасения состоит из парашюта и подвесной системы (строп). Мне очень не хотелось задействовать отдельный канал управления, поэтому я придумал центробежный выпуск парашюта. Да, вероятно, этот метод уже был разработан и реализован задолго до моего рождения, но в своём изделии я решил его применить.
Я смоделировал корпус с крышкой и пружиной. Отсек представляет собой цилиндр со створкой на петле и пружиной, что обеспечивает надежное и эффективное раскрытие парашюта.


На первом испытательном образце пружина крепилась с помощью винтов. Позже я решил упростить конструкцию и напечатать воедино проушины с корпусом и крышкой, добавив вторую проушину на корпусе. Теперь при сборке достаточно просто накинуть кольца пружины на эти проушины, что значительно облегчает процесс.

Осталось провести испытания, и мне было очень интересно узнать, на каких оборотах створка откроется и парашют вылетит. Расчёты показали, что скорость составит порядка 6,5 об/сек. Однако практика с теорией порой сильно разнится, поэтому необходимо испытать всё в реальных условиях, чтобы понять, как будет работать система.
Второй момент заключается в зависимости вращения корпуса от направления открытия крышки — по часовой стрелке и против часовой стрелки. Интересно выяснить, будет ли это влиять на скорость отдаления выброшенного в открытое воздушное пространство парашютного сгустка.
Ссылка, если не работает youtube.
При вращении попутно скорость открытия 5.9 об/сек
При вращении встречно скорость открытия 5,7 об/сек
Также было замечено невооружённым глазом, что при встречном открытии скорость отдаления парашютного сгустка несколько выше, чем при попутном. Видимо, это связано с тем, что крышка в последний момент скоротечного времени подталкивает парашют, способствуя его достижению первой космической скорости.
Теперь осталось протестировать систему в составе изделия. Для этого я закрепил её на стропе, проходящей вдоль фюзеляжа, и запустил одну диагональ моторов.
Ссылка, если не работает youtube.
Система управления, электроника
В качестве главной платы я выбрал ESP32, которая обладает множеством пинов для подключения различных датчиков и не требует слишком оптимизированного кода, что идеально подходит для моего не очень аккуратного программирования. Кроме того, она работает в среде Arduino IDE, что делает процесс разработки ещё проще.
Схема достаточно проста: в её основе лежит плата ESP32-DEVKIT V1, к которой подключены датчики, такие как датчик тока CJMCU-758, делитель напряжения из двух резисторов для измерения напряжения, датчик давления воздуха BME280 и гироскоп-акселерометр MPU-6050. Также в системе используются регуляторы оборотов BLHeli-s SPRING 30A ESC 2-6, приёмник FlySky FS-iA6B 6-канальный 2,4 ГГЦ.
На схеме ниже я просто взял готовые модули и соединил их между собой проводами, и, о чудо, это работает! Сам в шоке, не могу в это поверить, но это действительно так, и это факт.

Схема подключения всего оборудования выглядит гораздо компактнее, чем в реальной жизни. Это, вероятно, связано с тем, что в процессе сборки всё было не очень аккуратно. Тем не менее, на схеме представлена вся эта красота, которая демонстрирует, как гармонично соединены все компоненты.

Код
Я не программист в привычном понимании этого слова, поэтому некоторые из моих решений могут показаться странными профессионалам в этой области. Если у вас есть советы или подсказки, буду только рад — это поможет мне немного поумнеть.
Итак, барабанная дробь, вот он, код! Он состоит из 241 строки, и каждая из них содержит комментарий.
Код, длинный код, 241 строчка
//перечень используемых библиотек
#include <Servo.h>
#include "MPU6050.h" // подключаем библиотеку MPU6050
#include <Wire.h> // подключаем библиотекуработы с I2c
#include <BMP280_DEV.h> // подключаем библиотеку BMP280_DEV
#include <SPI.h> // подключаем библиотеку для работы с spi
#include <SD.h> // подключаем библиотеку для работы с sd картой
MPU6050 mpu; // не особо понимаааю что тут делаем...инициализируем, может
#include <EEPROM.h> // подключаем библиотеку для работы с внутренней памятью
#define EEPROM_SIZE 512 // Размер EEPROM (максимум 512 байт для ESP32)
//блок переменных (некоторые из них, возможно, не актуальны уже)
String DataSend, DataSendCOM, DataSendPoint, zagol; // создаю переменную для записи строки вывода в serial или SD
long time1, hThrottle, rThrottle, rRoll, hRoll, hPitch, rPitch, hYaw, rYaw; //задаю переменные типа long для счёта времени и переменные чтения данных с приёмника
int16_t ax, ay, az, gx, gy, gz, Zgx, Zgy, Zgz; // создаю переменные для MPU6050. int16_t т.к на DUE 32-битный контроллер, а надо 16 битное число
byte lognum; // переменная номера лога
int timeSD, i, ii=0, xx, yy, zz, sumGyroX, sumGyroY, sumGyroZ, periodSD=100, count=0; // создаю переменные для вычисления момента записи лога на sd карту
float gyroX, gyroY, gyroZ, axsi, aysi, azsi, gxsi, gysi, gzsi, avgGyroX, avgGyroY, avgGyroZ, spdZ, spdY, spdX, ctrlRoll_ang, ctrlPitch_ang, ctrlSpdZ, errRoll_d, errPitch_d; // создаю переменные для MPU6050 единицы g, градусы\сек
float temperature, pressure, zaltitude,altitude, altitudeRaw, rawAltitude, a_roll, a_pitch, a_yaw, g_roll, g_pitch, g_yaw , delta, dt, dt_avg, voltage, current, currentS; // Добавление переменных температуы давление, высоты
float airPress, T, Pst, alt, airspd, Pdin, Altzero, altZ, airspeedzero, airspdZ, roll, pitch, yaw, Z_roll, rawRoll, rawPitch, rawYaw , deltErRoll, deltErPitch; // переменные с двойной тчоностью для давления
double kp, ki, kd, kdz, kCtrl, Z_pitch, errorPitch, errorRoll, errorYaw,speedRollError, lasterrorYaw, integralPitch, integralRoll, lastErrorPitch, lastErrorRoll;
double servo1, servoFR, servoFL, servoBR, servoBLctrl, servoFRctrl, servoFLctrl, servoBRctrl, servoBL, servoDown, throttle, angle=0, CtrlPitch, CtrlRoll, CtrlYaw , incomingNumber; // ServoFR - front right т.е. управление передней правой сервой, винт правый !, аналогично остальные BL - back left -задняя правая
BMP280_DEV bmp280; // Создаём объект BMP280_DEV и настраиваем I2C (адрес 0x76) 77- для SPI
//Servo
Servo servo;
//
//цикл настроек и инициализаций датчиков
void setup() { // начало цикла настроек
Wire.begin(); // Подключаемся к шине i2c
pinMode(13, OUTPUT); // говорим, что 13 пин - выход
Serial.begin(115200); // запускаем монитор порта
bmp280.begin(BMP280_I2C_ALT_ADDR); // запускаем датчик давления
bmp280.setIIRFilter(IIR_FILTER_4); // Установить значение БИХ фильтра на 4
mpu.initialize(); // инциализируем MPU6050
mpu.setFullScaleAccelRange(MPU6050_ACCEL_FS_4); // диапазон акселерометра -4.. 4 g (может быть 2, 4, 6, 16)
mpu.setFullScaleGyroRange(MPU6050_GYRO_FS_1000); // диапазон гироскопа -500.. 500 град/сек (может быть 250, 500, 1000, 2000)
// смотрим какой номер лога в памяти, прибавляем к нему единиицу. при каждом включении платы такое происходит, чтобы лог писался в новый файл
EEPROM.begin(EEPROM_SIZE); // берём номер записи для запись лога
if (EEPROM.read(0) == 253) { // Если равно 253, записываем 0 в EEPROM
EEPROM.write(0, 0); // Если равно 253, записываем 0 в EEPROM
}
EEPROM.write(0, EEPROM.read(0)+1); // Читаем из EEPROM, прибавляем единицу и записываем по тому же адресу
EEPROM.commit(); // Сохраняем данные в EEPROM
lognum=EEPROM.read(0);
// записываю заголовок файла в csv файл
SD.begin(32);
File file = SD.open("/log_"+String(lognum)+".csv", FILE_APPEND);
zagol=String("millis, ms; iteration, ed; time_cycle, us; voltage, V; current, A; temp, oC; altitude, m; x,g; y,g; z,g; x,g/s; y,g/s; z,g/s; roll, grad; pitch,grad; yaw,grad;throttle, us; roll, us; pitch, us; yaw, us;servoFR, us; servoFL, us; servoBR, us; servoBL, us;"); // заголовок в лог
////zagol=String("millis, ms"+ " ms;"+"iteration"+ " ed;"+String("time_cycle")+" us;"+String("temp")+" oC");
file.println(zagol);
} // конец цикла настроек
//Начало основного цикла
void loop() { // начало основного цикла
time1 = micros(); // присваиваю переменной time1 значение в микросекундах начала работы программы
mpu.getMotion6(&ax, &ay, &az, &gx, &gy, &gz); // получаем данные с датчика, записываем в переменные
digitalWrite(13, HIGH); // 13 пин высокий уровень (сетодиод включаю)
i = ++i; // считаем количество циклов, каждая итерация +1
bmp280.startForcedConversion(); // запуска работы датчика давления
bmp280.getMeasurements(temperature, pressure, rawAltitude); // считыввание данных с датчика и запись в переменные
//цикл обнуления угловых скоростей с гироскопа
while (millis() < 4000) {
mpu.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);
bmp280.getMeasurements(temperature, pressure, zaltitude); // считыввание данных с датчика и запись в переменные, по высоте - для обнуления высоты
sumGyroX += gx; // вычисление суммарной угловой скорости
sumGyroY += gy ;
sumGyroZ += gz;
servo.writeMicroseconds(12, 900); // инициализация регуляторов оборота
servo.writeMicroseconds(13, 900);
servo.writeMicroseconds(14, 900);
servo.writeMicroseconds(15, 900);
ii=++ii;//вычисление количество тактов при измерении
delay(5); // Задержка между измерениями
zz=sumGyroZ;
// Усреднение значений
avgGyroX = sumGyroX / ii;
avgGyroY = sumGyroY / ii;
avgGyroZ = sumGyroZ / ii;
}
//Получение данных с приёмника по 3-м каналам
rThrottle = pulseIn(27, HIGH,3200); // 3 канал Считываем длительность импульса ШИМ на пине 2 с таймаутом 10 мс ПРОВЕРИТЬ, будет ли работать ? не работает, поменть на 27
rRoll = pulseIn(2, HIGH,3200); // 1 канал Считываем длительность импульса ШИМ на пине 2 с таймаутом 10 мс
rPitch = pulseIn(4, HIGH,3200); // 2 канал Считываем длительность импульса ШИМ на пине 2 с таймаутом 10 мс
rYaw = pulseIn(5, HIGH,3200); // 4 канал Считываем длительность импульса ШИМ на пине 2 с таймаутом 10 мс
//иногда, данные нулевые проскакивают, поэтому, чтобы этого не было, записываю нормальные значения в свои переменные
if (rPitch==0) {rPitch=hPitch;}
if (rThrottle==0) {rThrottle=hThrottle;}
if (rRoll==0) {rRoll=hRoll;}
if (rYaw==0) {rYaw=hYaw;}
hThrottle=rThrottle;
hRoll=rRoll;
hPitch=rPitch;
hYaw=rYaw;
// Вычисление углов, высоты
//перевод единиц в ускорение и угловую скорость
axsi=float(ax-417)/32768*4; // пересчёт единиц int единицы g. 4 -т.к. диапазон 4g + корректировка
aysi=float(ay+62)/32768*4; // пересчёт единиц int единицы g. 4 -т.к. диапазон 4g + корректировка
azsi=float(az+1700)/32768*4; // пересчёт единиц int единицы g. 4 -т.к. диапазон 4g + корректировка
gxsi=float(gx-avgGyroX)/32768*1000; // пересчёт единиц int в град/сек g. 1000 -т.к. диапазон 1000 град/сек
gysi=float(gy-avgGyroY)/32768*1000; // пересчёт единиц int град/сек g. 1000 -т.к. диапазон 1000 град/сек
gzsi=float(gz-avgGyroZ)/32768*1000; // пересчёт единиц int град/сек g. 1000 -т.к. диапазон 1000 град/сек
//Вычисление углов по акселерометрам
a_roll = atan2(aysi, azsi) * 180.0 / M_PI; //крен
a_pitch = atan2(axsi, azsi) * 180.0 / M_PI; //тангаж
//Вычисление углов по гироскопам, интегрирование
rawRoll += gxsi * dt; //крен
rawPitch += -gysi * dt;//тангаж
rawYaw += gzsi * dt;//курс
// Измерение и вычисление высоты
altitudeRaw=rawAltitude-zaltitude; // вычисление высоты относительно обнуленнной
// Pdin=(airPress/1024+0.04)/0.009; // вычисление динамического давления, в кПа
// airspd=sqrt((pow((Pdin/Pst+1),0.2857142857)-1)/0.2)*330; // расчёт воздушной скорости. 330 - скорость звука в воздухе. пересчитать нужно в зависииости от температуры
// Вычисление напряжения и тока
int sensorV = analogRead(A0); // Опрос датчика, отвечающего за измерение напряжение на акб
voltage = sensorV * (3.3 / 4095.0)*10.53; //вычисление напряжения
int sensorA = analogRead(A3); // Опрос датчика, отвечающего за тока
currentS = (sensorA-2920)/72.2; //* (3.3 / 4095.0)*1.0 вычисление тока
current = current* (1.0-0.1) +currentS*0.1; //усреднение тока,
// вычисление углов крена и тангажа, это комплиментарный фильтр опередения углов по
//гироскопу и акселерометру. веса настраивать нужно по месту, в зависимости от шумов
rawRoll = 0.985 * rawRoll + 0.015 * a_roll;
rawPitch = 0.985 * rawPitch + 0.015 * a_pitch;
// усреднение углов крена, тангажа, курса и высоты
roll = roll * (1.0 - 0.98) + rawRoll * 0.98; // 0,5 - коэффициент сглаживания , чем больше, тем меньше сглаживание
pitch = pitch * (1.0 - 0.98) + rawPitch* 0.98; // 0,5 - коэффициент сглаживания
yaw = yaw * (1.0 - 0.8) + rawYaw* 0.8; // 0,5 - коэффициент сглаживания
altitude=altitude*(1.0 - 0.25)+altitudeRaw*0.25;//усредненние высоты
spdZ=spdZ* (1.0 - 0.75) + gzsi* 0.75; // усреднение угловой скорости вокруг X для стабилизации оси Z, 0,75 - коэффициент сглаживания
spdY=spdY* (1.0 - 0.75) + gysi* 0.75; // усреднение угловой скорости вокруг Y для стабилизации оси Z, 0,75 - коэффициент сглаживания
spdX=spdX* (1.0 - 0.75) + gxsi* 0.75; // усреднение угловой скорости вокруг Z для стабилизации оси Z, 0,75 - коэффициент сглаживания
//Управление сервами
kp = 2.35; //1.9 Пропорциональный коэффициент крен/тангаж
ki =0.0350; //0.01 Интегральный коэффициент крен/тангаж
kd = 1.1; // 0.042Дифференциальный коэффициент крен/тангаж
kCtrl=0.450; //2.1коэффициент усиления управления пропорциональной составляющей
ctrlRoll_ang=(-1500+1500)/6; //вместо -1500 ставим rRoll вычитаю 1500, т.к середина 1500 мкс
ctrlPitch_ang=(-1500+1500)/6;// вместо -1500 ставим rPitch здесь должна юыть заданная угловая скорость//вычитаю 1500, т.к середина 1500 мкс, знак минус для изменения направления вращения. rPitch заданное угловое значение 1500 -это ноль (2000 - угол 50 градусов).
ctrlSpdZ=(rYaw-1500)*4.2;
errorRoll = -ctrlRoll_ang-roll; //вычисление разницы заданной и текущей угловой скосрости вокруг оси X (крен)
errorPitch = ctrlPitch_ang-pitch; //вычисление разницы заданной и текущей угловой скосрости вокруг оси Y (тангаж)
errorYaw = -ctrlSpdZ+spdZ;
integralPitch += errorPitch ; // Вычисляем интеграл ошибки углового положения по тангажу
integralPitch = constrain (integralPitch, -1000, 1000); //Ограничиваем интеграл
integralRoll += errorRoll ; // Вычисляем интеграл ошибки углового положения по крену
integralRoll = constrain (integralRoll, -1000, 1000); //Ограничиваем интеграл
CtrlYaw=errorYaw*0.1; //spdZ*kd;
errRoll_d=errRoll_d*(1-kCtrl)+(errorRoll-lastErrorRoll)*kCtrl;
CtrlRoll=errorRoll*kp+integralRoll*ki+kd*errRoll_d/dt_avg; //минус, т.к. нужно противовоздействие угловой скорости errorRoll* kp + integralRoll * ki
errPitch_d=errPitch_d*(1-kCtrl)+(errorPitch-lastErrorPitch)*kCtrl;
CtrlPitch=errorPitch*kp+integralPitch*ki+kd*errPitch_d/dt_avg; // и значение с ним - разница между заданной уголовой скоростью и текущей. ki
//Вычисление значений для управления мотрами
servoFR=(rThrottle-500)*1.5+CtrlPitch-CtrlRoll-CtrlYaw; //прибавить газ, тк. летим вверх, плюс тангаж, т.к мотор спереди и увеличение тангажа приведёт к положительному углу, аналогичнно с креном, по крусу мотор передний правый крутится по часовой стрелке, при увеличении оборотов момент будет против часовой стрелке, опэтому минус
servoFL=(rThrottle-500)*1.5+CtrlPitch+CtrlRoll+CtrlYaw;
servoBR=(rThrottle-500)*1.5-CtrlPitch-CtrlRoll+CtrlYaw;
servoBL=(rThrottle-500)*1.5-CtrlPitch+CtrlRoll-CtrlYaw;
//Находим наибольшее значение среди четырех переменных, если они больше 2000
if (servoFR > 2000 && servoFR > servoDown) {
servoDown = servoFR-2000; // Если servoFR больше 2000 и больше текущего servoDown, обновляем
}
if (servoFL > 2000 && servoFL > servoDown) {
servoDown = servoFL-2000; // Если servoFL больше 2000 и больше текущего servoDown, обновляем
}
if (servoBR > 2000 && servoBR > servoDown) {
servoDown = servoBR-2000; // Если servoBR больше 2000 и больше текущего servoDown, обновляем
}
if (servoBL > 2000 && servoBL > servoDown) {
servoDown = servoBL-2000; // Если servoBL больше 2000 и больше текущего servoDown, обновляем
}
if (servoFR <= 2000 && servoFL <= 2000 && servoBR <= 2000 && servoBL <= 2000) { // Проверяем, все ли значения меньше 2000
servoDown = 0; // Если все значения меньше или равны 2000, записываем 0
}
//Внесение поправки по первышению управляющего воздействия
servoFRctrl=servoFR-servoDown; //прибавить газ, тк. летим вверх, плюс тангаж, т.к мотор спереди и увеличение тангажа приведёт к положительному углу, аналогичнно с креном, по крусу мотор передний правый крутится по часовой стрелке, при увеличении оборотов момент будет против часовой стрелке, опэтому минус
servoFLctrl=servoFL-servoDown;
servoBRctrl=servoBR-servoDown;
servoBLctrl=servoBL-servoDown;
//Задание значений управления моторами
servo.writeMicroseconds(12, constrain (servoFLctrl, 900, 2000)); // servoFLctrl управление передним правым мотором, подклбюченного к 12 пину, ограничения от 900 до 2000 мкс
servo.writeMicroseconds(13, constrain (servoFRctrl, 900, 2000)); // servoFRctrl управление
servo.writeMicroseconds(14, constrain (servoBLctrl, 900, 2000)); // servoBLctrl управление
servo.writeMicroseconds(15, constrain (servoBRctrl, 900, 2000)); // servoBRctrl управление
//отправка в СОМ порт для просмотра переменных на компе
DataSendCOM= String(errorRoll,1)+" "+String(errRoll_d,1)+" "+String((errorPitch-lastErrorPitch)/dt_avg,2)+" "+String(dt,3)+" "+String(dt_avg,3); //datasend String(CtrlRoll,1)+"_"+String(CtrlPitch,1)+"_" +String(errorRoll,1)+"_" +String(errorPitch,1)+"_" +String(dt,4);
//формирование строки для записи на карту памяти
DataSend=String(millis())+";"+String(i)+";"+String(delta)+";"+String(voltage, 2)+";"+String(current, 2)+";"+String(temperature, 1)+";"+String(altitude, 1)+";" // формируем строку string и записываем её в переменную
+String(axsi)+";"+String(aysi)+";"+String(azsi)+";"+String(gxsi)+"; "+String(gysi)+";" +String(gzsi)+";"+String(roll,1)+";"+String(pitch,1)+";"+String(yaw,1)+";"+ //datasend
String(rThrottle)+";"+String(rRoll)+";"+String(rPitch)+";"+String(rYaw)+";"+String(servoFRctrl, 0)+";"+String(servoFLctrl, 0)+";"+String(servoBRctrl, 0)+";"+String(servoBLctrl, 0)+";";
DataSend.replace(".", ",");
DataSendPoint=DataSend;
Serial.println(DataSendCOM); // выводим полученные данные переменной DataSend в COM порт
//запись данных на карту памяти
if (SD.begin(32)) { // если карты нет, то ничего не делаем, даже не пытаемся записать
if (millis()-timeSD>=periodSD) // если разница времён больше заданного периода, то записываем данные на SD
{ timeSD=millis(); // записываю значение мс в перемменнную timeSD
SD.begin(32); // функция инициализирует библиотеку, присваивает контакт для сигнала (5)
File file = SD.open("/log_"+String(lognum)+".csv", FILE_APPEND); // открыть файл, который нужен для записи или чтения. Если нужный файл отсутствует на карте, то он будет создан
file.println(DataSendPoint); // печатает данные в файл до места, где появляется символ перевода каретки и пустая строка.
file.close();
}
} // закрывает файл, перед эти проверяет, сохранены ли данные на карту.
dt=delta/1000000;
dt_avg=dt_avg* (1.0 - 0.2) + dt* 0.2; // усреднение времени цикла. ( связано с большими временными затратами записи данных на флешку)
//delay(5);
delta = (micros() - time1); // вычисляем время выполнения цикла
//записываем полученные ошибки в новые переменные для работы D составляющей PID регулятора
lastErrorRoll = errorRoll; //запись ошибка заданной угловой скорости в переменную
lastErrorPitch = errorPitch; //запись ошибка заданной угловой скорости в переменную
lasterrorYaw = errorYaw; //запись ошибка заданной угловой скорости в переменную
}
Первые наземные запуски
Поскольку у меня не было никакого представления и опыта в проектировании подобных устройств, я не знал, как всё это будет работать в полётных условиях. У меня была уверенность, что с вероятностью 146% устройство не полетит и сразу сломается. Поэтому я решил проводить первые запуски мотором и тестирование стабилизации на подвесе. Это вносит свои коррективы, так как момент инерции сборки в целом становится несколько больше, чем у самого изделия. Однако это мелочи, которые можно будет проверить после отработки.

Вибрация - это боль
Вторая проблема, с которой я столкнулся, заключалась в вибрациях. Угловая скорость MEMS-гироскопа может зависеть от вибраций из-за эффекта вибрационной чувствительности, когда внешние колебания вызывают паразитные сигналы на выходе датчика. Особенно сильно это проявляется на резонансных частотах, когда вибрации приводят к дополнительным погрешностям в измерениях.
Для уменьшения влияния вибраций обычно применяется демпфирование, компенсационные алгоритмы и конструктивная оптимизация гироскопа. Именно с этой проблемой я столкнулся, и мне пришлось установить плату с акселерометром и гироскопом на виброизоляцию, чтобы минимизировать негативное воздействие вибраций.
Ссылка, если не работает youtube.
Ну вот, практически всё готово к полётам. Устройство управляется и демонстрирует довольно стабильную работу, по крайней мере, на земле, когда находится на верёвочном подвесе.
Ссылка, если не работает youtube.
Регулятор оборотов - это боль
Я столкнулся с проблемой: в какой-то момент настройки регулятора сбивались, и мне приходилось каждый раз его перенастраивать. Как оказалось, причина заключалась в том, что нужно было убрать галочку «Programming by Tx».
Иногда возникает необходимость настроить программируемый регулятор оборотов BLHeli. Для этого я буду использовать программатор BLHeliSuit-S/32.


Подключение регулятора к программатору осуществляется достаточно просто: разъём вставляется в программатор, при этом чёрный провод подключается к GND, а белый — к UART.
Программу для ПК использовал именно эту, так как другие версии почему-то не работают.
Важно помнить, что на регулятор необходимо подать питание, иначе успеха не будет.
После запуска интерфейс программы выглядит следующим образом:

После этого нажимаем кнопку Connect и затем Read Setup. В результате интерфейс у меня изменился на следующий:

Видимо, отображение интерфейса зависит от количества настроек в регуляторе. После внесения изменений в настройки необходимо нажать кнопку Write Setup.
Теперь наземные приключения завершены, проблемы остались позади. Добро пожаловать в поля!
Добрались до полётов и тестов в воздушном океане!
Первый вылет
Ну что ж, свершилось! Электрическая ракета, которая должна была стать венцом инженерной мысли, наконец-то оторвалась от земли. Однако, вместо того чтобы уверенно взмыть в небеса, она проявила непредсказуемое поведение, совершив эффектный кульбит вокруг моей головы, словно проверяя устойчивость конструкции. В результате, устройство направилось прямиком в ближайшую припаркованную машину. Похоже, что ракета восприняла парковку как нечто скучное и решила внести элемент экшена в свой первый полёт.
Погодные условия: темно, ветер 4-5 м/с, температура -2 градуса.
Ссылка, если не работает youtube.
Видео этого «культового мероприятия» уже, вероятно, станет настоящим мемом. На фото ниже вы можете увидеть результаты полета — обломки ракеты. Тем не менее, эта ситуация открывает возможности для анализа и улучшения, а также для дальнейшей работы над устранением выявленных недостатков.

Самое интересное заключается в том, что необходимо разобраться в причинах воздушного инцидента.
Логи, записанные в формате *.csv, можно сравнить с чёрным ящиком в самолёте: только вместо катастрофы над океаном у нас произошла авария на парковке. В этих логах можно увидеть, как электроракета, похоже, решила, что законы физики — это всего лишь рекомендации, и начала вращаться так, будто её запустили в центрифуге.

На графиках отчетливо видно, что угловая скорость росла, в то время как управляющие воздействия оставались на прежнем уровне. Похоже, ракета решила, что стабильность — это удел слабаков и выбрала свободный полёт. В результате она упала. Дважды. Ведь один раз — это случайность, а два — уже система.

Оказывается, я забыл изменить коэффициенты для полёта без подвеса. Момент инерции оказался больше, и изделие не смогло справиться с собственными характеристиками. Похоже, ракета решила, что если уж падать, то с размахом, и не просто упасть, а оставить след в истории — прямо в багажнике какой-то машины.

С одной стороны, это можно считать провалом. Однако с другой стороны, у меня теперь есть весомый аргумент для того, чтобы обновить корпус. Старый корпус, который мне никогда не нравился, теперь ещё и слегка помят. Но это открывает возможность создать новый, который будет не только эстетически привлекательнее, но и, возможно, менее подвержен поломкам.
Планы на будущие полёты включают несколько важных шагов: Во-первых, необходимо пересмотреть коэффициенты, чтобы ракета в следующий раз не решила устроить балет на парковке. Во-вторых, стоит улучшить корпус, чтобы он мог выдерживать не только сам полёт, но и мои нервы. И, наконец, нужно провести новые тесты, желательно вдалеке от машин и людей, чтобы минимизировать риски и обеспечить безопасность.
После нескольких дней размышлений о жизни и анализа цифр в логах, я пришёл к осознанию ещё одной проблемы, о которой знал, но совершенно забыл в ходе первых полётов. Ошибка скрыта в одной строчке кода (тот код, что выше, уже не имеет этого бага).
servoFL=(rThrottle-500)*1.5+CtrlPitch+CtrlRoll+CtrlYaw;
В процессе управления системой наблюдается, что сигнал rThrottle, поступающий с передатчика в диапазоне от 1000 до 2000 мкс, вызывает зашкаливание управляющего воздействия на передний левый мотор (servoFL) при значениях rThrottle, превышающих 1700 мкс. Это приводит к тому, что мотор работает на максимальных оборотах, что затрудняет стабилизацию углов и управление в целом.
Для предотвращения подобных ситуаций рекомендуется придерживаться следующих мер:
На этапе ручного управления следует избегать перемещения стика управления газом более, чем на половину его диапазона. Это поможет сохранить контроль над системой и предотвратить избыточное ускорение.
Необходимо внести изменения в код управления, чтобы при приближении любого управляющего сигнала к 2000 мкс автоматически снижался уровень газа на величину превышения. Это позволит сохранить стабильность управления и предотвратить неконтролируемое поведение моторов.
Данные меры помогут улучшить управляемость системы и обеспечить более безопасное функционирование в различных режимах работы.
Второй вылет
Ссылка, если не работает youtube.
Итоги второго полета
К сожалению, результаты второго полета оказались не такими успешными, как хотелось бы. Несмотря на все усилия, код не сработал должным образом и я снова столкнулся с проблемой зашкаливания. Это вызывает определенное разочарование, так как надеялся на более стабильную работу системы.
Согласно логам, при увеличении сигнала ШИМ до значения более 1735 мкс началось настоящее «веселье». Электроракета начала крутиться и вертеться, что свидетельствует о неконтролируемом поведении. Это подчеркивает необходимость дальнейшей доработки алгоритмов управления и тщательной настройки системы.
Продолжу анализировать полученные данные и искать решения для устранения этих проблем. Надеюсь, что в будущем удастся добиться более стабильных результатов и избежать подобных ситуаций.

Предложения по улучшению системы управления электроракеты.
В процессе анализа результатов второго полета я пришел к нескольким важным выводам, которые, на мой взгляд, помогут улучшить работу электроракеты и избежать проблем в будущем.
Исправление ошибок в перераспределении тяги и алгоритме управления.
Необходимо провести детальный анализ текущих алгоритмов, чтобы выявить и устранить возможные ошибки в перераспределении тяги. Это позволит добиться более стабильного поведения ракеты в полете и предотвратить неконтролируемые маневры.
Увеличение напряжения аккумуляторной батареи. В настоящее время используется аккумуляторная батарея формата 3S, однако для достижения лучших результатов целесообразно перейти на 4S. Это обеспечит большую мощность и улучшит общую производительность системы.
Оптимизация угла наклона моторов. Рассматриваю возможность изменения выкоса моторов для ускорения выброса парашюта. Увеличение угловой скорости при выбросе парашюта может значительно повысить эффективность системы и обеспечить более безопасное приземление.
Эти шаги помогут улучшить управление электроракетой и сделать полеты более предсказуемыми и безопасными. Надеюсь, что с их реализацией смогу достичь желаемых результатов в следующих испытаниях.
Третий вылет
Ссылка, если не работает youtube.
Важность укладки парашюта и строп в системе управления электроракеты.
В процессе работы над электроракетой я столкнулся с критически важным аспектом — укладкой парашюта и строп. Ранее я использовал метод, при котором стропы наматывались на сложенный парашют. Это создавало своеобразный «замедлитель»: при выбросе парашют вылетал, а стропы разматывались, что позволяло мне успеть выключить моторы до того, как возникали проблемы с запутыванием.
Однако в последнем испытании я решил сложить парашют отдельно от строп. При выпуске парашют вылетел, но, к сожалению, стропы не расправились должным образом и остались запутанными. Это привело к фатальному падению ракеты и её разрушению.
Этот опыт подчеркивает важность правильной укладки парашюта и строп для обеспечения безопасного приземления. В будущем необходимо вернуться к проверенному методу укладки, чтобы избежать подобных инцидентов и гарантировать надежность системы в критических ситуациях.
Рекомендации для достижения наилучших результатов. Итоги.
Для оптимизации работы электроракеты и повышения ее эффективности, я предлагаю следующие шаги:
Использование отдельного микроконтроллера для обработки данных. В настоящее время частота обновления данных с гироскопа, акселерометра и датчика давления составляет около 60 Гц. Однако при записи на SD‑карту (раз в 10 секунд) эта частота падает до 30 Гц. Выделение отдельного микроконтроллера для обработки данных позволит поддерживать стабильную частоту обновления и улучшить качество получаемой информации.
Изменение конструкции корпуса. Рекомендуется сделать стенки корпуса толще и/или предусмотреть каналы для карбоновых трубок, что позволит уменьшить габариты изделия. Это, в свою очередь, снизит момент инерции и улучшит управляемость ракеты.
Корректировка p‑составляющей ПИД‑регулятора. Увеличение p‑составляющей может значительно улучшить реакцию системы, однако это должно быть сделано с учетом первого пункта, чтобы избежать нежелательных колебаний.
Отдельный канал для выброса парашюта. Необходимо предусмотреть отсек для парашюта и реализовать его выброс через отдельный канал, что повысит надежность системы при приземлении.
Оптимизация конструкции амортизатора для датчика IMU6050. Изменение конструкции амортизатора поможет снизить влияние вибраций на показания гироскопа, что обеспечит более точные данные о положении ракеты.
Прописать зависимость коэффициентов ПИД‑регулятора от тяги и скорости. Существует мнение о том, что с увеличением скорости необходимо уменьшать коэффициенты ПИД‑регулятора. Необходимо провести анализ и прописать эту зависимость для более точной настройки системы.
Перераспределение «весов» управляющих воздействий. Следует изменить распределение управляющих воздействий общей тяги и управления ориентацией, чтобы они не мешали друг другу и обеспечивали более гармоничное функционирование системы.
Увеличение частоты записи логов. Запись логов с частотой 10 Гц является слишком медленной. Реализация первого пункта поможет увеличить эту частоту как минимум в 2–3 раза, что позволит получать более актуальные данные о состоянии системы.
Добавление информации о составляющих ПИД‑регулятора в логи. Включение данных о коэффициентах ПИД‑регулятора в запись логов позволит проводить более детальный анализ работы системы и выявлять возможные проблемы.
Эти рекомендации помогут значительно улучшить работу электроракеты и достичь лучших результатов в будущих испытаниях.
Конец
Буду рад услышать вашу критику и советы! Мне интересно узнать мнение о прочитанном. С удовольствием ознакомлюсь с вашими мыслями и эмоциями.
Также приглашаю вас подписаться на мой Telegram-канал. Тематика там разнообразная. В нем я периодически делюсь промежуточными результатами своих проектов. Буду рад видеть вас среди подписчиков и обмениваться идеями!