← На главную

Памятка по декодированию PWM и PPM сигнала

Типичная радиоаппаратура работает как-то так. Есть передатчик (собственно, сама аппа) и приемник. Приемник с передатчиком общаются по какому-то своему протоколу, часто закрытому. Приемник декодирует этот протокол и передает положение ручек на аппаратуре дальше, например, полетному контроллеру (ПК) квадрокоптера. ПК и приемник общаются по своему протоколу, который должны понимать оба. В этом месте большой популярностью пользуются PWM и PPM. Есть и другие варианты, в частности, SBUS, DSM2 и DSX, но в рамках данной статьи мы рассмотрим только PWM и PPM.

PWM (Pulse Width Modulation), он же ШИМ, всем хорошо знаком. Раз в 20 мс по проводу передается положительный импульс, длительность которого определяет положение ручки. Длительность импульса около 1000 микросекунд соответствует одному крайнему положению, а 2000 микросекунд – другому крайнему положению. На практике присутствует некоторая ошибка измерения, из-за чего, в частности, полетный контроллер и аппаратура требуют калибровки. PWM прост и понятен, но плох тем, что требует отдельного провода на каждый канал (то есть, каждую ручку аппаратуры). Сейчас многие аппаратуры имеют 8 и более каналов, а значит при использовании PWM приходится использовать много проводов.

PPM (Pulse Position Modulation) – это такая попытка запихнуть много PWM сигналов в один провод, ну или, по крайней мере, мне лично нравится о нем так думать. PPM всегда передает короткие импульсы. Паузы между фронтами импульсов соответствуют длительности одного PWM сигнала. Сигналы передаются последовательно, сначала значение на первом канале, затем на втором, и так далее. Соответствие между PPM и PWM сигналами хорошо отражает следующая осциллограмма, записанная на Rigol DS1054Z:

Связь между PWM и PPM сигналами

Осциллограмма снята с приемника RadioLink R8EF, имеющего режим, при котором на два его пина подаются сигналы PPM и SBUS, а на остальные пины – PWM сигнал для каналов с 3 по 8. Поэтому PWM сигналы для каналов 1 и 2 не показаны. Тут можно видеть несколько интересных особенностей. Во-первых, данный конкретный приемник использует для логической единицы 3.3 В, хотя и питается от 5 В. Во-вторых, в нем PPM сигнал инвертирован по сравнению с тем, как его обычно рисуют на картинках (например, в этом треде). Как ни странно, все написанное выше про фронты импульсов при этом остается верным. В частности, на картинке курсорами выделены фронты, соответствующие PWM сигналу на 3 канале. При этом PPM сигнал оказывается смещенным относительно PWM сигналов, но вообще-то приемник и не обязан был их как-то синхронизировать.

PPM работает хорошо до тех пор, пока вы не пытаетесь засунуть в него больше 8 каналов. Если каналов больше, то либо сигналы начинают обновляться с задержкой больше 20 мс (как в случае с PWM), либо приходится «сжимать» сигналы, теряя их точность, либо использовать дополнительные провода. Я не видел, чтобы по PPM передавали больше 8 каналов.

Хорошо, теперь допустим, что я хочу управлять своим роботом при помощи радиоаппаратуры. Вот соответствующий код для PWM:

#include <Arduino.h> #include <PinChangeInt.h> #define NCHANNELS 8 #define CH1_PIN 5 // CH2_PIN = CH1_PIN + 1, etc volatile int pwm_value[NCHANNELS] = { 0 }; volatile int prev_time[NCHANNELS] = { 0 }; void rising(); void falling() { uint8_t pin = PCintPort::arduinoPin; PCintPort::attachInterrupt(pin, &rising, RISING); pwm_value[pin - CH1_PIN] = micros() - prev_time[pin - CH1_PIN]; } void rising() { uint8_t pin = PCintPort::arduinoPin; PCintPort::attachInterrupt(pin, &falling, FALLING); prev_time[pin-CH1_PIN] = micros(); } void setup() { for(uint8_t i = 0; i < NCHANNELS; i++) { pinMode(CH1_PIN + i, INPUT_PULLUP); PCintPort::attachInterrupt(CH1_PIN + i, &rising, RISING); } Serial.begin(9600); } void loop() { for(uint8_t i = 0; i < NCHANNELS; i++) Serial.println("ch" + String(i+1) + " = " + String(pwm_value[i])); Serial.println("----------------"); delay(1000); }

А это – код для PPM:

#include <Arduino.h> #include <PinChangeInt.h> #define PPM_PIN 6 #define MAX_CHANNELS 12 volatile int pwm_value[MAX_CHANNELS] = { 0 }; volatile int prev_time = 0; volatile int curr_channel = 0; volatile bool overflow = false; void rising() { int tstamp = micros(); /* overflow should never acutally happen, but who knows... */ if(curr_channel < MAX_CHANNELS) { pwm_value[curr_channel] = tstamp - prev_time; if(pwm_value[curr_channel] > 2100) { /* it's actually a sync */ pwm_value[curr_channel] = 0; curr_channel = 0; } else curr_channel++; } else overflow = true; prev_time = tstamp; } void setup() { pinMode(PPM_PIN, INPUT_PULLUP); PCintPort::attachInterrupt(PPM_PIN, &rising, RISING); Serial.begin(9600); } void loop() { for(uint8_t i = 0; i < MAX_CHANNELS; i++) Serial.println("ch" + String(i+1) + " = " + String(pwm_value[i])); if(overflow) Serial.println("OVERFLOW!"); Serial.println("----------------"); delay(1000); }

Код был проверен на радиоаппаратуре RadioLink T8FB и приемнике к ней R8EF. На следующем фото приемник, переведенный в режим PPM, подключен к Arduino Nano с залитой в нее прошивкой для PPM:

Arduino и декодирование PWM/PPM сигнала

Пример отладочного вывода по UART:

ch1 = 1492 ch2 = 1500 ch3 = 1508 ch4 = 1496 ch5 = 2000 ch6 = 996 ch7 = 1996 ch8 = 2000 ...

Назначение использованной выше библиотеки PinChangeInt должно быть понятно по коду. Она позволяет вешать прерывания на передний и задний фронты (нарастание и спад) сигнала на заданных пинах. Подробности об этой библиотеке можно найти здесь и здесь. Полная версия кода прошивок для декодирования PWM и PPM сигналов доступна на GitHub.

Вооруженные полученными здесь знаниями, мы можем не только управлять Arduino при помощи радиоаппаратуры, но и, например, паять перекодировщики PWM в/из PPM (если не хочется платить за готовые на AliExpress), или даже изготавливать собственные радиоаппаратуры на базе какого-нибудь NRF24L01 или иного радиомодуля.