Часть 4. Вертикальные контроллеры (Throttle Controller) в Ardupilot.
Внимание! “Актуально для ArduCopter 4.6.x (параметры других версий могут отличаться).”
Таблица соответствия для последующих версий 4.7.+:
PSC_ACCZ_*↔PSC_D_ACC_*PSC_VELZ_P↔PSC_D_VEL_PPSC_POSZ_P↔PSC_D_POS_P
Эта статья — четвёртая часть цикла по настройке ArduPilot. Сегодня мы будем разбирать тюнинг вертикальных контроллеров в ArduPilot. Мы рассмотрим настройку:
- контроллера тяги (throttle controller)
- контроллера вертикальной скорости (vertical velocity controller)
- контроллера вертикальной позиции (высоты / vertical position controller)
Этот материал будет опираться на теорию и практические аспекты PID-регулирования, которые мы подробно рассматривали в третьей части данной видео-серии, где мы занимались настройкой PID для контроллеров угловой скорости (rate) и ориентации (attitude). Поэтому, если вы ещё не смотрели тот выпуск, настоятельно рекомендую начать с него, а затем вернуться к этому уроку — так терминология и методика, которую мы будем применять, станут для вас гораздо понятнее.
Содержание данного урока ориентировано на энтузиастов и хоббийных пилотов, которые настраивают дроны с диаметром пропеллеров до примерно 8 дюймов. Если вы занимаетесь настройкой значительно более крупных и тяжёлых аппаратов для коммерческих, промышленных или иных профессиональных применений, эти уроки не для вас.
Место в серии. База → фильтры/гироскоп → rate‑PID → attitude → удержание высоты (этот урок) → Loiter → навигация по точкам. Каждый шаг опирается на предыдущий.
Содержание
- 1. Теория: как работает вертикальный стек контроллеров
- 2. Подготовка: логирование и инструменты
- 3. Тюнинг контроллера газа: пошаговый алгоритм
- 4. Контроллер вертикальной скорости (VELZ)
- 5. Контроллер вертикальной позиции (POSZ)
- 6. Диагностика: типичные симптомы и решения
- 7. Чек‑лист перед настройкой вертикальных контроллеров
1. Теория: как работает вертикальный стек контроллеров
Иерархия контроллеров
Вертикальное управление в ArduPilot построено как каскад из трёх уровней.
Сигнал проходит сверху вниз:
- Контроллер позиции (POSZ / Vertical Position Controller) — пропорциональный (только P). Преобразует ошибку по высоте в целевую вертикальную скорость (desired climb rate).
- Контроллер скорости (VELZ / Vertical Velocity Controller) — полноценный PID. Преобразует целевую скорость в целевое ускорение.
- Контроллер тяги (ACCZ / Throttle Controller) — PID с feedforward. Преобразует целевое ускорение в команду моторам (управление тягой / thrust output).
Контроллер газа (Throttle Controller): назначение, параметры и математическая модель
Контроллер газа (throttle controller, он же контроллер ускорения по оси Z / ACCZ) — нижний уровень вертикального стека. Его задача: преобразовать запрошенное вертикальное ускорение (requested vertical acceleration), предоставленное другими контурами управления или прямым вводом пилота, в выходную команду моторам (motor output / управление тягой / thrust command).
Контроллер включает в себя пропорциональную (P), интегральную (I), дифференциальную (D), прямую (feedforward / FF) и дифференциальную прямую (derivative feedforward / DFF) составляющие — точно так же, как и контроллеры угловой скорости (rate controllers), которые мы рассматривали в предыдущей части этой серии. И настраивается он точно таким же образом.
Математическая модель контроллера (упрощённо):
где:
- \(u(t)\) — выходной сигнал контроллера (команда моторам, управление тягой / thrust command);
- \(e(t) = r(t) - y(t)\) — ошибка регулирования (целевое ускорение минус фактическое измеренное ускорение);
- \(r(t)\) — целевое ускорение (reference / desired acceleration);
- \(y(t)\) — измеренное ускорение по оси Z (actual acceleration);
- \(K_p\) — коэффициент пропорциональной составляющей (P-gain);
- \(K_i\) — коэффициент интегральной составляющей (I-gain);
- \(K_d\) — коэффициент дифференциальной составляющей (D-gain);
- \(K_{ff}\)— коэффициент прямой связи (feedforward gain);
- \(K_{dff}\) — коэффициент дифференциальной прямой связи (derivative feedforward gain).
Параметры в ArduPilot
| Параметр (Full Parameter List) | Где найти в UI Mission Planner | Описание |
|---|---|---|
PSC_ACCZ_P |
Config → Extended Tuning → Throttle (Accel to Motor) → P, так же в Full Parameter List |
Пропорциональный коэффициент контроллера газа (тяги) / Proportional gain |
PSC_ACCZ_I |
Там же → I | Интегральный коэффициент контроллера газа (тяги) / Integral gain |
PSC_ACCZ_D |
Там же → D | Дифференциальный коэффициент контроллера газа (тяги) / Derivative gain |
PSC_ACCZ_FF |
Только Full Parameter List | Feedforward (прямая связь) — расширенный тюнинг / Feedforward gain |
PSC_ACCZ_D_FF |
Только Full Parameter List | Derivative Feedforward — расширенный тюнинг / Derivative feedforward gain |
PSC_ACCZ_FF и PSC_ACCZ_D_FF). Они требуются для сложных кейсов.2. Подготовка: логирование и инструменты
Необходимые настройки логирования
Для прохождения этого процесса настройки вам необходимо иметь корректно настроенные параметры логирования в ArduPilot. Если вы разбираете уроки серии по порядку, то вы уже выполнили эту подготовку, потому что мы рассматривали настройку логирования в начале второй части — тюнинга фильтров гироскопа (gyro filter tuning). Прежде чем приступать к настройке фильтров, мы подробно разбирались, как настроить все необходимые параметры логирования. Поэтому, если вы ещё не видели вторую часть, пожалуйста, вернитесь и ознакомтесь с ней, чтобы убедиться, что ваши настройки логирования корректны.
Где искать параметры в Mission Planner
Два пути доступа к параметрам:
- Быстрый (Extended Tuning): Config → Extended Tuning → разделы Throttle Accel to Motor, Throttle Rate, Altitude Hold.
- Полный (Full Parameter List): Config → Full Parameter List → поиск по имени (например,
PSC_ACCZ_P).
3. Тюнинг контроллера тяги: пошаговый алгоритм
Процесс, который мы будем проходить для настройки контроллера тяги, в точности соответствует процессу, который мы использовали для настройки контроллеров угловой скорости (rate controllers) в третьей части этой серии. Однако у нас будет одно существенное отличие: у нас не будет доступа к графикам ступенчатого отклика (step response plots) для контроллера газа, потому что они не генерируются инструментом PID Review Tool. Поэтому нам придётся настраивать контроллер газа, используя данные временны́х рядов (time series data), которые доступны в Mission Planner. Это делает задачу немного более сложной, но не настолько, чтобы с ней нельзя было справиться — мы уже знаем, как выполнять настройку по данным временны́х рядов из третьей части.
Порядко тот же:
- Мы начнём с настройки баланса между пропорциональной и дифференциальной составляющими (P:D balance)
- Затем будем увеличивать общие коэффициенты PID для уменьшения ошибки регулирования и получения более «плотного» отклика от контроллера газа,
- При необходимости, прозведем отдельную настройку интегральной составляющей (I-term).
Проведение Полётов для сбора данных
Условия выполнения полётов для настройки
- Режим полёта: Altitude Hold (Удержание высоты) или Loiter (Зависание) — Тюнинг удобнее делать в AltHold/Loiter, потому что вы вручную задаёте вертикальные команды, а контроллер высоты гарантированно активен.
- Тип манёвра: резкие вертикальные движения — быстро увеличивайте газ, заставляя дрон набирать высоту, затем быстро уменьшайте газ, заставляя дрон снижаться, и повторяйте этот цикл 3–5 раз.
- Амплитуда движения: достаточно 2–3 метров изменения высоты. Поскольку мы анализируем ускорение, а не скорость или позицию, дрон не должен значительно менять высоту в этих тестовых полётах.
- Длительность сбора данных: обычно вам не понадобится более 20–30 секунд данных для одного тестового полёта, так что процесс сбора может быть довольно быстрым — просто выполните несколько вертикальных рывков, скачайте лог, проанализируйте данные и внесите соответствующие корректировки в настройки.
Шаг 1: баланс P/D (PD balance)
Цель этого этапа: убрать осцилляции и добиться того, чтобы фактическое ускорение (зелёная линия на графике) повторяло целевое ускорение (красная линия) без «перелёта» (overshoot) и без заметного запаздывания (lag).
Порядок действий
- Скачайте лог с тестового полёта через USB: в Mission Planner перейдите в Data → DataFlash Logs → Download DataFlash Log.
- Откройте скачанный лог кнопкой Review a Log (также на вкладке Data).
- В открывшемся окне перейдите в правую часть интерфейса, найдите секцию PID A (это данные для контроллера высоты / контроллера газа).
- Активируйте отображение target (целевое ускорение) и actual (фактическое ускорение) для оси Z.
- Оцените график:
- Осцилляции, «гребёнка»: признак слишком высокого P-коэффициента или
нулевогоD-коэффициента по умолчанию. - Ниже
P = 0.5D = 0.
- Осцилляции, «гребёнка»: признак слишком высокого P-коэффициента или

- Запаздывание, «размазанность»: признак слишком низкого P-коэффициента или избыточного D-коэффициента.
- Идеальный результат: зелёная линия (actual) следует за красной (target) с минимальной задержкой и без колебаний.
НижеP = 0.25D = 0.005

- Внесите корректировки в параметры ⇑:
- Повторите полёт, скачайте новый лог, сравните графики.
Шаг 2: увеличение общих коэффициентов
Когда вы нашли корректный баланс между пропорциональной и дифференциальной составляющими для контроллера газа, можно приступать к «затягиванию» отклика — пропорциональному увеличению всех трёх коэффициентов (P, I, D) для уменьшения ошибки регулирования и получения более быстрой реакции.
Алгоритм масштабирования коэффициентов
Такой подход сохраняет соотношение между пропорциональным членом и дифференциальным членом, а также между пропорциональным и интегральным членами. Следовательно, характер переходного процесса контроллера остаётся неизменным — вы просто увеличиваете все коэффициенты одновременно, чтобы «затянуть» отклик и уменьшить ошибку PID.
- Увеличьте значения P, I и D одновременно на 10% (умножьте каждый на α = 1.1).
- Выполните короткий тестовый полёт с теми же вертикальными манёврами.
- Скачайте и проанализируйте лог: нет ли новых осцилляций, «дёрганий», шума в моторах.
- Повторяйте процедуру увеличения на 10% и тестирования до тех пор, пока не начнёте замечать признаки нестабильности.
- При первых признаках осцилляций — откатите значения на 10–20% назад для получения запаса устойчивости.
PSC_ACCZ_D контроллер начинает самовозбуждаться из-за шума измерений акселерометра. Если осцилляции появились после увеличения именно дифференциального коэффициента — снижайте его в первую очередь, не трогая остальные параметры.Шаг 3: тонкая настройка I-составляющей (опционально)
Интегральная составляющая (I-term) отвечает за устранение долгосрочной ошибки регулирования (например, медленный дрейф высоты при ветре или при изменении массы аппарата). У интегрального коэффициента обычно очень широкое окно устойчивости, поэтому часто значения по умолчанию оказывается достаточно для стабильной работы.
Когда и как настраивать I-член
- Настраивать, если: вы замечаете медленный дрейф высоты в режиме удержания (AltHold), или систематическую ошибку, которая накапливается после длительных манёвров.
- Метод: увеличивайте только коэффициент
PSC_ACCZ_Iшагами по 10%, контролируя лог после каждого изменения. - Критерий остановки: появление низкочастотных осцилляций (период 1–3 секунды) — это признак переинтегрирования (integral windup).
- Фиксация: откатите последнее увеличение на 10–20% для получения запаса устойчивости.
4. Контроллер вертикальной скорости (VELZ)
Контроллер вертикальной скорости (vertical velocity controller) располагается выше контроллера газа в иерархии вертикального стека. Он принимает целевую скорость (target velocity) от контроллера позиции и преобразует её в целевое ускорение (target acceleration), которое затем передаётся контроллеру газа.
Это ещё один PID-контроллер. Параметры можно найти в полном списке параметров (Full Parameter List). Они начинаются с префикса PSC_VELZ_, за которым следует обозначение составляющей: P, I, D. Также доступны параметры для прямой связи (feedforward), фильтрации ошибки и фильтрации производной, однако мы не будем подробно рассматривать их в этом уроке. Важно отметить, что в контроллере вертикальной скорости отсутствуют производная прямая связь (derivative feedforward) и фильтрация целевого значения (target filtering).
На практике нам не потребуется использовать все эти параметры для получения действительно качественного результата, потому что это PID-контроллер второго уровня (second stage PID controller) — то есть это PID-контроллер, который управляет другим PID-контуром (контроллером тяги). Требования к нему мягче: часто достаточно только пропорциональной составляющей.
Параметры и где их найти
| Параметр | Описание | Доступ в Mission Planner |
|---|---|---|
PSC_VELZ_P |
Пропорциональный коэффициент контроллера вертикальной скорости | Extended Tuning → Throttle Rate |
PSC_VELZ_I, PSC_VELZ_D |
Интегральный и дифференциальный коэффициенты для скорости | Только Full Parameter List |
PSC_VELZ_FF, PSC_VELZ_FLTD |
Feedforward и фильтр производной | Только Full Parameter List, расширенный тюнинг |
Методика настройки
- В Mission Planner откройте скачанный лог → перейдите в раздел CTune (справа в интерфейсе просмотра логов).
- Активируйте отображение параметров DCRT (Desired Climb Rate / Желаемая скорость набора высоты) и CRT (Climb Rate / Фактическая скорость набора высоты).
- Оцените совпадение кривых на графике:
- Идеальный результат: линии практически совпадают, фактическая скорость точно следует за целевой.
- Запаздывание отклика: увеличить
PSC_VELZ_Pна 10–20%. - Перерегулирование (overshoot): уменьшить
PSC_VELZ_Pили добавить немного дифференциальной составляющей (D).
- Для хоббийных сборок часто достаточно отрегулировать только пропорциональный член (P). Интегральную и дифференциальную составляющие оставьте по умолчанию, если нет явной необходимости в их корректировке.
5. Контроллер вертикальной позиции (POSZ)
Контроллер вертикальной позиции (vertical position controller) — верхний уровень вертикального стека. Это простой пропорциональный контроллер (только P-составляющая): он преобразует ошибку по высоте (разницу между желаемой и фактической высотой) в целевую вертикальную скорость (desired climb rate), которая передаётся вниз по цепочке контроллеру скорости.

Параметр и его влияние
Где найти параметр:
- Extended Tuning → Altitude Hold → Altitude to Climb Rate → P
- Или в Full Parameter List:
PSC_POSZ_P
Как подбирать значение
- Откройте лог в Mission Planner → раздел CTune.
- Активируйте отображение параметров DAlt (Desired Altitude / Желаемая высота) и Alt (Actual Altitude / Фактическая высота).
- Оцените реакцию системы на графике:
- Медленное, «вялое» слежение: увеличьте
PSC_POSZ_Pна 10–20% для более агрессивного отклика. - Перерегулирование (зелёная линия «перескакивает» красную, затем возвращается): уменьшите коэффициент на 10–20%.
- Стабильное совпадение: настройка завершена, параметр подобран корректно.
- Медленное, «вялое» слежение: увеличьте

PSC_POSZ_P = 1.0 уже даёт приемлемый результат. Меняйте его только при явной необходимости, если наблюдаете проблемы с удержанием высоты.6. Диагностика: типичные симптомы и решения
| Симптом | Вероятные причины | Решение |
|---|---|---|
| Осцилляции по высоте в режиме AltHold | Слишком высокий PSC_ACCZ_P; нулевой PSC_ACCZ_D; шум в акселерометре; неверный баланс P/D. |
Снизить P, добавить D (начать с 0.005). Проверить фильтры гироскопа/акселерометра (Урок 2). Перепроверить PD balance по графику target/actual. |
| Медленная реакция на газ (тягу), «задумчивость» при вертикальных командах | Низкий PSC_ACCZ_P; избыточный D; неверный баланс между членами. |
Увеличить общий масштаб коэффициентов (×1.1), проверить PD balance по графику target/actual. Убедиться, что нет чрезмерного демпфирования. |
| Дрейф высоты при удержании (медленное смещение) | Недостаточный I-член (PSC_ACCZ_I); внешние возмущения (ветер, изменение массы). |
Аккуратно увеличить PSC_ACCZ_I шагами по 10%. Проверить, не является ли дрейф следствием ветра (тогда это нормально и не требует коррекции). |
| VELZ: целевая и фактическая скорость не совпадают (DCRT ≠ CRT) | Неверный PSC_VELZ_P; проблемы на уровне контроллера газа (тяги); неверная настройка нижестоящего контура. |
Сначала убедиться, что контроллер газа отлажен. Затем подкорректировать PSC_VELZ_P ±10–20%. Проверить логи PID A перед настройкой VELZ. |
| POSZ: перерегулирование по высоте (Alt overshoots DAlt) | Слишком высокий PSC_POSZ_P. |
Уменьшить коэффициент на 10–20%, повторить тест. Проверить, что контроллеры нижних уровней стабильны. |
| Лог не показывает данные PID A / CTune | Неверные настройки логирования; режим полёта без вертикальных контроллеров (например, Acro); данные не записываются. | Проверить LOG_BITMASK, INS_LOG_BAT_OPT. Выполнять тесты только в AltHold/Loiter. Убедиться, что лог скачан через USB после полёта. |
7. Чек‑лист перед настройкой вертикальных контроллеров
Отметьте только подтверждённые действия. Пропуск пунктов — частая причина «необъяснимого» поведения, которое на самом деле имеет вполне конкретную причину.
| ✓ | Действие | Критерий выполнения |
|---|---|---|
| Логирование настроено | LOG_BITMASK, INS_LOG_BAT_OPT, INS_FAST_SAMPLE установлены корректно (см. Урок 2). |
|
| Rate/Attitude PID отлажены | Дрон стабилен в режимах Acro и Stabilize, нет вибраций, логи чистые (Урок 3). | |
| Понимаю иерархию вертикальных контроллеров | Знаю, что тюнинг идёт снизу вверх: ACCZ (газ) → VELZ (скорость) → POSZ (позиция). | |
| Полёты для ACCZ выполнены | Режим: AltHold/Loiter. Манёвр: резкие вертикальные движения. Длительность: 20–30 секунд данных. | |
| PD balance найден для контроллера газа | В разделе PID A график actual следует за target без осцилляций и с минимальной задержкой. | |
| Общие коэффициенты масштабированы | P/I/D увеличены синхронно (×1.1) до предела устойчивости, затем откат на 10–20% для запаса. | |
| I-член проверен (опционально) | Если настраивался — увеличен шагами по 10% до первых осцилляций, затем откат для стабильности. | |
| VELZ проверен в разделе CTune | DCRT и CRT совпадают, при необходимости подкорректирован PSC_VELZ_P. |
|
| POSZ проверен в разделе CTune | DAlt и Alt совпадают, PSC_POSZ_P подобран под желаемую агрессивность отклика. |
|
| Финальный комплексный тест | Короткий полёт в режимах AltHold и Loiter: высота держится, реакция на команды предсказуема, лог чистый. |










