[Из песочницы] От Винта! Или РПО ВИШ на Arduino
Предложили мне сделать прототип регулятора постоянных оборотов (РПО) для прототипа винта изменяемого шага (ВИШ) небольшого летательного аппарата (ЛА).
Что имеем: ЛА — Аэропоракт А-27М, двигатель Rotax 912, прототип ВИШ с электрическим приводом.
Что требуется: Изготовить прототип РПО, который должен уметь поддерживать заранее заданные обороты — 3 режима, иметь возможность в ручную управлять шагом винта, иметь индикаторы увеличения\уменьшения шага винта и индикаторы срабатывания концевых переключателей.
Задача РПО сводится к изменению угла установки лопастей (шаг винта) в зависимости от режима полета, таким образом, чтобы обороты винта всегда оставались постоянными. В зависимости от скорости горизонтального полета шаг винта меняется от ᵠ мин. до ᵠ макс. На взлетном режиме при нулевой горизонтальной скорости шаг винта минимален. По мере увеличения горизонтальной скорости угол атаки лопасти уменьшается (угол атаки на рисунке не показан, но он примерно равен ᵠ мин.). Уменьшается сопротивление вращению — винт «облегчается». Обороты двигатель начинают возрастать, РПО увеличивает шаг винта, при этом увеличивается сопротивление вращению винта — винт «затяжеляется». Обороты двигатель падают. Так РПО поддерживает заданные обороты.
Изменение угла установки лопастей, производится при помощи электрического привода. Для принятия решения о том, в какую сторону, и с какой скоростью вращать эл. двигатель привода, нужно знать только дельту, между текущей скоростью и заданной. РПО будет стремиться удерживать дельту в диапазоне от -60 до 60. При отрицательной дельте — уменьшается угол установки лопасти, при положительной — увеличивается. В идеале РПО должен стремиться держать нулевое значение, но на практике это невозможно, по многим причинам.
Для большей эффективности, скорость изменения угла установки, изменяется:
если дельта больше |150| скорость «MAX» — максимальнаяесли дельта больше |60| скорость «MIN» — минимальна
За основу регулятора, была взят Arduino. Я не стал прибегать к технологии Shieldsbuilding, а просто взял голый микроконтроллер, и залил туда загрузчик от Arduino. Использовал альтернативный загрузчик из пакета optiboot. Стандартный загрузчик некорректно работает с watchdog.
В качестве силовой части была использована пара полумостов BTS7960. Это очень сильно с запасом, но поскольку я старался сделать по максимуму надежную схему, выбор пал на них. Сигнал тахометра берется штатный с двигателя, подключил через оптрон 6N137, светодиод D6, гасит импульсы обратной полярности. Датчик тока ACS712–05A, используется только для определения срабатывания концевых выключателей. Ручное управление установки шага винта, реализовано программно, это не очень хорошо, но для первого прототипа вполне сгодится. Переключатель выбора режима работы, на уровне электрической схемы реализован так, чтобы при всех неопределенных положениях (интервал между соседними секциями контактов), интерпретировался как — ручной режим.
Плата была изготовлена по технологии Oracal, двухсторонняя, мне так легче разводить. Элементы с монтажом в отверстия, активно использовались для перехода на другую сторону платы. Поскольку плата не сложная, разводку делал прямо в CorelDRAW. Рисовал линиями нужной толщины, затем превращал их в контур. Очень удобно рисовать по сетке, в режиме точек, с шагом 1.27 мм, с включенной привязкой к сетке. Подготовленные контуры вырезал при помощи плоттера, на пленке Oracal. Монтажной пленкой перенес на заранее подготовленный текстолит. Немного кропотливой работы по удалению ненужных частей пленки, и плата готова к травлению. Далее все стандартно.
Корпус был изготовлен собственноручно владельцем ЛА, из листового полистирола толщиной 2 мм. Для экранирования от помех, был обклеен алюминиевой фольгой и подключен к общему проводу.
Для подбора оптимальных значений настроек РПО, была успешно проведена серия наземных и летных испытаний.
#include
volatile unsigned long micros_prev = 0; // Предидущее значение микросекунд long rpm_sum = 0; // Сумма накопленых N значений оборотов int rpm_val = 0; // Счетчик N int rpm = 0; // Тахометр int rpm_go = 0; // Заданные обороты int rpm_select = 0; // Переключатель режимов int rotor_left = 0; // Флаг вращения в лево int rotor_right = 0; // Флаг вращения в право int current = 0; // Датчик тока int current_left = 0; // Флаг факта наличия вращения в лево int current_right = 0; // Флаг факта наличия вращения в право
void setup () { wdt_disable (); // Отключаем wdt pinMode (2, INPUT); digitalWrite (2, HIGH); // RPM Сигнал с тахометра и подтяжка к + pinMode (4, INPUT); // IS Ошибка драйвера (обработка сигнала не реализована) pinMode (7, INPUT); digitalWrite (7, HIGH); // Step_down Малый шаг и подтяжка к + pinMode (8, INPUT); digitalWrite (8, HIGH); // Step_up Большой шаги подтяжка к + pinMode (13, OUTPUT); // Светодиод — Ручной режим «красный» pinMode (3, OUTPUT); // INH Разрешить крутить эл.двигатель pinMode (5, OUTPUT); // IN 1-ый полумост pinMode (6, OUTPUT); // IN 2-ой полумост pinMode (12, OUTPUT); // Светодиод — Большой шаг «зеленый» pinMode (11, OUTPUT); // Светодиод — Малый шаг «зеленый» pinMode (10, OUTPUT); // Светодиод — Большой шаг отбойник «красный» упор pinMode (9, OUTPUT); // Светодиод — Малый шаг отбойник «красный» упор attachInterrupt (0, RPM_IN, FALLING); // Активируем внешнее прерывание wdt_enable (WDTO_2S); // Включаем wdt с интервалом 2 секунды }
void loop () { wdt_reset (); // Сбрасывам счетчик wdt MODE (); CURR (); LED (); }
// Функция вращения в лево void LEFT () { digitalWrite (5, HIGH); digitalWrite (6, LOW); digitalWrite (3, HIGH); }
// Функция вращения в лево — скорость «MAX» (ШИМ) void LEFT_MAX () { digitalWrite (5, HIGH); digitalWrite (6, LOW); analogWrite (3, 200); }
// Функция вращения в лево — скорость «MIN» (ШИМ) void LEFT_MIN () { digitalWrite (5, HIGH); digitalWrite (6, LOW); analogWrite (3, 120); }
// Функция вращения в право void RIGHT () { digitalWrite (5, LOW); digitalWrite (6, HIGH); digitalWrite (3, HIGH); }
// Функция вращения в право — скорость «MAX» (ШИМ) void RIGHT_MAX () { digitalWrite (5, LOW); digitalWrite (6, HIGH); analogWrite (3, 200); }
// Функция вращения в право — скорость «MIN» (ШИМ) void RIGHT_MIN () { digitalWrite (5, LOW); digitalWrite (6, HIGH); analogWrite (3, 120); }
// Функция остановки эл.двигателя с торможением void STOP () { digitalWrite (5, LOW); digitalWrite (6, LOW); digitalWrite (3, HIGH); }
// Функция ручного режима void HAND () { if (digitalRead (7) == LOW) { LEFT (); // Крутим эл.двигатель в лево если нажата кнопка в лево rotor_left = 1; } else { rotor_left = 0; } if (digitalRead (8) == LOW) { RIGHT (); // Крутим эл.двигатель в право если нажата кнопка в право rotor_right = 1; } else { rotor_right = 0; } if (rotor_left == 0 && rotor_right == 0) { STOP (); // Остановка эл.двигателя если не нажата ни одна кнопка } }
// Функция автоматического режима void AUTO () { if ((micros () — micros_prev) > 1000000) { rpm = 0; } // Отработка вращения в лево if (rpm < rpm_go - 60) { if (rpm < rpm_go - 150) { LEFT_MAX (); } else { LEFT_MIN (); }; rotor_left = 1; } else { rotor_left = 0; } // Отработка вращения в право if (rpm > rpm_go + 60) { if (rpm > rpm_go + 150) { RIGHT_MAX (); } else { RIGHT_MIN (); }; rotor_right = 1; } else { rotor_right = 0; } // Отработка диапазона «stop» if (rotor_left == 0 && rotor_right == 0) { STOP (); } }
// Функция обработки переключателя режимов работы void MODE () { rpm_select = analogRead (0); if (rpm_select < 100) { rpm_go = 0; // Ручной режим } else { if (rpm_select > 800) { rpm_go = 5700; // Автоматический режим «Взлет/Посадка» } else { if (rpm_select > 450) { rpm_go = 5300; // Автоматический режим «Набор высоты» } else { rpm_go = 4600; // Автоматический режим «Круиз» } } } if (rpm_go == 0) { HAND (); } else { AUTO (); } }
// Функция распознавания направления вращения эл.двигателя void CURR () { for (int i = 0; i < 4; i++) { current = current + analogRead(1); } current = current / 5; if (current < 496) { current_left = 1; } else { current_left = 0; } if (current > 516) { current_right = 1; } else { current_right = 0; } }
// Функция отработки светодиодов void LED () { if (rpm_go == 0) { digitalWrite (13, HIGH); // Ручной режим } else { digitalWrite (13, LOW); } // Если эл.двигатель крутим в лево, а вращения нет, то включаем красный светодиод «Малый шаг» упор if (rotor_left == 1 && current_left == 0) { digitalWrite (11, LOW); digitalWrite (9, HIGH); } // Если эл.двигатель крутим в лево, то включаем зеленый светодиод «Малый шаг» else { if (rotor_left == 1) { digitalWrite (11, HIGH); digitalWrite (9, LOW); } else { digitalWrite (11, LOW); digitalWrite (9, LOW); } } // Если эл.двигатель крутим в право, а вращения нет, то включаем красный светодиод «Большой шаг» упор if (rotor_right == 1 && current_right == 0) { digitalWrite (12, LOW); digitalWrite (10, HIGH); } // Если эл.двигатель крутим в право, то включаем зеленый светодиод «Большой шаг» else { if (rotor_right == 1) { digitalWrite (12, HIGH); digitalWrite (10, LOW); } else { digitalWrite (12, LOW); digitalWrite (10, LOW); } } }
// Функция обработки сигнала с тахометра с усреднением данных void RPM_IN () { rpm_sum = rpm_sum + (60000000.0 / (micros () — micros_prev)); micros_prev = micros (); rpm_val++; if (rpm_val >= 10) { rpm = rpm_sum / 10; rpm_sum = 0; rpm_val = 0; } }