Выбор контроллера (18+ ШИМ, беспроводная связь, 3.3 логика, встроенный BEC)

тоже момент интересный. esp-now сам не реализует проверку контрольных сумм? или реализует только при использовании шифрования? думаю, вчитаясь внимательнее в описание сам ответ найду на этот вопрос. замучал я, да?)))

WiFi реализует.

1 лайк

В ESP-NOW для Arduino почему-то отсутствует тип данных esp_now_recv_info_t. По документации указатель на него должен быть первым параметром в колл-бэке, привязываемом esp_now_register_recv_cb(). Но в место этого там просто указатель на uint8_t по которому можно получить mac отправителя. Возможно, остальные данные тоже есть, я не пробовал двигать указатель “правее”. Такая вот особенность, просто для информации…

В общем, связь и ШИМ готово. На случай, если кому тоже интересно, кидаю готовое на данный момент

Код для пульта

#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include <Wire.h>

#include <esp_now.h>
#include <WiFi.h>

//#include <esp_adc/adc_oneshot.h>
//#include <esp_adc/adc_cali.h>
//#include <esp_adc/adc_cali_scheme.h>

const uint8_t FONT[91][5] PROGMEM = {
  { B00000000, B00000000, B00000000, B00000000, B00000000 },
  { B00000000, B00000000, B01011111, B00000000, B00000000 },
  { B00000000, B00000110, B00000000, B00000110, B00000000 },
  { B00010100, B00111110, B00010100, B00111110, B00010100 },
  { B01001000, B01010100, B11010110, B01010100, B00100100 },
  { B00100011, B00010011, B00001000, B01100100, B01100010 },
  { B00101000, B01010100, B01010100, B00100000, B01010000 },
  { B00000000, B00000000, B00000110, B00000000, B00000000 },
  { B00000000, B00011100, B00100010, B01000001, B00000000 },
  { B00000000, B01000001, B00100010, B00011100, B00000000 },
  { B00010100, B00001000, B00111110, B00001000, B00010100 },
  { B00001000, B00001000, B00111110, B00001000, B00001000 },
  { B00000000, B10000000, B01100000, B00000000, B00000000 },
  { B00001000, B00001000, B00001000, B00001000, B00001000 },
  { B00000000, B00000000, B01000000, B00000000, B00000000 },
  { B00100000, B00010000, B00001000, B00000100, B00000010 },
  { B00111110, B01010001, B01001001, B01000101, B00111110 },
  { B00000000, B01000010, B01111111, B01000000, B00000000 },
  { B01110010, B01001001, B01001001, B01001001, B01000110 },
  { B00100001, B01000001, B01001001, B01001101, B00110011 },
  { B00011000, B00010100, B00010010, B01111111, B00010000 },
  { B00100111, B01000101, B01000101, B01000101, B00111001 },
  { B00111100, B01001010, B01001001, B01001001, B00110001 },
  { B01000001, B00100001, B00010001, B00001001, B00000111 },
  { B00110110, B01001001, B01001001, B01001001, B00110110 },
  { B01000110, B01001001, B01001001, B00101001, B00011110 },
  { B00000000, B00000000, B00100100, B00000000, B00000000 },
  { B00000000, B10000000, B01100100, B00000000, B00000000 },
  { B00001000, B00010100, B00100010, B01000001, B00000000 },
  { B00010100, B00010100, B00010100, B00010100, B00010100 },
  { B00000000, B01000001, B00100010, B00010100, B00001000 },
  { B00000010, B00000001, B01011001, B00001001, B00000110 },
  { B00111110, B01000001, B01011101, B01010001, B01001110 },
  { B01111100, B00010010, B00010001, B00010010, B01111100 },
  { B01111111, B01001001, B01001001, B01001001, B00110110 },
  { B00111110, B01000001, B01000001, B01000001, B00100010 },
  { B01111111, B01000001, B01000001, B01000001, B00111110 },
  { B01111111, B01001001, B01001001, B01001001, B01000001 },
  { B01111111, B00001001, B00001001, B00001001, B00000001 },
  { B00111110, B01000001, B01000001, B01010001, B01110010 },
  { B01111111, B00001000, B00001000, B00001000, B01111111 },
  { B00000000, B01000001, B01111111, B01000001, B00000000 },
  { B00100000, B01000000, B01000001, B00111111, B00000001 },
  { B01111111, B00001000, B00010100, B00100010, B01000001 },
  { B01111111, B01000000, B01000000, B01000000, B01000000 },
  { B01111111, B00000010, B00011100, B00000010, B01111111 },
  { B01111111, B00000100, B00001000, B00010000, B01111111 },
  { B00111110, B01000001, B01000001, B01000001, B00111110 },
  { B01111111, B00001001, B00001001, B00001001, B00000110 },
  { B00111110, B01000001, B01010001, B00100001, B01011110 },
  { B01111111, B00001001, B00011001, B00101001, B01000110 },
  { B00100110, B01001001, B01001001, B01001001, B00110010 },
  { B00000001, B00000001, B01111111, B00000001, B00000001 },
  { B00111111, B01000000, B01000000, B01000000, B00111111 },
  { B00011111, B00100000, B01000000, B00100000, B00011111 },
  { B00111111, B01000000, B00111000, B01000000, B00111111 },
  { B01100011, B00010100, B00001000, B00010100, B01100011 },
  { B00000011, B00000100, B01111000, B00000100, B00000011 },
  { B01100001, B01010001, B01001001, B01000101, B01000011 },
  { B00000000, B01111111, B01000001, B01000001, B00000000 },
  { B00000010, B00000100, B00001000, B00010000, B00100000 },
  { B00000000, B01000001, B01000001, B01111111, B00000000 },
  { B00000100, B00000010, B00000001, B00000010, B00000100 },
  { B01000000, B01000000, B01000000, B01000000, B01000000 },
  { B00000000, B00000010, B00000100, B00000000, B00000000 },
  { B00100000, B01010100, B01010100, B01111000, B01000000 },
  { B01111111, B00101000, B01000100, B01000100, B00111000 },
  { B00111000, B01000100, B01000100, B01000100, B00101000 },
  { B00111000, B01000100, B01000100, B00101000, B01111111 },
  { B00111000, B01010100, B01010100, B01010100, B00011000 },
  { B00000000, B00001000, B01111110, B00001001, B00000010 },
  { B00011000, B10100100, B10100100, B10100100, B01111000 },
  { B01111111, B00010000, B00001000, B00001000, B01110000 },
  { B00000000, B01001000, B01111010, B01000000, B00000000 },
  { B00100000, B01000000, B01000000, B00111010, B00000000 },
  { B01111111, B00010000, B00101000, B01000100, B00000000 },
  { B00000000, B01000001, B01111111, B01000000, B00000000 },
  { B01111100, B00000100, B01111000, B00000100, B01111000 },
  { B01111100, B00001000, B00000100, B00000100, B01111000 },
  { B00111000, B01000100, B01000100, B01000100, B00111000 },
  { B11111100, B00101000, B01000100, B01000100, B00111000 },
  { B00111000, B01000100, B01000100, B00101000, B11111100 },
  { B01111100, B00001000, B00000100, B00000100, B00001000 },
  { B01001000, B01010100, B01010100, B01010100, B00100100 },
  { B00000100, B00000100, B00111110, B01000100, B00100100 },
  { B00111100, B01000000, B01000000, B00100000, B01111100 },
  { B00011100, B00100000, B01000000, B00100000, B00011100 },
  { B00111100, B01000000, B00111000, B01000000, B00111100 },
  { B01000100, B00101000, B00010000, B00101000, B01000100 },
  { B00001100, B01010000, B01010000, B01010000, B00111100 },
  { B01000100, B01100100, B01010100, B01001100, B01000100 }
};
  


class cScreen {

  public:

    void define () {

      Wire.begin();
      delay(200);
      Wire.setClock(8000000);
      Wire.beginTransmission(_address);
      Wire.write(0x00); // OLED_COMMAND_MODE режим отправки команд нон-стопом
      Wire.write(0xAE); // OLED_DISPLAY_OFF выключить дисплей
      Wire.write(0xD5); // OLED_CLOCKDIV по всей видимости, делитель частоты внутренних часов, хз зачем
      Wire.write(0x80); //
      Wire.write(0x8D); // OLED_CHARGEPUMP ???
      Wire.write(0x14); //
      Wire.write(0x20); // OLED_ADDRESSING_MODE способ адресации какой-то
      Wire.write(0x01); // OLED_VERTICAL вертикальная ориентация
      Wire.write(0xA1); // OLED_NORMAL_H без отражения слева направо
      Wire.write(0xC8); // OLED_NORMAL_V без отражения сверху вниз
      Wire.write(0x81); // OLED_CONTRAST контраст
      Wire.write(0x7F); // по всей видимости величина контраста
      Wire.write(0xDB); // OLED_SETVCOMDETECT ???
      Wire.write(0x40); // 
      Wire.write(0xA6); // OLED_NORMALDISPLAY не инвертировать состояние пикселей
      //Wire.write(0xAF); // OLED_DISPLAY_ON включить дисплей
      Wire.endTransmission();
      Wire.beginTransmission(_address);
      Wire.write(0x00); // OLED_COMMAND_MODE режим отправки команд нон-стопом 
      Wire.write(0xDA); // OLED_SETCOMPINS    не представляю, что именно, связано с разрешением.
      Wire.write(0x12); // OLED_HEIGHT_64     Возможно, какой-то режим адресации/сопоставления памяти
      Wire.write(0xA8); // OLED_SETMULTIPLEX  (чип может не знать, какая именно матрица к нему подключена)
      Wire.write(0x3F); // OLED_64
      Wire.endTransmission();

    }
    
    void draw (char (*lines)[6][22], bool selected) {

      //for (uint8_t i = 0; i < 6; i++) for (uint8_t j = 0; j < 22; j++) if ((*lines)[i][j] == '\0') (*lines)[i][j] = 32;

      // для каждой из 8 страниц памяти монитора
      for (uint8_t row = 0; row < 8; row++) {

        Wire.beginTransmission(_address);
        Wire.write(0x00); // OLED_COMMAND_MODE режим отправки команд нон-стопом
        Wire.write(0xB0 + row); // выбор адреса страницы 0..7
        Wire.write(2); // младший адрес столбца (не менять)
        Wire.write(16); // старший адрес столбца (не менять)

        uint8_t index_1, index_2;

        // отправка 8 пакетов по 16 байт (ограничения Wire.h)
        for (uint8_t col = 0; col < 128; col++) {

          // перезапускаем отправку каждые 16 байт
          if (col % 16 == 0) {
            Wire.endTransmission();
            Wire.beginTransmission(_address);
            Wire.write(0x40); // OLED_DATA_MODE
          }

          int8_t  bt = col % 6 - 1; // индекс байта в шрифте

          if (col > 125) Wire.write(col == 127 ? B00000000 : row == 1 ? B00000100 : row == 4 && selected ? B11111110 : row == 5 && selected ? B00000111 : B00000000);
          else if (bt == -1) {
            Wire.write(row == 1 ? B00000100 : row == 4 && selected ? B11111110 : row == 5 && selected ? B00000111 : B00000000);
            uint8_t ch = col / 6; // индекс символа в строке
            uint8_t i_1 = row < 1 ? 0 : row < 3 ? 1 : row < 4 ? 2 : row < 6 ? 3 : row < 7 ? 4 : 5;
            uint8_t i_2 = row == 2 ? 2 : row == 5 ? 4 : 0;
            index_1 = (uint8_t)(*lines)[i_1][ch] - 32;
            index_2 = i_2 != 0 ? (uint8_t)(*lines)[i_2][ch] - 32 : 0;
          } else if (row == 0) Wire.write( pgm_read_byte(&FONT[index_1][bt]) );
          else   if (row == 1) Wire.write( pgm_read_byte(&FONT[index_1][bt]) << 4 | B00000100 );
          else   if (row == 2) Wire.write( pgm_read_byte(&FONT[index_1][bt]) >> 4 | pgm_read_byte(&FONT[index_2][bt]) << 7 );
          else   if (row == 3) Wire.write( pgm_read_byte(&FONT[index_1][bt]) >> 1 );
          else   if (row == 4) Wire.write( selected ? (uint8_t)~pgm_read_byte(&FONT[index_1][bt]) << 2 | B00000010 : pgm_read_byte(&FONT[index_1][bt]) << 2 );
          else   if (row == 5) Wire.write( selected ? (uint8_t)~pgm_read_byte(&FONT[index_1][bt]) >> 6 | B00000100 | pgm_read_byte(&FONT[index_2][bt]) << 5 : pgm_read_byte(&FONT[index_1][bt]) >> 6 | pgm_read_byte(&FONT[index_2][bt]) << 5 );
          else   if (row == 6) Wire.write( pgm_read_byte(&FONT[index_1][bt]) >> 3 );
          else                 Wire.write( pgm_read_byte(&FONT[index_1][bt]) );

        }
    
        // закрываем отправку после выхода из цикла
        Wire.endTransmission();
    
      }
    
    }

    // вкл/выкл экран
    void power (bool value) {
      Wire.beginTransmission(_address);
      Wire.write(0x80); // OLED_ONE_COMMAND_MODE
      Wire.write(value ? 0xAF : 0xAE); // OLED_DISPLAY_ON / OLED_DISPLAY_OFF
      Wire.endTransmission();
    }
    
    /* // яркость 0-255
    void contrast (uint8_t value) {
      Wire.beginTransmission(_address);
      Wire.write(0x00); // OLED_COMMAND_MODE
      Wire.write(0x81); // OLED_CONTRAST
      Wire.write(value);
      Wire.endTransmission();
      //delayMicroseconds(2);
    } */

  private:
  
    const uint8_t _address = 0x3C;

};











const uint64_t protocol_options_uid = 8683477418810728652;
const uint64_t protocol_comands_uid = 8900317804858057850;

struct protocol_head_t { uint64_t protocol_uid; int64_t counter; };

struct options_message_t {
  protocol_head_t head;
  char lines[6][22];
  bool selected;
};

struct comands_message_t {
  protocol_head_t head;
  int16_t  left_x,
           left_y,
           right_x,
           right_y,
           encoder;
  bool     top,
           centre,
           bottom;
};

// принимаемое сообщение с набором выводимых на экран опций
options_message_t options_message;
// количество неполучений пакетов, при котором будет зафиксирована потеря связи и пульт будет считать себя свободным
const uint16_t rc_silence_lost = 5;
// счетчик количества неполученных пакетов (при включении пульта соединения не будет)
uint16_t rc_silence = rc_silence_lost;
// используемый канал Wi-Fi, должен быть одинаковый на роботе и пульте
uint8_t chanel = 1;





// ф-ия приема
void rc_receive (const uint8_t*  mac, const uint8_t* data, int data_len) {

  // сначала проверяем, а что собсно пришло
  if (data_len == sizeof(options_message_t)) {

    // получение заголовка данных
    protocol_head_t head;
    memcpy(&head, data, sizeof(protocol_head_t));
    
    // проверка соответствия типа протокола
    if (head.protocol_uid == protocol_options_uid) {
      // есть ли пир в списке
      if (esp_now_is_peer_exist(mac)) {

        // пакет пришел от зарегистрированного пира
        // соблюдается ли очередность следования пакетов или была потеря связи
        if (head.counter >= options_message.head.counter || rc_silence >= rc_silence_lost) {
      
          // принимаем новый пакет целиком
          memcpy(&options_message, data, sizeof(options_message_t));
          // сброс счетчика неполученных пакетов
          rc_silence = 0;

        } // else сообщения старше последнего принятого игнорируются

      } else if (rc_silence >= rc_silence_lost) {

        // пакет пришел от незарегистрированного приа, но после потери связи
        // принимаем новый пакет целиком, т.к. в нем пришли актуальные опции
        memcpy(&options_message, data, sizeof(options_message_t));
        // сброс счетчика неполученных пакетов
        rc_silence = 0;
        // удаление всех сохраненных unicast пиров
        esp_now_peer_info_t peer;
        while (esp_now_fetch_peer(true, &peer) == ESP_OK) esp_now_del_peer(peer.peer_addr);
        // формирование данных пира, от которого получен пакет
        esp_now_peer_info_t unicastPeer = {
          .peer_addr = { mac[0],mac[1],mac[2],mac[3],mac[4],mac[5] },
          .lmk = { 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00 },
          .channel = chanel,
          .ifidx = WIFI_IF_STA,
          .encrypt = false,
          .priv = NULL
        };
        // добавление пира, от которого получен пакет (иначе не сможем ему ничего отправить)
        esp_now_add_peer(&unicastPeer);

      }

    } // else уникальный идентификатор формата инфообмена не соответствует ожидаемому

  } // else длина пакета не соответствует ожидаемой

}





// прерывание для энкодера
int8_t isr_encoder = 0;
static void IRAM_ATTR gpio_isr_encoder_handler (void *args) {
  
  isr_encoder = gpio_get_level((gpio_num_t)6) ? (isr_encoder > 0 ? 1 : -1) : (isr_encoder < 0 ? -1 : 1);

}

// прерывания для кнопок
bool isr_top = false, isr_centre = false, isr_bottom = false;
static void IRAM_ATTR gpio_isr_top_handler    (void *args) { isr_top    = true; }
static void IRAM_ATTR gpio_isr_centre_handler (void *args) { isr_centre = true; }
static void IRAM_ATTR gpio_isr_bottom_handler (void *args) { isr_bottom = true; }





int16_t getStickAxis (uint8_t pin, int16_t centre) {

  const uint8_t deathzone = 100;
  int16_t value = analogRead(pin);
  return (value > centre) ? map(constrain(value, centre + deathzone,               4095), centre + deathzone, 4095, 0,  2000)
                          : map(constrain(value,                  0, centre - deathzone), centre - deathzone,    0, 0, -2000);

}





// задача для организации связи
void task_rc (void *param) {

  // ИНИЦИАЛИЗАЦИЯ

  // периодичность вызова в миллисекундах
  const uint16_t pheriod_ms = 75;

  // порты и прерывания
  gpio_install_isr_service(ESP_INTR_FLAG_LEVEL1); // 1-6, ESP_INTR_FLAG_NMI
  // порт 5 прерывание энкодера
  gpio_reset_pin((gpio_num_t)5);
  gpio_set_direction((gpio_num_t)5, GPIO_MODE_INPUT);
  gpio_set_pull_mode((gpio_num_t)5, GPIO_FLOATING);
  gpio_isr_handler_add((gpio_num_t)5, gpio_isr_top_handler, NULL);
  gpio_set_intr_type((gpio_num_t)5, GPIO_INTR_POSEDGE);
  gpio_intr_enable((gpio_num_t)5);
  // порт 6 второй контакт энкодера
  gpio_reset_pin((gpio_num_t)6);
  gpio_set_direction((gpio_num_t)6, GPIO_MODE_INPUT);
  gpio_set_pull_mode((gpio_num_t)6, GPIO_FLOATING);
  // порт 7 прерывание энкодера
  gpio_reset_pin((gpio_num_t)7);
  gpio_set_direction((gpio_num_t)7, GPIO_MODE_INPUT);
  gpio_set_pull_mode((gpio_num_t)7, GPIO_FLOATING);
  gpio_isr_handler_add((gpio_num_t)7, gpio_isr_encoder_handler, NULL);
  gpio_set_intr_type((gpio_num_t)7, GPIO_INTR_POSEDGE);
  gpio_intr_enable((gpio_num_t)7);
  // порт 7 кнопка энкодера
  gpio_reset_pin((gpio_num_t)8);
  gpio_set_direction((gpio_num_t)8, GPIO_MODE_INPUT);
  gpio_set_pull_mode((gpio_num_t)8, GPIO_FLOATING);
  gpio_isr_handler_add((gpio_num_t)8, gpio_isr_centre_handler, NULL);
  gpio_set_intr_type((gpio_num_t)8, GPIO_INTR_POSEDGE);
  gpio_intr_enable((gpio_num_t)8);
  // порт 5 прерывание энкодера
  gpio_reset_pin((gpio_num_t)9);
  gpio_set_direction((gpio_num_t)9, GPIO_MODE_INPUT);
  gpio_set_pull_mode((gpio_num_t)9, GPIO_FLOATING);
  gpio_isr_handler_add((gpio_num_t)9, gpio_isr_bottom_handler, NULL);
  gpio_set_intr_type((gpio_num_t)9, GPIO_INTR_POSEDGE);
  gpio_intr_enable((gpio_num_t)9);

  /* // аналоги
  // gpio1 = adc1_ch0
  // gpio2 = adc1_ch1
  // gpio3 = adc1_ch2
  // gpio4 = adc1_ch3
  adc_oneshot_unit_handle_t adc1_handle = nullptr;
  adc_oneshot_unit_init_cfg_t init_config1 = { .unit_id = ADC_UNIT_1 };
  adc_oneshot_new_unit(&init_config1, &adc1_handle);
  adc_oneshot_chan_cfg_t config = { .atten = ADC_ATTEN_DB_12, .bitwidth = ADC_BITWIDTH_DEFAULT };  // default width is max supported width
  adc_oneshot_config_channel(adc1_handle, ADC_CHANNEL_0, &config);
  int32_t raw = 0;
  adc_oneshot_read(adc1_handle, ADC_CHANNEL_0, &raw);*/
  static int16_t left_x_center  = analogRead(A0),
                 left_y_center  = analogRead(A1),
                 right_x_center = analogRead(A3),
                 right_y_center = analogRead(A2);
  for (uint8_t i = 0; i < 64; i++) {
    left_x_center  = (left_x_center  + analogRead(A0)) / 2;
    left_y_center  = (left_y_center  + analogRead(A1)) / 2;
    right_x_center = (right_x_center + analogRead(A3)) / 2;
    right_y_center = (right_y_center + analogRead(A2)) / 2;
  }

  // инициализация экрана
  cScreen screen;
  screen.define();
  // включение экрана
  screen.power(true);

  // запуск Wi-Fi
  WiFi.mode(WIFI_STA);
  // инициализация ESP-NOW
  esp_now_init();

  // привязка функции обработки полученных данных
  esp_now_register_recv_cb(rc_receive);

  // запуск бесконечного цикла задачи
  for (;;) {

    // время начала цикла (для определения момента следующего старта)
    TickType_t last_RC_at = xTaskGetTickCount();

    // сделать для энкодера счетчик ненулевых состояний, случившихся подряд каждый цикл отправки - передавать его значение
    static int8_t encoder = isr_encoder;
    encoder = isr_encoder != 0 ? abs(encoder) < 100 ? encoder + isr_encoder : encoder : 0;

    // заполнение пакета для отправки
    comands_message_t comands_message = {
      .head = (protocol_head_t) { protocol_comands_uid, esp_timer_get_time() },
      .left_x  = getStickAxis(A0, left_x_center ),
      .left_y  = getStickAxis(A1, left_y_center ),
      .right_x = getStickAxis(A3, right_x_center),
      .right_y = getStickAxis(A2, right_y_center),
      .encoder = encoder,
      .top     = isr_top,
      .centre  = isr_centre,
      .bottom  = isr_bottom
    };
    // сбрасываем все контроллы
    isr_encoder = 0;
    isr_top     = false;
    isr_centre  = false;
    isr_bottom  = false;

    // пульт не отправляет инициативных запросов, а только отвечает на них
    if (rc_silence == 0) {
      
      // были получены новые данные
      // отключение обработки принятых сообщений воизбежание модификации данных в процессе вывода на экран
      //esp_now_unregister_send_cb();
      // отрисовка экрана
      screen.draw(&options_message.lines, options_message.selected);
      // привязка функции обработки полученных данных
      //esp_now_register_recv_cb(rc_receive);
      // отправка команд - всегда таргетно
      esp_now_send(NULL, (uint8_t*)&comands_message, sizeof(comands_message_t));
      
    } else if (rc_silence >= rc_silence_lost) {
      
      // долго не поступало новых запросов - считаем, что связь потеряна и пульт свободен
      // наполнение экрана текстом
      static char lines[6][22] = { "    DISCONNECTED!    ",
                                   "                     ",
                                   "                     ",
                                   "Turn on your robot...",
                                   "                     ",
                                   "                     " };
      // отрисовка экрана
      screen.draw(&lines, esp_timer_get_time() / 1000000 % 2 != 0);
      
    }


  
    // если не будет вызова rc_receive() то rc_silence будет расти каждую итерацию
    if (rc_silence <= rc_silence_lost) rc_silence++;

    // возврат управления шедулеру
    vTaskDelayUntil(&last_RC_at, pdMS_TO_TICKS(pheriod_ms));
    
  }
  
  // аварийная остановка задачи (не должна сработать никогда)
  vTaskDelete(NULL);
  
}





void setup () {
  
  xTaskCreatePinnedToCore (task_rc, "R/C", 4096*10, NULL, (2 | portPRIVILEGE_BIT), NULL, xPortGetCoreID());

}





void loop() {

  delay(5000);

}





код для робота

#include "freertos/FreeRTOS.h"
#include "freertos/task.h"

#include <esp_now.h>
#include <WiFi.h>
//#include <esp_wifi.h>





// структура для хранения пары значений "номер вывода GPIO" - "ширина импульса PWM в микросекундах"
struct pwm_channel_t { uint8_t pin; uint16_t value; };

// массив каналов PWM
pwm_channel_t cahnnels[] = { { 18, 0 }, { 48, 0 }, {  1, 0 },
                             {  2, 0 }, {  3, 0 }, {  4, 0 },
                             { 12, 0 }, { 13, 0 }, { 14, 0 },
                             {  5, 0 }, {  6, 0 }, {  7, 0 },
                             {  9, 0 }, { 10, 0 }, { 17, 0 },
                             { 21, 0 }, { 38, 0 }, { 47, 0 } };





// задача для генерации импульсов PWM на все каналы каждые 20 миллисекунд
void task_pwm (void *param) {

  // ИНИЦИАЛИЗАЦИЯ

  // периодичность вызова в миллисекундах
  const uint16_t pheriod_ms = 20;

  // количество каналов
  const uint8_t cahnnelsCount = sizeof(cahnnels) / sizeof(cahnnels[0]);

  // ограничение максимальной длины импульса
  const uint16_t pulseWidthTreshold = 3000;

  // маски регистров, по которым будут подниматься каналы
  uint32_t up_port_0_mask = 0, up_port_1_mask = 0;
  // массив последовательности временных задержек
  uint16_t delays[cahnnelsCount];
  // массивы масок регистров, по которым будут гаситься каналы
  uint32_t down_port_0_masks[cahnnelsCount];
  uint32_t down_port_1_masks[cahnnelsCount];

  for (uint8_t i = 0; i < cahnnelsCount; i++) {
    // конфигурация выводов
    gpio_reset_pin((gpio_num_t)cahnnels[i].pin);
    gpio_set_direction((gpio_num_t)cahnnels[i].pin, GPIO_MODE_OUTPUT);
    gpio_set_pull_mode((gpio_num_t)cahnnels[i].pin, GPIO_FLOATING);
    // установка нулевых стартовых значений для масок и задержек
    delays[i] = 0;
    down_port_0_masks[i] = 0;
    down_port_1_masks[i] = 0;
  }

  // запуск бесконечного цикла задачи
  for (;;) {

    // блокировка шедулера - гарантия, что формирование импульсов выполнится без остановки на другие задачи
    vTaskSuspendAll();

    // время начала генерации импульсов (для определения момента следующего старта)
    TickType_t last_PWM_at = xTaskGetTickCount();

    // ГЕНЕРАЦИЯ ИМПУЛЬСОВ

    // переача в регистры масок, содержащих биты всех портов с не нулевой длиной импульса
    GPIO.out_w1ts      |= up_port_0_mask;
    GPIO.out1_w1ts.val |= up_port_1_mask;

    // гашение портов согласно очередности с соответствующими задержками
    for (uint8_t i = 0; i < cahnnelsCount; i++) {
      // задержка
      ets_delay_us(delays[i]);
      // переача в регистры масок, содержащих биты всех портов, которые необходимо погасить на данной итерации
      GPIO.out_w1tc      |= down_port_0_masks[i];
      GPIO.out1_w1tc.val |= down_port_1_masks[i];
    }

    // ВЫЗОВ ПЕРЕРАССЧЕТА КИНЕМАТИКИ

    // с использованием дельты времени 20 мс в качестве инкрементов всех процессов
    // ...

    // ПОДГОТОВКА ДАННЫХ ДЛЯ СЛЕДУЮЩЕЙ ИТЕРАЦИИ

    // маски регистров, по которым будут подниматься порты (временные переменные)
    uint32_t tmp_up_port_0_mask = 0, tmp_up_port_1_mask = 0;
    // массив последовательности временных задержек (временные переменные)
    uint16_t tmp_delays[cahnnelsCount];
    // массивы масок регистров, по которым будут гаситься порты (временные переменные)
    uint32_t tmp_down_port_0_masks[cahnnelsCount];
    uint32_t tmp_down_port_1_masks[cahnnelsCount];
    // установка нулевых значений задержек и масок
    for (uint8_t i = 0; i < cahnnelsCount; i++) {
      tmp_delays[i] = 0;
      tmp_down_port_0_masks[i] = 0;
      tmp_down_port_1_masks[i] = 0;
    }
    // минимальная длина импульса, определенная на предыдущей итерации цикла наполнения массивов
    uint16_t minPreviouse = 0;
    // минимальная длина импульса, определенная на текущей итерации цикла наполнения массивов
    uint16_t minCurrent = cahnnels[0].value;
    // счетчик обработанных каналов
    uint8_t current = 0;
    // индекс текущего элемента во временных массивах
    uint8_t to = 0;
    // признак того, что наполнение массивов прошло успешно
    bool succesfull = true;
    
    // цикл наполнения массивов
    while ((current < cahnnelsCount) && succesfull) {
      
      // поиск минимального значения длины импульса, превосходящего предыдущее значение (найденное в предыдущей итерации)
      for (uint8_t i = 0; i < cahnnelsCount; i++) if (cahnnels[i].value < minCurrent && cahnnels[i].value > minPreviouse)
        minCurrent = cahnnels[i].value;
      
      // запись значения дельты времени в массив задержек
      tmp_delays[to] = minCurrent - minPreviouse;
      // перезапись предыдущего минимального значения
      minPreviouse = minCurrent;

      // сброс признака успешного наполнения массивов
      succesfull = false;
      // формирование масок для всех каналов ШИМ, у которых длина импульса равна найденной
      for (uint8_t from = 0; from < cahnnelsCount; from++) if (cahnnels[from].value == minCurrent) {

        // если cahnnels[] не изменялся извне и наполнение проходит успешно, то данная команда выполнится хотя бы раз за каждый проход
        succesfull = true;

        // если длина импульса на канале ненулевая, то в порты добавляется бит соответствующего пина
        if (minCurrent > 0) {

          // определение группы регистров
          if (cahnnels[from].pin > 32) {

            // смещение в регистрах группы 1
            uint32_t add_1 = 1 << (cahnnels[from].pin - 32);
            // добавление в маску регистра поднимающихся портов
            tmp_up_port_1_mask |= add_1;
            // добавление в маску регистра гасящихся портов
            tmp_down_port_1_masks[to] |= add_1;

          } else {

            // смещение в регистрах группы 0
            uint32_t add_0 = 1 << cahnnels[from].pin;
            // добавление в маску регистра поднимающихся портов
            tmp_up_port_0_mask |= add_0;
            // добавление в маску регистра гасящихся портов
            tmp_down_port_0_masks[to] |= add_0;

          }

        }

        // инкриментация счетчика обработанных каналов
        current++;

      }

      // инкриментация индекса текущего элемента в наполняемых массивах
      to++;

      // сброс минимума для успешного поиска на следующей итерации
      minCurrent = pulseWidthTreshold;
    
    }
  
    // если наполнения массивов прошло успешно
    if (succesfull) {
      
      // копирование масок поднятия портов
      up_port_0_mask = tmp_up_port_0_mask;
      up_port_1_mask = tmp_up_port_1_mask;

      // копирование значениq из временных массивов в массивы для генерации импульсов
      for (uint8_t i = 0; i < cahnnelsCount; i++) {

        delays[i] = tmp_delays[i];
        down_port_0_masks[i] = tmp_down_port_0_masks[i];
        down_port_1_masks[i] = tmp_down_port_1_masks[i];

      }
      
    } // else при желании можно зафиксировать ошибку
    
    // разблокировка шедулера
    xTaskResumeAll();

    // возврат управления шедулеру
    vTaskDelayUntil(&last_PWM_at, pdMS_TO_TICKS(pheriod_ms));
    
  }
  
  // аварийная остановка задачи (не должна сработать никогда)
  vTaskDelete(NULL);
  
}





const uint64_t protocol_options_uid = 8683477418810728652;
const uint64_t protocol_comands_uid = 8900317804858057850;

struct protocol_head_t { uint64_t protocol_uid; int64_t counter; };



struct options_message_t {
  protocol_head_t head;
  char lines[6][22];
  bool selected;
};

struct comands_message_t {
  protocol_head_t head;
  int16_t  left_x,
           left_y,
           right_x,
           right_y,
           encoder;
  bool     top,
           centre,
           bottom;
};

// принимаемое сообщение с набором команд от пульта
comands_message_t commands_message;
// количество неполучений пакетов, при котором будет зафиксирована потеря связи и будут рассылаться запросы на коннект
const uint16_t rc_silence_lost = 5;
// количество неполучений пакетов, при котором инициируется складывание конструкции
const uint16_t rc_silence_lay_down = 20;
// счетчик количества неполученных пакетов (при включении робота соединения не будет)
uint16_t rc_silence = rc_silence_lay_down;
// используемый канал Wi-Fi, должен быть одинаковый на роботе и пульте
uint8_t chanel = 1;





// ф-ия приема
void rc_receive (const uint8_t*  mac, const uint8_t* data, int data_len) {

  // сначала проверяем, а что собсно пришло
  if (data_len == sizeof(comands_message_t)) {
    
    // получение заголовка данных
    protocol_head_t head;
    memcpy(&head, data, sizeof(protocol_head_t));
    
    // проверка соответствия типа протокола
    if (head.protocol_uid == protocol_comands_uid) {
      // есть ли пир в списке
      if (esp_now_is_peer_exist(mac)) {

        // пакет пришел от зарегистрированного пира
        // соблюдается ли очередность следования пакетов или была потеря связи
        if (head.counter >= commands_message.head.counter) {
      
          // принимаем новый контролл целиком, еали не было потери связи
          memcpy(&commands_message, data, sizeof(comands_message_t));
          // сброс счетчика неполученных пакетов
          rc_silence = 0;
      
        } else if (rc_silence >= rc_silence_lost) {

          // так как пользователь не видел опций робота, принимаем ТОЛЬКО счетчик пакетов
          commands_message.head.counter = head.counter;
          // сброс счетчика неполученных пакетов
          rc_silence = 0;

        } // else сообщения старше последнего принятого игнорируются

      } else if (rc_silence >= rc_silence_lost) {

        // пакет пришел от незарегистрированного приа, но после потери связи
        // так как пользователь не видел опций робота, принимаем ТОЛЬКО счетчик пакетов
        commands_message.head.counter = head.counter;
        // сброс счетчика неполученных пакетов
        rc_silence = 0;
        // удаление всех сохраненных unicast пиров
        esp_now_peer_info_t peer;
        while (esp_now_fetch_peer(true, &peer) == ESP_OK) esp_now_del_peer(peer.peer_addr);
        // формирование данных пира, от которого получен пакет
        esp_now_peer_info_t unicastPeer = {
          .peer_addr = { mac[0],mac[1],mac[2],mac[3],mac[4],mac[5] },
          .lmk = { 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00 },
          .channel = chanel,
          .ifidx = WIFI_IF_STA,
          .encrypt = false,
          .priv = NULL
        };
        // добавление пира, от которого получен пакет (иначе не сможем ему ничего отправить)
        esp_now_add_peer(&unicastPeer);

      }

    } // else уникальный идентификатор формата инфообмена не соответствует ожидаемому
      
  } // else длина пакета не соответствует ожидаемой

}





// платформа всегда может либо выполненять кинематического задания, либо находиться в одном из статичных состояний и ожидать команды
enum conditions_t {
  LAYED,
  CALIBRATION,
  RISED,
  ANIMATIONS,
  TUNE
};

// стилей управления сервоприводами тоже два: прямое (только для калибровки) и координатное




// задача для организации управления и связи
void task_rc (void *param) {

  // ИНИЦИАЛИЗАЦИЯ

  // периодичность вызова в миллисекундах
  const uint16_t pheriod_ms = 50;

  // адрес для широковещательного (broadcast) запроса
  uint8_t broadcast[6] = { 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF };

  // запуск Wi-Fi
  WiFi.mode(WIFI_STA);
  // инициализация ESP-NOW
  esp_now_init();

  // создание конфига broadcast пира
  esp_now_peer_info_t broadcastPeer = {
    .peer_addr = { broadcast[0],broadcast[1],broadcast[2],broadcast[3],broadcast[4],broadcast[5] },
    .lmk = { 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00 },
    .channel = chanel,
    .ifidx = WIFI_IF_STA,
    .encrypt = false,
    .priv = NULL
  };
  // добавление broadcast пира
  esp_now_add_peer(&broadcastPeer);

  // текущее состояние
  conditions_t condition = LAYED;

  // запуск бесконечного цикла задачи
  for (;;) {

    // время начала цикла (для определения момента следующего старта)
    TickType_t last_RC_at = xTaskGetTickCount();
    
    // отключение обработки принятых сообщений воизбежание модификации данных контроллов
    esp_now_unregister_send_cb();
    
    // предзаполнение пакета для отправки
    options_message_t options_message = {
      .head = {
        .protocol_uid = protocol_options_uid,
        .counter = esp_timer_get_time()
      },
      .lines = { "                     ",
                 "                     ",
                 "                     ",
                 "                     ",
                 "                     ",
                 "                     " },
      .selected = false
    };

    // обработка команд и управление состояниями
    if (false) { // act

      // ВЫПОЛНЯЕТСЯ КИНЕМАТИЧЕСКОЕ ЗАДАНИЕ

      // вывод сообщения "Waiting..." на экран

    } else if (condition == LAYED) {

      // СЛОЖЕННОЕ СОСТОЯНИЕ
    
      String menu[] = {
        "- Rise               ",
        "- Calibration        "
      };
      uint8_t count = sizeof(menu) / sizeof(menu[0]);
      static uint8_t i = 0;

      if (commands_message.bottom || commands_message.centre) {
        if (i == 0) {
          // создает задание перевода из LAYED в RISED
          // ***
        } else if (i == 1) {
          // создает задание перевода из LAYED в CALIBRATION
          condition = CALIBRATION; // ***
        }
      } else if (commands_message.encoder > 0) {
        i = (i == count - 1) ? 0 : i + 1 ;
      } else if (commands_message.encoder < 0) {
        i = (i == 0) ? count - 1 : i - 1 ;
      }

      String("        LAYED        ").toCharArray(options_message.lines[0], 22);
      options_message.selected = true;
      if (i > 1)         menu[i - 2].toCharArray(options_message.lines[1], 22);
      if (i > 0)         menu[i - 1].toCharArray(options_message.lines[2], 22);
                         menu[i    ].toCharArray(options_message.lines[3], 22);
      if (i < count - 1) menu[i + 1].toCharArray(options_message.lines[4], 22);
      if (i < count - 2) menu[i + 2].toCharArray(options_message.lines[5], 22);

      /*String("I received").toCharArray(options_message.lines[1], 22);
      String("encoder: " + String(commands_message.encoder)).toCharArray(options_message.lines[2], 22);
      String("left_x: " + String(commands_message.left_x)).toCharArray(options_message.lines[3], 22);*/

    } else if (condition == CALIBRATION) {

      // КАЛИБРОВКА СЕРВОПРИВОДОВ
    
      // инициализация перевода из CALIBRATION в LAYED при окончательной потере связи
      if (rc_silence >= rc_silence_lay_down) {  }

      String menu[] = {
        "< Back...            ",
        "- Limb 0 Servo 0     ",
        "- Limb 0 Servo 1     ",
        "- Limb 0 Servo 2     ",
        "- Limb 1 Servo 0     ",
        "- Limb 1 Servo 1     ",
        "- Limb 1 Servo 2     ",
        "- Limb 2 Servo 0     ",
        "- Limb 2 Servo 1     ",
        "- Limb 2 Servo 2     ",
        "- Limb 3 Servo 0     ",
        "- Limb 3 Servo 1     ",
        "- Limb 3 Servo 2     ",
        "- Limb 4 Servo 0     ",
        "- Limb 4 Servo 1     ",
        "- Limb 4 Servo 2     ",
        "- Limb 5 Servo 0     ",
        "- Limb 5 Servo 1     ",
        "- Limb 5 Servo 2     "
      };
      uint8_t count = sizeof(menu) / sizeof(menu[0]);
      static uint8_t i = 0;
      
      /*static bool selected = false;
      static uint16_t value = 1500;
      
            КОНЕЧНОСТЬ 2 СЕРВО 1
      вращайте энкодер для позиционирования
                   825
      -30 = 800
      0 = 1500
      30 = 2200
      какой позиции соответствует текущее положение?
      -30 = 800 < 825
      0 = 1500
      30 = 2200
      
      */

      if (commands_message.top || ((commands_message.bottom || commands_message.centre) && i == 0)) {
        // создает задание перевода из CALIBRATION в LAYED
        condition = LAYED; // ***
      } else if (commands_message.bottom || commands_message.centre) {
        // вычисление индекса серво
        // ***
      } else if (commands_message.encoder > 0) {
        i = (i == count - 1) ? 0 : i + 1 ;
      } else if (commands_message.encoder < 0) {
        i = (i == 0) ? count - 1 : i - 1 ;
      }

      //String(String(i) + " / " + String(count)).toCharArray(options_message.lines[1], 22);

      String("     CALIBRATION     ").toCharArray(options_message.lines[0], 22);
      options_message.selected = true;
      if (i > 1)         menu[i - 2].toCharArray(options_message.lines[1], 22);
      if (i > 0)         menu[i - 1].toCharArray(options_message.lines[2], 22);
                         menu[i    ].toCharArray(options_message.lines[3], 22);
      if (i < count - 1) menu[i + 1].toCharArray(options_message.lines[4], 22);
      if (i < count - 2) menu[i + 2].toCharArray(options_message.lines[5], 22);

    } else if (condition == RISED) {

      // ПОХОДНАЯ СТОЙКА
    
      // инициализация перевода из RISED в LAYED при окончательной потере связи
      if (rc_silence >= rc_silence_lay_down) {  }

      // обрабатываем контроллы

      // строим пункты меню
      // - LAY (создает задание перевода в LAYED)
      // - ANIMATIONS (переключение в ANIMATIONS)
      // - PARAMETERS (переключение в TUNE)
      
      static uint8_t i = 0;

    } else if (condition == ANIMATIONS) {

      // ПОХОДНАЯ СТОЙКА - СПИСОК АНИМАЦИЙ
    
      // инициализация перевода из ANIMATIONS в LAYED при окончательной потере связи
      if (rc_silence >= rc_silence_lay_down) {  }

      // обрабатываем контроллы

      // строим пункты меню
      // - Back (переключение в RISED)
      // - Animation 1 (создает задание выполнение анимации Animation 1)
      // - Animation 2 (создает задание выполнение анимации Animation 2)
      // - Animation 3 (создает задание выполнение анимации Animation 3)
      // - ...
      
      static uint8_t i = 0;

    } else if (condition == TUNE) {

      // ПОХОДНАЯ СТОЙКА - НАСТРОЙКА ПАРАМЕТРОВ ХОДЬБЫ
    
      // инициализация перевода из TUNE в LAYED при окончательной потере связи
      if (rc_silence >= rc_silence_lay_down) {  }

      // обрабатываем контроллы

      // строим пункты меню
      // - Back (переключение в RISED)
      // - Setting 1 (отображение окна настройки параметра 1)
      // - Setting 2 (отображение окна настройки параметра 2)
      // - Setting 3 (отображение окна настройки параметра 3)
      // - ...
      
      static uint8_t i = 0;

    }

    // обнуление контроллов, так как они уже использовались
    commands_message.left_x = 0;
    commands_message.left_y = 0;
    commands_message.right_x = 0;
    commands_message.right_y = 0;
    commands_message.encoder = 0;
    commands_message.top = false;
    commands_message.centre = false;
    commands_message.bottom = false;

    // привязка функции обработки полученных данных
    esp_now_register_recv_cb(rc_receive);

    // отправка запроса на команды: таргетно (если не потеряна связь) или широковещательно (если связь потеряна)
    esp_now_send((rc_silence > rc_silence_lost) ? broadcast : NULL, (uint8_t*)&options_message, sizeof(options_message_t));

    // если не будет вызова rc_receive() то rc_silence будет расти каждую итерацию
    if (rc_silence <= rc_silence_lay_down) rc_silence++;

    // возврат управления шедулеру
    vTaskDelayUntil(&last_RC_at, pdMS_TO_TICKS(pheriod_ms));
    
  }
  
  // аварийная остановка задачи (не должна сработать никогда)
  vTaskDelete(NULL);
  
}













void setup () {

  Serial.begin (9600);

  // добавление задач в шедулер (функция, имя, размер_стека, параметры_NULL, приоритет, хэндлер_NULL, текущее_ядро) // TaskHandle_t taskHandler_pwm;
  xTaskCreatePinnedToCore (task_pwm, "PWM", 4096, NULL, (2 | portPRIVILEGE_BIT), NULL, xPortGetCoreID());
  xTaskCreatePinnedToCore (task_rc, "R/C", 4096*10, NULL, (2 | portPRIVILEGE_BIT), NULL, xPortGetCoreID());

}



uint16_t minP = 500, maxP = 2500;
uint16_t val[18] = { 1500, minP, minP, minP, minP, minP, minP, minP, minP, minP, minP, minP, minP, minP, minP, minP, minP, minP };

void loop() {

  for (uint8_t i = 0; i < 18; i++) {
    val[i] += i;
    if (val[i] > maxP * 2 - minP) val[i] = minP;
    cahnnels[i].value = val[i] > maxP ? maxP * 2 - val[i] : val[i];

    //Serial.print(" " + String(cahnnels[i].value));
  }
  cahnnels[1].value = minP;
  cahnnels[2].value = maxP;
  //Serial.println();



  delay(20);

}



Реализация ШИМ осталась пока прежней:

Перед генерацией импульсов создаются массивы задержек между одновременным началом импульсов и окончанием каждого из импульсов, а также строятся бит-маски регистров портов, по которым будет производиться гашение портов между задержками. Все массивы в хронологическом порядке, иными словами - строится очередь.
При генерации импульсов сначала поднимаются все порты, у которых ненулевая длина импульса ШИМ
Затем в цикле перебирается очередь, в каждом проходе:

  • ожидание задержки
  • гашение портов путем присваивания битмапки в регистр

Реализация связи:

Робот с пультом общается в обе стороны, в формате запрос-ответ, причем инициатива со стороны робота

Запрос со стороны робота выглядит как набор параметров:

  • id типа пакета данных
  • номер пакета
  • полезные данные: массивов char [6][21] (на самом деле [6][22], постараюсь найти способ обрезать ‘\0’ и вообще надо поразбираться в C-строках) и булевка - инвертировать ли 4-ю строку текста (таким образом реализуется выделение текущего пункта)

Ответ со стороны пульта:

  • id типа пакета данных (отличается от такового у запроса робота, но всегда одинаковый)
  • номер пакета
  • полезные данные: состояние 4 осей аналоговых стиков, 3 кнопок и 1 энкодера

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

Робот отправляет инициативные запросы каждую итерацию цикла задачи. Принимает в обработку сообщения только от пульта, с которым установлено соединение. Тоже ведет счетчик неполучения ответов, при достижении определенного значения считает связь потерянной. Если связь потеряна, вместо unicast запроса конкретному пульту, отправляет broadcast запрос в ожидании ответа от любого свободного пульта. В случае получения ответа правильного формата, робот добавляет пульт в список пиров, обнуляет счетчик, начинает принимать пакеты целиком со следующей итерации цикла задачи.

Для блокирования изменения принимаемых данных во время выполнения их обработки, колл-бэки на время обработки отключаются (возможно это в корне неверный подход). В связи с этим, чтобы не попасть в “синхрон” и не терять пакеты один за другим, циклы задач на пульте и на роботе сделаны разной частоты (на пульте на треть медленнее). Как бы бредово ни звучало, но работает стабильно.


Всё сыроватое, переменные раскиданы как попало, далеко не везде применены константы, а комментарии могут слегка расходиться с действительностью. Но в целом, связь и ШИМ работают. Пульт коннектится и восстанавливает связь автоматически, без прописывания адресов в коде. Менюшки строятся и скроллются, инпутлаг незаметен. Супер короче

Про особенности шкодинга в ArduinoIDE. Помимо того, что в пакете ESP32S3-NANO для Arduino не все типы данных ESP-IDF соответствуют документации, так еще и напрочь отсутствуют функции ADC - только кастрированные варианты в стиле Arduino. Не то чтобы парит, но хотел сделать максимально приближенно к фреймворку разработчика. Вдруг захочу на эклипс перекатиться. Ан-нет, придется переписывать часть проектика)))

Огромное человеческое спасибо vvb333007 за исчерпывающие ответы!

Также нехило помог сайт хорошего человека Все статьи – kotyara12.ru и у него вроде канал на дзене тоже есть

1 лайк

это все-же была плохая идея - выяснилось при скролле меню на 10+ пунктов. Пересматриваю алгоритм работы пульта: перенес отрисовку и ответ в on_receive коллбэк при успешном приеме от зареганного пира. Осталось только причесать и угомонить чрезчур резвую работу энкодера, у которого к тому же на 1 щелчок приходится сразу два инкремента…

Готово. В состоянии потянуть передачу данных с периодичностью ШИМ, т.е. 50 раз в секунду. Прошивка пульта претерпела значительные изменения:

#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include <esp_now.h>
#include <WiFi.h>
#include <Wire.h>





// битмап шрифта (длинное)
const uint8_t FONT[91][5] PROGMEM = {
  { B00000000, B00000000, B00000000, B00000000, B00000000 },
  { B00000000, B00000000, B01011111, B00000000, B00000000 },
  { B00000000, B00000110, B00000000, B00000110, B00000000 },
  { B00010100, B00111110, B00010100, B00111110, B00010100 },
  { B01001000, B01010100, B11010110, B01010100, B00100100 },
  { B00100011, B00010011, B00001000, B01100100, B01100010 },
  { B00101000, B01010100, B01010100, B00100000, B01010000 },
  { B00000000, B00000000, B00000110, B00000000, B00000000 },
  { B00000000, B00011100, B00100010, B01000001, B00000000 },
  { B00000000, B01000001, B00100010, B00011100, B00000000 },
  { B00010100, B00001000, B00111110, B00001000, B00010100 },
  { B00001000, B00001000, B00111110, B00001000, B00001000 },
  { B00000000, B10000000, B01100000, B00000000, B00000000 },
  { B00001000, B00001000, B00001000, B00001000, B00001000 },
  { B00000000, B00000000, B01000000, B00000000, B00000000 },
  { B00100000, B00010000, B00001000, B00000100, B00000010 },
  { B00111110, B01010001, B01001001, B01000101, B00111110 },
  { B00000000, B01000010, B01111111, B01000000, B00000000 },
  { B01110010, B01001001, B01001001, B01001001, B01000110 },
  { B00100001, B01000001, B01001001, B01001101, B00110011 },
  { B00011000, B00010100, B00010010, B01111111, B00010000 },
  { B00100111, B01000101, B01000101, B01000101, B00111001 },
  { B00111100, B01001010, B01001001, B01001001, B00110001 },
  { B01000001, B00100001, B00010001, B00001001, B00000111 },
  { B00110110, B01001001, B01001001, B01001001, B00110110 },
  { B01000110, B01001001, B01001001, B00101001, B00011110 },
  { B00000000, B00000000, B00100100, B00000000, B00000000 },
  { B00000000, B10000000, B01100100, B00000000, B00000000 },
  { B00001000, B00010100, B00100010, B01000001, B00000000 },
  { B00010100, B00010100, B00010100, B00010100, B00010100 },
  { B00000000, B01000001, B00100010, B00010100, B00001000 },
  { B00000010, B00000001, B01011001, B00001001, B00000110 },
  { B00111110, B01000001, B01011101, B01010001, B01001110 },
  { B01111100, B00010010, B00010001, B00010010, B01111100 },
  { B01111111, B01001001, B01001001, B01001001, B00110110 },
  { B00111110, B01000001, B01000001, B01000001, B00100010 },
  { B01111111, B01000001, B01000001, B01000001, B00111110 },
  { B01111111, B01001001, B01001001, B01001001, B01000001 },
  { B01111111, B00001001, B00001001, B00001001, B00000001 },
  { B00111110, B01000001, B01000001, B01010001, B01110010 },
  { B01111111, B00001000, B00001000, B00001000, B01111111 },
  { B00000000, B01000001, B01111111, B01000001, B00000000 },
  { B00100000, B01000000, B01000001, B00111111, B00000001 },
  { B01111111, B00001000, B00010100, B00100010, B01000001 },
  { B01111111, B01000000, B01000000, B01000000, B01000000 },
  { B01111111, B00000010, B00011100, B00000010, B01111111 },
  { B01111111, B00000100, B00001000, B00010000, B01111111 },
  { B00111110, B01000001, B01000001, B01000001, B00111110 },
  { B01111111, B00001001, B00001001, B00001001, B00000110 },
  { B00111110, B01000001, B01010001, B00100001, B01011110 },
  { B01111111, B00001001, B00011001, B00101001, B01000110 },
  { B00100110, B01001001, B01001001, B01001001, B00110010 },
  { B00000001, B00000001, B01111111, B00000001, B00000001 },
  { B00111111, B01000000, B01000000, B01000000, B00111111 },
  { B00011111, B00100000, B01000000, B00100000, B00011111 },
  { B00111111, B01000000, B00111000, B01000000, B00111111 },
  { B01100011, B00010100, B00001000, B00010100, B01100011 },
  { B00000011, B00000100, B01111000, B00000100, B00000011 },
  { B01100001, B01010001, B01001001, B01000101, B01000011 },
  { B00000000, B01111111, B01000001, B01000001, B00000000 },
  { B00000010, B00000100, B00001000, B00010000, B00100000 },
  { B00000000, B01000001, B01000001, B01111111, B00000000 },
  { B00000100, B00000010, B00000001, B00000010, B00000100 },
  { B01000000, B01000000, B01000000, B01000000, B01000000 },
  { B00000000, B00000010, B00000100, B00000000, B00000000 },
  { B00100000, B01010100, B01010100, B01111000, B01000000 },
  { B01111111, B00101000, B01000100, B01000100, B00111000 },
  { B00111000, B01000100, B01000100, B01000100, B00101000 },
  { B00111000, B01000100, B01000100, B00101000, B01111111 },
  { B00111000, B01010100, B01010100, B01010100, B00011000 },
  { B00000000, B00001000, B01111110, B00001001, B00000010 },
  { B00011000, B10100100, B10100100, B10100100, B01111000 },
  { B01111111, B00010000, B00001000, B00001000, B01110000 },
  { B00000000, B01001000, B01111010, B01000000, B00000000 },
  { B00100000, B01000000, B01000000, B00111010, B00000000 },
  { B01111111, B00010000, B00101000, B01000100, B00000000 },
  { B00000000, B01000001, B01111111, B01000000, B00000000 },
  { B01111100, B00000100, B01111000, B00000100, B01111000 },
  { B01111100, B00001000, B00000100, B00000100, B01111000 },
  { B00111000, B01000100, B01000100, B01000100, B00111000 },
  { B11111100, B00101000, B01000100, B01000100, B00111000 },
  { B00111000, B01000100, B01000100, B00101000, B11111100 },
  { B01111100, B00001000, B00000100, B00000100, B00001000 },
  { B01001000, B01010100, B01010100, B01010100, B00100100 },
  { B00000100, B00000100, B00111110, B01000100, B00100100 },
  { B00111100, B01000000, B01000000, B00100000, B01111100 },
  { B00011100, B00100000, B01000000, B00100000, B00011100 },
  { B00111100, B01000000, B00111000, B01000000, B00111100 },
  { B01000100, B00101000, B00010000, B00101000, B01000100 },
  { B00001100, B01010000, B01010000, B01010000, B00111100 },
  { B01000100, B01100100, B01010100, B01001100, B01000100 }
};

// функция инициализации экрана SH1106 с разрешением 128 x 64
void SH1106_init () {

  const uint8_t _address = 0x3C;
  Wire.begin();
  delay(5);
  Wire.setClock(8000000);
  Wire.beginTransmission(_address);
  Wire.write(0x00); // OLED_COMMAND_MODE режим отправки команд нон-стопом
  Wire.write(0xAE); // OLED_DISPLAY_OFF выключить дисплей
  Wire.write(0xD5); // OLED_CLOCKDIV по всей видимости, делитель частоты внутренних часов, хз зачем
  Wire.write(0x80); //
  Wire.write(0x8D); // OLED_CHARGEPUMP ???
  Wire.write(0x14); //
  Wire.write(0x20); // OLED_ADDRESSING_MODE способ адресации какой-то
  Wire.write(0x01); // OLED_VERTICAL вертикальная ориентация
  Wire.write(0xA1); // OLED_NORMAL_H без отражения слева направо
  Wire.write(0xC8); // OLED_NORMAL_V без отражения сверху вниз
  Wire.write(0x81); // OLED_CONTRAST контраст
  Wire.write(0x7F); // по всей видимости величина контраста
  Wire.write(0xDB); // OLED_SETVCOMDETECT ???
  Wire.write(0x40); // 
  Wire.write(0xA6); // OLED_NORMALDISPLAY не инвертировать состояние пикселей
  Wire.write(0xAF); // OLED_DISPLAY_ON включить дисплей
  Wire.endTransmission();
  Wire.beginTransmission(_address);
  Wire.write(0x00); // OLED_COMMAND_MODE режим отправки команд нон-стопом 
  Wire.write(0xDA); // OLED_SETCOMPINS    не представляю, что именно, связано с разрешением.
  Wire.write(0x12); // OLED_HEIGHT_64     Возможно, какой-то режим адресации/сопоставления памяти
  Wire.write(0xA8); // OLED_SETMULTIPLEX  (чип может не знать, какая именно матрица к нему подключена)
  Wire.write(0x3F); // OLED_64
  Wire.endTransmission();

}

// функция отрисовывает строки, переданные в массиве символов 21 x 6
// первая строка считается заголовком, под ней всегда рисуется горизонтальная черта
// если selected = true, то строка № 4 (посередине экрана, если не считать заголовка) выводится инвертированной
void SH1106_draw (char (*lines)[6][21], bool selected) {

  const uint8_t _address = 0x3C;

  // для каждой из 8 страниц памяти монитора
  for (uint8_t row = 0; row < 8; row++) {

    Wire.beginTransmission(_address);
    Wire.write(0x00); // OLED_COMMAND_MODE режим отправки команд нон-стопом
    Wire.write(0xB0 + row); // выбор адреса страницы 0..7
    Wire.write(2); // младший адрес столбца (не менять)
    Wire.write(16); // старший адрес столбца (не менять)

    uint8_t index_1, index_2;

    // отправка 8 пакетов по 16 байт (ограничения Wire.h)
    for (uint8_t col = 0; col < 128; col++) {

      // перезапускаем отправку каждые 16 байт
      if (col % 16 == 0) {
        Wire.endTransmission();
        Wire.beginTransmission(_address);
        Wire.write(0x40); // OLED_DATA_MODE
      }

      int8_t  bt = col % 6 - 1; // индекс байта в шрифте

      if (col > 125) Wire.write(col == 127 ? B00000000 : row == 1 ? B00000100 : row == 4 && selected ? B11111110 : row == 5 && selected ? B00000111 : B00000000);
      else if (bt == -1) {
        Wire.write(row == 1 ? B00000100 : row == 4 && selected ? B11111110 : row == 5 && selected ? B00000111 : B00000000);
        uint8_t ch = col / 6; // индекс символа в строке
        uint8_t i_1 = row < 1 ? 0 : row < 3 ? 1 : row < 4 ? 2 : row < 6 ? 3 : row < 7 ? 4 : 5;
        uint8_t i_2 = row == 2 ? 2 : row == 5 ? 4 : 0;
        index_1 = (uint8_t)(*lines)[i_1][ch] - 32;
        index_2 = i_2 != 0 ? (uint8_t)(*lines)[i_2][ch] - 32 : 0;
      } else if (row == 0) Wire.write( pgm_read_byte(&FONT[index_1][bt]) );
      else   if (row == 1) Wire.write( pgm_read_byte(&FONT[index_1][bt]) << 4 | B00000100 );
      else   if (row == 2) Wire.write( pgm_read_byte(&FONT[index_1][bt]) >> 4 | pgm_read_byte(&FONT[index_2][bt]) << 7 );
      else   if (row == 3) Wire.write( pgm_read_byte(&FONT[index_1][bt]) >> 1 );
      else   if (row == 4) Wire.write( selected ? (uint8_t)~pgm_read_byte(&FONT[index_1][bt]) << 2 | B00000010 : pgm_read_byte(&FONT[index_1][bt]) << 2 );
      else   if (row == 5) Wire.write( selected ? (uint8_t)~pgm_read_byte(&FONT[index_1][bt]) >> 6 | B00000100 | pgm_read_byte(&FONT[index_2][bt]) << 5 : pgm_read_byte(&FONT[index_1][bt]) >> 6 | pgm_read_byte(&FONT[index_2][bt]) << 5 );
      else   if (row == 6) Wire.write( pgm_read_byte(&FONT[index_1][bt]) >> 3 );
      else                 Wire.write( pgm_read_byte(&FONT[index_1][bt]) );

    }

    // закрываем отправку после выхода из цикла
    Wire.endTransmission();

  }

}

/* неиспользуемые
// вкл/выкл экран
void SH1106_power (bool value) {
  const uint8_t _address = 0x3C;
  Wire.beginTransmission(_address);
  Wire.write(0x80); // OLED_ONE_COMMAND_MODE
  Wire.write(value ? 0xAF : 0xAE); // OLED_DISPLAY_ON / OLED_DISPLAY_OFF
  Wire.endTransmission();
}
// яркость 0-255
void SH1106_contrast (uint8_t value) {
  Wire.beginTransmission(_address);
  Wire.write(0x00); // OLED_COMMAND_MODE
  Wire.write(0x81); // OLED_CONTRAST
  Wire.write(value);
  Wire.endTransmission();
  //delayMicroseconds(2);
}
*/





// глобальные переменные для работы с GPIO & ADC
// состояние энкодера из прерывания
volatile int8_t isr_encoder = 0;
// состояние кнопок из прерываний
volatile bool isr_top = false, isr_centre = false, isr_bottom = false;
// калибровочные значения центров осей аналоговых стиков
int16_t left_x_center  = 2048, left_y_center  = 2048, right_x_center = 2048, right_y_center = 2048;

// функции для работы с GPIO & ADC
// прерывание для энкодера. В результате выполнения в isr_encoder будет одно из трех направлений вращения: -1 / 0 / 1
static void IRAM_ATTR gpio_isr_encoder_handler (void *args) {

  static volatile bool last = false;
  if (gpio_get_level((gpio_num_t)7) && last) { // прерывание на gpio7 !!!
    isr_encoder = (gpio_get_level((gpio_num_t)6) == last) ? -1 : 1;
    last = false;
  } else last = true;

}
// прерывания для кнопок, должны срабатывать при отпускании кнопок - обработка дребезга, вероятно, не потребуется
static void IRAM_ATTR gpio_isr_top_handler    (void *args) { isr_top    = true; }
static void IRAM_ATTR gpio_isr_centre_handler (void *args) { isr_centre = true; }
static void IRAM_ATTR gpio_isr_bottom_handler (void *args) { isr_bottom = true; }
// функция для получения значения оси аналогового стика,
// принимает номер пина и калибровочный центр оси аналогового стика,
// возвращает отмасштабированные значения -2000..2000 с центром 0
int16_t adc_axis_value (uint8_t pin, int16_t ct) {

  const uint8_t dz = 100; // мертвая зона
  int16_t val = analogRead(pin);
  return (val > ct) ? map(constrain(val, ct + dz,    4095), ct + dz, 4095, 0,  2000)
                    : map(constrain(val,       0, ct - dz), ct - dz,    0, 0, -2000);

}
// инициализация цифровых и аналоговых портов
void gpio_init() {
  
  // инициализация "упрощенной" обработки прерываний
  gpio_install_isr_service(ESP_INTR_FLAG_LEVEL1); // 1-6, ESP_INTR_FLAG_NMI
  // gpio 5 кнопка "BACK"
  gpio_reset_pin((gpio_num_t)5);
  gpio_set_direction((gpio_num_t)5, GPIO_MODE_INPUT);
  gpio_set_pull_mode((gpio_num_t)5, GPIO_FLOATING);
  gpio_isr_handler_add((gpio_num_t)5, gpio_isr_top_handler, NULL);
  gpio_set_intr_type((gpio_num_t)5, GPIO_INTR_POSEDGE);
  gpio_intr_enable((gpio_num_t)5);
  // gpio 6 контакт энкодера "TRB" (единственный цифровой вход без прерывания)
  gpio_reset_pin((gpio_num_t)6);
  gpio_set_direction((gpio_num_t)6, GPIO_MODE_INPUT);
  gpio_set_pull_mode((gpio_num_t)6, GPIO_FLOATING);
  // gpio 7 контакт энкодера "TRA"
  gpio_reset_pin((gpio_num_t)7);
  gpio_set_direction((gpio_num_t)7, GPIO_MODE_INPUT);
  gpio_set_pull_mode((gpio_num_t)7, GPIO_FLOATING);
  gpio_isr_handler_add((gpio_num_t)7, gpio_isr_encoder_handler, NULL);
  gpio_set_intr_type((gpio_num_t)7, GPIO_INTR_ANYEDGE);
  gpio_intr_enable((gpio_num_t)7);
  // gpio 8 кнопка "PSH"
  gpio_reset_pin((gpio_num_t)8);
  gpio_set_direction((gpio_num_t)8, GPIO_MODE_INPUT);
  gpio_set_pull_mode((gpio_num_t)8, GPIO_FLOATING);
  gpio_isr_handler_add((gpio_num_t)8, gpio_isr_centre_handler, NULL);
  gpio_set_intr_type((gpio_num_t)8, GPIO_INTR_POSEDGE);
  gpio_intr_enable((gpio_num_t)8);
  // gpio 9 кнопка "CON"
  gpio_reset_pin((gpio_num_t)9);
  gpio_set_direction((gpio_num_t)9, GPIO_MODE_INPUT);
  gpio_set_pull_mode((gpio_num_t)9, GPIO_FLOATING);
  gpio_isr_handler_add((gpio_num_t)9, gpio_isr_bottom_handler, NULL);
  gpio_set_intr_type((gpio_num_t)9, GPIO_INTR_POSEDGE);
  gpio_intr_enable((gpio_num_t)9);
  // определение центров осей аналоговых стиков
  for (uint8_t i = 0; i < 64; i++) {
    left_x_center  = (left_x_center  + analogRead(A0)) / 2;
    left_y_center  = (left_y_center  + analogRead(A1)) / 2;
    right_x_center = (right_x_center + analogRead(A3)) / 2;
    right_y_center = (right_y_center + analogRead(A2)) / 2;
  }
  
}





// типы данных для организации связи по ESP-NOW
// структура заголовка сообщения
struct protocol_head_t { uint64_t protocol_uid; int64_t counter; };
// структура входящего сообщения - набор данных, выводимый на экран
struct options_message_t {
  protocol_head_t head;
  char lines[6][21];
  bool selected;
};
// структура исходящего пакета - набор значений органов управления
struct comands_message_t {
  protocol_head_t head;
  int16_t  left_x,
           left_y,
           right_x,
           right_y,
           encoder;
  bool     top,
           centre,
           bottom;
};
// глобальные переменные для организации связи по ESP-NOW
// робот и пульт должны использовать одинаковые каналы Wi-Fi и идентификаторы форматов сообщений!
// уникальный идентификатор формата данных options_message_t
const uint64_t protocol_options_uid = 8683477418810728652;
// уникальный идентификатор формата данных comands_message_t
const uint64_t protocol_comands_uid = 8900317804858057850;
// используемый канал Wi-Fi
uint8_t chanel = 1;
// количество неполучений пакетов, при котором будет зафиксирована потеря связи
const uint16_t rc_silence_lost = 5;
// счетчик количества неполученных пакетов
uint16_t rc_silence = rc_silence_lost;





// функция для приема сообщений по протоколу ESP-NOW и ответа на них
void rc_receive (const uint8_t*  mac, const uint8_t* data, int data_len) {

  static int64_t counter = 0;

  // сначала проверяем, а что собсно пришло
  if (data_len == sizeof(options_message_t)) {

    // получение заголовка данных
    protocol_head_t head;
    memcpy(&head, data, sizeof(protocol_head_t));
    
    // проверка соответствия типа протокола
    if (head.protocol_uid == protocol_options_uid) {

      // есть ли пир в списке
      if (esp_now_is_peer_exist(mac)) {

        // пакет пришел от зарегистрированного пира
        // если соблюдается очередность следования пакетов, или была потеря связи
        if (head.counter > counter || rc_silence >= rc_silence_lost) {
          
          // сброс счетчика неполученных пакетов
          rc_silence = 0;
          // вывод принятых данных на экран
          options_message_t options_message;
          memcpy(&options_message, data, sizeof(options_message_t));
          SH1106_draw(&options_message.lines, options_message.selected);
          // подготовка набора команд в ответ
          // накопительный счетчик для энкодера
          static int16_t inc = 0;
          inc = isr_encoder == 0 ? (inc > 0 ? inc - 1 : 0) : (inc < 10 ? inc + 1 : 10);
          int16_t encoder = (isr_encoder == 0) ? 0 : (isr_encoder > 0 ? inc * inc : - inc * inc);
          comands_message_t comands_message = {
            .head = (protocol_head_t) { protocol_comands_uid, esp_timer_get_time() },
            .left_x  = adc_axis_value(A0, left_x_center ),
            .left_y  = adc_axis_value(A1, left_y_center ),
            .right_x = adc_axis_value(A3, right_x_center),
            .right_y = adc_axis_value(A2, right_y_center),
            .encoder = encoder,
            .top     = isr_top,
            .centre  = isr_centre,
            .bottom  = isr_bottom
          };
          // сброс использованных значений кнопок и энкодера
          isr_encoder = 0;
          isr_top     = false;
          isr_centre  = false;
          isr_bottom  = false;
          // таргетная отправка команд
          esp_now_send(NULL, (uint8_t*)&comands_message, sizeof(comands_message_t));

        } // else сообщения старше последнего принятого игнорируются

      } else if (rc_silence >= rc_silence_lost) {

        // пакет пришел от незарегистрированного приа, но после потери связи
        // удаление всех сохраненных unicast пиров
        esp_now_peer_info_t peer;
        while (esp_now_fetch_peer(true, &peer) == ESP_OK) esp_now_del_peer(peer.peer_addr);
        // формирование данных пира, от которого получен пакет
        esp_now_peer_info_t unicastPeer = {
          .peer_addr = { mac[0],mac[1],mac[2],mac[3],mac[4],mac[5] },
          .lmk = { 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00 },
          .channel = chanel,
          .ifidx = WIFI_IF_STA,
          .encrypt = false,
          .priv = NULL
        };
        // добавление пира, от которого получен пакет (иначе не сможем ему ничего отправить)
        esp_now_add_peer(&unicastPeer);
        // сброс неактуальных значений кнопок и энкодера
        isr_encoder = 0;
        isr_top     = false;
        isr_centre  = false;
        isr_bottom  = false;

      }

    } // else уникальный идентификатор формата инфообмена не соответствует ожидаемому

  } // else длина пакета не соответствует ожидаемой

}





// задача с заданной периодичностью ведет счетчик неполучения пакетов
// в случае, если связь потеряна - выводит на экран соответствующую информацию
void task_connection_watch (void *param) {

  // ИНИЦИАЛИЗАЦИЯ

  // периодичность вызова в миллисекундах
  const uint16_t pheriod_ms = 50;

  // инициализация портов и прерываний
  gpio_init();

  // инициализация экрана
  SH1106_init();

  // запуск Wi-Fi
  WiFi.mode(WIFI_STA);
  // инициализация ESP-NOW
  esp_now_init();
  // привязка функции обработки полученных данных
  esp_now_register_recv_cb(rc_receive);

  // запуск бесконечного цикла задачи
  for (;;) {
    
    // время начала цикла задачи
    TickType_t last_start_at = xTaskGetTickCount();

    if (rc_silence >= rc_silence_lost) {
      
      // нет установленной связи с каким-либо устройством
      // наполнение экрана текстом
      char lines[6][21] = { { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                            { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                            { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                            { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                            { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                            { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 } };
      memcpy(lines[0], F("    DISCONNECTED!    "), 21);
      memcpy(lines[3], F("Turn ON your robot..."), 21);
      // отрисовка экрана
      SH1106_draw(&lines, esp_timer_get_time() / 1000000 % 2 != 0);
      
    }

    // если не будет вызова rc_receive() то rc_silence будет расти каждую итерацию
    if (rc_silence <= rc_silence_lost) rc_silence++;

    // возврат управления шедулеру
    vTaskDelayUntil(&last_start_at, pdMS_TO_TICKS(pheriod_ms));
    
  }
  
  // аварийная остановка задачи (не должна сработать никогда)
  vTaskDelete(NULL);
  
}





void setup () {
  
  // можно было инициализацию прописать здесь, но прописана в task_connection_watch
  
  // запуск задачи
  xTaskCreatePinnedToCore (task_connection_watch, "R/C", 4096, NULL, (2 | portPRIVILEGE_BIT), NULL, xPortGetCoreID());

}





void loop() {
  
  // пережиток прошлого...

  vTaskDelay(pdMS_TO_TICKS(10000));

}





С роботом по-проще:

#include "freertos/FreeRTOS.h"
#include "freertos/task.h"

#include <esp_now.h>
#include <WiFi.h>





// структура для хранения пары значений "номер вывода GPIO" - "ширина импульса PWM в микросекундах"
struct pwm_channel_t { uint8_t pin; uint16_t value; };

// массив каналов PWM
pwm_channel_t cahnnels[] = { { 18, 1500 }, { 48,    0 }, {  1,    0 },
                             {  2,    0 }, {  3,    0 }, {  4,    0 },
                             { 12,    0 }, { 13,    0 }, { 14,    0 },
                             {  5,    0 }, {  6,    0 }, {  7,    0 },
                             {  9,    0 }, { 10,    0 }, { 17,    0 },
                             { 21,    0 }, { 38,    0 }, { 47,    0 } };





// задача для генерации импульсов PWM на все каналы каждые 20 миллисекунд
void task_pwm (void *param) {

  // ИНИЦИАЛИЗАЦИЯ

  // периодичность вызова в миллисекундах
  const uint16_t pheriod_ms = 20;

  // количество каналов
  const uint8_t cahnnelsCount = sizeof(cahnnels) / sizeof(cahnnels[0]);

  // ограничение максимальной длины импульса
  const uint16_t pulseWidthTreshold = 3000;

  // маски регистров, по которым будут подниматься каналы
  uint32_t up_port_0_mask = 0, up_port_1_mask = 0;
  // массив последовательности временных задержек
  uint16_t delays[cahnnelsCount];
  // массивы масок регистров, по которым будут гаситься каналы
  uint32_t down_port_0_masks[cahnnelsCount];
  uint32_t down_port_1_masks[cahnnelsCount];

  for (uint8_t i = 0; i < cahnnelsCount; i++) {
    // конфигурация выводов
    gpio_reset_pin((gpio_num_t)cahnnels[i].pin);
    gpio_set_direction((gpio_num_t)cahnnels[i].pin, GPIO_MODE_OUTPUT);
    gpio_set_pull_mode((gpio_num_t)cahnnels[i].pin, GPIO_FLOATING);
    // установка нулевых стартовых значений для масок и задержек
    delays[i] = 0;
    down_port_0_masks[i] = 0;
    down_port_1_masks[i] = 0;
  }

  // запуск бесконечного цикла задачи
  for (;;) {

    // блокировка шедулера - гарантия, что формирование импульсов выполнится без остановки на другие задачи
    vTaskSuspendAll();

    // время начала генерации импульсов (для определения момента следующего старта)
    TickType_t last_PWM_at = xTaskGetTickCount();

    // ГЕНЕРАЦИЯ ИМПУЛЬСОВ

    // переача в регистры масок, содержащих биты всех портов с не нулевой длиной импульса
    GPIO.out_w1ts      |= up_port_0_mask;
    GPIO.out1_w1ts.val |= up_port_1_mask;

    // гашение портов согласно очередности с соответствующими задержками
    for (uint8_t i = 0; i < cahnnelsCount; i++) {
      // задержка
      ets_delay_us(delays[i]);
      // переача в регистры масок, содержащих биты всех портов, которые необходимо погасить на данной итерации
      GPIO.out_w1tc      |= down_port_0_masks[i];
      GPIO.out1_w1tc.val |= down_port_1_masks[i];
    }

    // ВЫЗОВ ПЕРЕРАССЧЕТА КИНЕМАТИКИ

    // с использованием дельты времени 20 мс в качестве инкрементов всех процессов
    // ...

    // ПОДГОТОВКА ДАННЫХ ДЛЯ СЛЕДУЮЩЕЙ ИТЕРАЦИИ

    // маски регистров, по которым будут подниматься порты (временные переменные)
    uint32_t tmp_up_port_0_mask = 0, tmp_up_port_1_mask = 0;
    // массив последовательности временных задержек (временные переменные)
    uint16_t tmp_delays[cahnnelsCount];
    // массивы масок регистров, по которым будут гаситься порты (временные переменные)
    uint32_t tmp_down_port_0_masks[cahnnelsCount];
    uint32_t tmp_down_port_1_masks[cahnnelsCount];
    // установка нулевых значений задержек и масок
    for (uint8_t i = 0; i < cahnnelsCount; i++) {
      tmp_delays[i] = 0;
      tmp_down_port_0_masks[i] = 0;
      tmp_down_port_1_masks[i] = 0;
    }
    // минимальная длина импульса, определенная на предыдущей итерации цикла наполнения массивов
    int32_t minPreviouse = -1;
    // минимальная длина импульса, определенная на текущей итерации цикла наполнения массивов
    uint16_t minCurrent = cahnnels[0].value;
    // счетчик обработанных каналов
    uint8_t current = 0;
    // индекс текущего элемента во временных массивах
    uint8_t to = 0;
    // признак того, что наполнение массивов прошло успешно
    bool succesfull = true;
    
    // цикл наполнения массивов
    while ((current < cahnnelsCount) && succesfull) {
      
      // поиск минимального значения длины импульса, превосходящего предыдущее значение (найденное в предыдущей итерации)
      for (uint8_t i = 0; i < cahnnelsCount; i++) if (cahnnels[i].value < minCurrent && cahnnels[i].value > minPreviouse)
        minCurrent = cahnnels[i].value;
      
      // запись значения дельты времени в массив задержек
      tmp_delays[to] = minPreviouse == -1 ? minCurrent : minCurrent - minPreviouse;
      // перезапись предыдущего минимального значения
      minPreviouse = minCurrent;

      // сброс признака успешного наполнения массивов
      succesfull = false;
      // формирование масок для всех каналов ШИМ, у которых длина импульса равна найденной
      for (uint8_t from = 0; from < cahnnelsCount; from++) if (cahnnels[from].value == minCurrent) {

        // если cahnnels[] не изменялся извне и наполнение проходит успешно, то данная команда выполнится хотя бы раз за каждый проход
        succesfull = true;

        // если длина импульса на канале ненулевая, то в порты добавляется бит соответствующего пина
        if (minCurrent > 0) {

          // определение группы регистров
          if (cahnnels[from].pin > 32) {

            // смещение в регистрах группы 1
            uint32_t add_1 = 1 << (cahnnels[from].pin - 32);
            // добавление в маску регистра поднимающихся портов
            tmp_up_port_1_mask |= add_1;
            // добавление в маску регистра гасящихся портов
            tmp_down_port_1_masks[to] |= add_1;

          } else {

            // смещение в регистрах группы 0
            uint32_t add_0 = 1 << cahnnels[from].pin;
            // добавление в маску регистра поднимающихся портов
            tmp_up_port_0_mask |= add_0;
            // добавление в маску регистра гасящихся портов
            tmp_down_port_0_masks[to] |= add_0;

          }

        }

        // инкриментация счетчика обработанных каналов
        current++;

      }

      // инкриментация индекса текущего элемента в наполняемых массивах
      to++;

      // сброс минимума для успешного поиска на следующей итерации
      minCurrent = pulseWidthTreshold;
    
    }
  
    // если наполнения массивов прошло успешно
    if (succesfull) {
      
      // копирование масок поднятия портов
      up_port_0_mask = tmp_up_port_0_mask;
      up_port_1_mask = tmp_up_port_1_mask;

      // копирование значениq из временных массивов в массивы для генерации импульсов
      for (uint8_t i = 0; i < cahnnelsCount; i++) {

        delays[i] = tmp_delays[i];
        down_port_0_masks[i] = tmp_down_port_0_masks[i];
        down_port_1_masks[i] = tmp_down_port_1_masks[i];

      }
      
    } // else при желании можно зафиксировать ошибку
    
    // разблокировка шедулера
    xTaskResumeAll();

    // возврат управления шедулеру
    vTaskDelayUntil(&last_PWM_at, pdMS_TO_TICKS(pheriod_ms));
    
  }
  
  // аварийная остановка задачи (не должна сработать никогда)
  vTaskDelete(NULL);
  
}





const uint64_t protocol_options_uid = 8683477418810728652;
const uint64_t protocol_comands_uid = 8900317804858057850;

struct protocol_head_t { uint64_t protocol_uid; int64_t counter; };

struct options_message_t {
  protocol_head_t head;
  char lines[6][21];
  bool selected;
};

struct comands_message_t {
  protocol_head_t head;
  int16_t  left_x,
           left_y,
           right_x,
           right_y,
           encoder;
  bool     top,
           centre,
           bottom;
};

// принимаемое сообщение с набором команд от пульта
comands_message_t commands_message;
// количество неполучений пакетов, при котором будет зафиксирована потеря связи и будут рассылаться запросы на коннект
const uint16_t rc_silence_lost = 5;
// количество неполучений пакетов, при котором инициируется складывание конструкции
const uint16_t rc_silence_lay_down = 20;
// счетчик количества неполученных пакетов (при включении робота соединения не будет)
uint16_t rc_silence = rc_silence_lay_down;
// используемый канал Wi-Fi, должен быть одинаковый на роботе и пульте
uint8_t chanel = 1;





// ф-ия приема
void rc_receive (const uint8_t*  mac, const uint8_t* data, int data_len) {

  // сначала проверяем, а что собсно пришло
  if (data_len == sizeof(comands_message_t)) {
    
    // получение заголовка данных
    protocol_head_t head;
    memcpy(&head, data, sizeof(protocol_head_t));
    
    // проверка соответствия типа протокола
    if (head.protocol_uid == protocol_comands_uid) {
      // есть ли пир в списке
      if (esp_now_is_peer_exist(mac)) {

        // пакет пришел от зарегистрированного пира
        // соблюдается ли очередность следования пакетов или была потеря связи
        if (head.counter >= commands_message.head.counter) {
      
          // принимаем новый контролл целиком, еали не было потери связи
          memcpy(&commands_message, data, sizeof(comands_message_t));
          // сброс счетчика неполученных пакетов
          rc_silence = 0;
      
        } else if (rc_silence >= rc_silence_lost) {

          // так как пользователь не видел опций робота, принимаем ТОЛЬКО счетчик пакетов
          commands_message.head.counter = head.counter;
          // сброс счетчика неполученных пакетов
          rc_silence = 0;

        } // else сообщения старше последнего принятого игнорируются

      } else if (rc_silence >= rc_silence_lost) {

        // пакет пришел от незарегистрированного приа, но после потери связи
        // так как пользователь не видел опций робота, принимаем ТОЛЬКО счетчик пакетов
        commands_message.head.counter = head.counter;
        // сброс счетчика неполученных пакетов
        rc_silence = 0;
        // удаление всех сохраненных unicast пиров
        esp_now_peer_info_t peer;
        while (esp_now_fetch_peer(true, &peer) == ESP_OK) esp_now_del_peer(peer.peer_addr);
        // формирование данных пира, от которого получен пакет
        esp_now_peer_info_t unicastPeer = {
          .peer_addr = { mac[0],mac[1],mac[2],mac[3],mac[4],mac[5] },
          .lmk = { 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00 },
          .channel = chanel,
          .ifidx = WIFI_IF_STA,
          .encrypt = false,
          .priv = NULL
        };
        // добавление пира, от которого получен пакет (иначе не сможем ему ничего отправить)
        esp_now_add_peer(&unicastPeer);

      }

    } // else уникальный идентификатор формата инфообмена не соответствует ожидаемому
      
  } // else длина пакета не соответствует ожидаемой

}





// платформа всегда может либо выполненять кинематического задания, либо находиться в одном из статичных состояний и ожидать команды
enum conditions_t {
  LAYED,
  CALIBRATION,
  RISED,
  ANIMATIONS,
  TUNE
};
// стилей управления сервоприводами тоже два: прямое (только для калибровки) и координатное





// задача для организации управления и связи
void task_rc (void *param) {

  // ИНИЦИАЛИЗАЦИЯ

  // периодичность вызова в миллисекундах
  const uint16_t pheriod_ms = 20;

  // адрес для широковещательного (broadcast) запроса
  uint8_t broadcast[6] = { 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF };

  // запуск Wi-Fi
  WiFi.mode(WIFI_STA);
  // инициализация ESP-NOW
  esp_now_init();

  // создание конфига broadcast пира
  esp_now_peer_info_t broadcastPeer = {
    .peer_addr = { broadcast[0],broadcast[1],broadcast[2],broadcast[3],broadcast[4],broadcast[5] },
    .lmk = { 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00 },
    .channel = chanel,
    .ifidx = WIFI_IF_STA,
    .encrypt = false,
    .priv = NULL
  };
  // добавление broadcast пира
  esp_now_add_peer(&broadcastPeer);

  // текущее состояние
  conditions_t condition = LAYED;

  // запуск бесконечного цикла задачи
  for (;;) {

    // время начала цикла (для определения момента следующего старта)
    TickType_t last_RC_at = xTaskGetTickCount();
    
    // отключение обработки принятых сообщений воизбежание модификации данных контроллов
    esp_now_unregister_send_cb();
    
    // предзаполнение пакета для отправки
    options_message_t options_message = {
      .head = {
        .protocol_uid = protocol_options_uid,
        .counter = esp_timer_get_time()
      },
      .lines = { { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                 { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                 { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                 { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                 { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                 { 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 } },
      .selected = false
    };

    // обработка команд и управление состояниями
    if (false) {

      // ВЫПОЛНЯЕТСЯ КИНЕМАТИЧЕСКОЕ ЗАДАНИЕ
      
      String("    PROCESSING...    ").toCharArray(options_message.lines[0], 22);
      // как вариант сделать таймер обратного отсчета в строке № 4

    } else if (condition == LAYED) {

      // СЛОЖЕННОЕ СОСТОЯНИЕ
    
      String menu[] = {
        "  Rise!              ",
        "  Calibration        "
      };
      uint8_t count = sizeof(menu) / sizeof(menu[0]);
      static uint8_t i = 0;

      if (commands_message.bottom || commands_message.centre) {
        if (i == 0) {
          // создает задание перевода из LAYED в RISED
          // ***
        } else if (i == 1) {
          // создает задание перевода из LAYED в CALIBRATION
          condition = CALIBRATION; // ***
        }
      } else if (commands_message.encoder > 0) {
        i = (i == count - 1) ? 0 : i + 1 ;
      } else if (commands_message.encoder < 0) {
        i = (i == 0) ? count - 1 : i - 1 ;
      }

      memcpy(options_message.lines[0], F("        LAYED        "), 21);
      options_message.selected = true;
      if (i > 1)         memcpy(options_message.lines[1], menu[i - 2].c_str(), 21);
      if (i > 0)         memcpy(options_message.lines[2], menu[i - 1].c_str(), 21);
                         memcpy(options_message.lines[3], menu[i    ].c_str(), 21);
      if (i < count - 1) memcpy(options_message.lines[4], menu[i + 1].c_str(), 21);
      if (i < count - 2) memcpy(options_message.lines[5], menu[i + 2].c_str(), 21);

      //String celsius = String(temperatureRead());
      //memcpy(options_message.lines[0], celsius.c_str(), celsius.length());

    } else if (condition == CALIBRATION) {

      // КАЛИБРОВКА СЕРВОПРИВОДОВ
    
      // инициализация перевода из CALIBRATION в LAYED при окончательной потере связи
      if (rc_silence >= rc_silence_lay_down) {  }
      
      static uint8_t screen = 0, // текущее подменю
                     limb   = 0, // выбранная конечность
                     servo  = 0, // выбранная серво
                     point  = 0; // выбранная позиция привязки значения
      
      static uint16_t value; // текущее положение вала серво

      if (screen == 0) {
        
        // ЭКРАН ВЫБОР СЕРВО
        
        // список
        String menu[] = {
          "< Lay                ",
          "  Limb 0, Servo 0    ",
          "  Limb 0, Servo 1    ",
          "  Limb 0, Servo 2    ",
          "  Limb 1, Servo 0    ",
          "  Limb 1, Servo 1    ",
          "  Limb 1, Servo 2    ",
          "  Limb 2, Servo 0    ",
          "  Limb 2, Servo 1    ",
          "  Limb 2, Servo 2    ",
          "  Limb 3, Servo 0    ",
          "  Limb 3, Servo 1    ",
          "  Limb 3, Servo 2    ",
          "  Limb 4, Servo 0    ",
          "  Limb 4, Servo 1    ",
          "  Limb 4, Servo 2    ",
          "  Limb 5, Servo 0    ",
          "  Limb 5, Servo 1    ",
          "  Limb 5, Servo 2    "
        };
        uint8_t count = sizeof(menu) / sizeof(menu[0]);
        static uint8_t i = 0;
        
        // контроллы
        if (commands_message.top || ((commands_message.bottom || commands_message.centre) && i == 0)) {
          // инициализация задания перевода из CALIBRATION в LAYED
          condition = LAYED; // ***
        } else if (commands_message.bottom || commands_message.centre) {
          // выбор серво
          limb = (i - 1) / 3;
          servo = (i - 1) % 3;
          screen = 1;
          value = cahnnels[0].value; // ***
        } else if (commands_message.encoder > 0) {
          // прокрутка вниз
          i = (i == count - 1) ? 0 : i + 1 ;
        } else if (commands_message.encoder < 0) {
          // прокрутка вверх
          i = (i == 0) ? count - 1 : i - 1 ;
        }
        
        // отрисовка
        memcpy(options_message.lines[0], F("     CALIBRATION     "), 21);
        options_message.selected = true;
        if (i > 1)         memcpy(options_message.lines[1], menu[i - 2].c_str(), 21);
        if (i > 0)         memcpy(options_message.lines[2], menu[i - 1].c_str(), 21);
                           memcpy(options_message.lines[3], menu[i    ].c_str(), 21);
        if (i < count - 1) memcpy(options_message.lines[4], menu[i + 1].c_str(), 21);
        if (i < count - 2) memcpy(options_message.lines[5], menu[i + 2].c_str(), 21);
        
      } else if (screen == 1) {
        
        // ЭКРАН ПОЗИЦИОНИРОВАНИЕ СЕРВО
        
        // контроллы
        if (commands_message.top) {
          screen = 0;
        } else if (commands_message.bottom || commands_message.centre) {
          screen = 2;
          point = 1;
        } else if (commands_message.encoder != 0) {
          value = constrain(value + commands_message.encoder, 500, 2500);
          // установить ШИМ напрямую
          cahnnels[0].value = value; // ***
        }
        
        // отрисовка
        memcpy(options_message.lines[0], ("   LIMB " + String(limb) + ", SERVO " + String(servo) + "   ").c_str(), 21);
        int16_t a_min = -30, a_mid = 0, a_max = 30, p_min = 500, p_mid = 1500, p_max = 2500;
        memcpy(options_message.lines[2] + 4 - String(a_min).length(), String(a_min).c_str(), String(a_min).length());
        memcpy(options_message.lines[3] + 4 - String(a_mid).length(), String(a_mid).c_str(), String(a_mid).length());
        memcpy(options_message.lines[4] + 4 - String(a_max).length(), String(a_max).c_str(), String(a_max).length());
        options_message.lines[2][5] = '=';
        options_message.lines[3][5] = '=';
        options_message.lines[4][5] = '=';
        memcpy(options_message.lines[2] + 7, String(p_min).c_str(), String(p_min).length());
        memcpy(options_message.lines[3] + 7, String(p_mid).c_str(), String(p_mid).length());
        memcpy(options_message.lines[4] + 7, String(p_max).c_str(), String(p_max).length());
        memcpy(options_message.lines[3] + 19 - String(value).length(), String(value).c_str(), String(value).length());
        options_message.lines[3][20] = '<';
        
      } else if (screen == 2) {
        
        // ЭКРАН ПРИВЯЗКА ПОЗИЦИИ
        
        char menu[3][21] = { { 32,32,32,32,32,'=',32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                             { 32,32,32,32,32,'=',32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 },
                             { 32,32,32,32,32,'=',32,32,32,32,32,32,32,32,32,32,32,32,32,32,32 } };

        
        // действия
        if (commands_message.top) {
          screen = 1;
        } else if (commands_message.bottom || commands_message.centre) {
          // применить калибровку к точке
          screen = 1;
          // servo_min_mid_max = value
        } else if (commands_message.encoder > 0) {
          // прокрутка вниз
          point = (point == 2) ? 0 : point + 1 ;
        } else if (commands_message.encoder < 0) {
          // прокрутка вверх
          point = (point == 0) ? 2 : point - 1 ;
        }

        // отрисовка
        memcpy(options_message.lines[0], F("  What position is?  "), 21);
        options_message.selected = true;

        int16_t a_min = -30, a_mid = 0, a_max = 30, p_min = 500, p_mid = 1500, p_max = 2500;
        memcpy(menu[0] + 4 - String(a_min).length(), String(a_min).c_str(), String(a_min).length());
        memcpy(menu[1] + 4 - String(a_mid).length(), String(a_mid).c_str(), String(a_mid).length());
        memcpy(menu[2] + 4 - String(a_max).length(), String(a_max).c_str(), String(a_max).length());
        menu[0][5] = '=';
        menu[1][5] = '=';
        menu[2][5] = '=';
        memcpy(menu[0] + 7, String(p_min).c_str(), String(p_min).length());
        memcpy(menu[1] + 7, String(p_mid).c_str(), String(p_mid).length());
        memcpy(menu[2] + 7, String(p_max).c_str(), String(p_max).length());

        if (point > 1) memcpy(options_message.lines[1], menu[point - 2], 21);
        if (point > 0) memcpy(options_message.lines[2], menu[point - 1], 21);
                       memcpy(options_message.lines[3], menu[point    ], 21);
        if (point < 2) memcpy(options_message.lines[4], menu[point + 1], 21);
        if (point < 1) memcpy(options_message.lines[5], menu[point + 2], 21);

        memcpy(options_message.lines[3] + 19 - String(value).length(), String(value).c_str(), String(value).length());
        options_message.lines[3][13] = '<';
        options_message.lines[3][12] = '<';
        
      }

    } else if (condition == RISED) {

      // ПОХОДНАЯ СТОЙКА
    
      // инициализация перевода из RISED в LAYED при окончательной потере связи
      if (rc_silence >= rc_silence_lay_down) {  }

      // обрабатываем контроллы

      // строим пункты меню
      // - LAY (создает задание перевода в LAYED)
      // - ANIMATIONS (переключение в ANIMATIONS)
      // - PARAMETERS (переключение в TUNE)
      
      static uint8_t i = 0;

    } else if (condition == ANIMATIONS) {

      // ПОХОДНАЯ СТОЙКА - СПИСОК АНИМАЦИЙ
    
      // инициализация перевода из ANIMATIONS в LAYED при окончательной потере связи
      if (rc_silence >= rc_silence_lay_down) {  }

      // обрабатываем контроллы

      // строим пункты меню
      // - Back (переключение в RISED)
      // - Animation 1 (создает задание выполнение анимации Animation 1)
      // - Animation 2 (создает задание выполнение анимации Animation 2)
      // - Animation 3 (создает задание выполнение анимации Animation 3)
      // - ...
      
      static uint8_t i = 0;

    } else if (condition == TUNE) {

      // ПОХОДНАЯ СТОЙКА - НАСТРОЙКА ПАРАМЕТРОВ ХОДЬБЫ
    
      // инициализация перевода из TUNE в LAYED при окончательной потере связи
      if (rc_silence >= rc_silence_lay_down) {  }

      // обрабатываем контроллы

      // строим пункты меню
      // - Back (переключение в RISED)
      // - Setting 1 (отображение окна настройки параметра 1)
      // - Setting 2 (отображение окна настройки параметра 2)
      // - Setting 3 (отображение окна настройки параметра 3)
      // - ...
      
      static uint8_t i = 0;

    }

    // обнуление контроллов, так как они уже использовались
    commands_message.left_x = 0;
    commands_message.left_y = 0;
    commands_message.right_x = 0;
    commands_message.right_y = 0;
    commands_message.encoder = 0;
    commands_message.top = false;
    commands_message.centre = false;
    commands_message.bottom = false;

    // привязка функции обработки полученных данных
    esp_now_register_recv_cb(rc_receive);

    // отправка запроса на команды: таргетно (если не потеряна связь) или широковещательно (если связь потеряна)
    esp_now_send((rc_silence > rc_silence_lost) ? broadcast : NULL, (uint8_t*)&options_message, sizeof(options_message_t));

    // если не будет вызова rc_receive() то rc_silence будет расти каждую итерацию
    if (rc_silence <= rc_silence_lay_down) rc_silence++;

    // возврат управления шедулеру
    vTaskDelayUntil(&last_RC_at, pdMS_TO_TICKS(pheriod_ms));
    
  }
  
  // аварийная остановка задачи (не должна сработать никогда)
  vTaskDelete(NULL);
  
}





void setup () {

  Serial.begin (9600);

  // добавление задач в шедулер (функция, имя, размер_стека, параметры_NULL, приоритет, хэндлер_NULL, текущее_ядро) // TaskHandle_t taskHandler_pwm;
  xTaskCreatePinnedToCore (task_pwm, "PWM", 4096, NULL, (2 | portPRIVILEGE_BIT), NULL, xPortGetCoreID());
  xTaskCreatePinnedToCore (task_rc, "R/C", 4096*10, NULL, (2 | portPRIVILEGE_BIT), NULL, xPortGetCoreID());

}





void loop() {

  // пережиток прошлого...

  vTaskDelay(pdMS_TO_TICKS(10000));

}





Таки сократил передачу char[6][22] до char[6][21]. Перейти на memcpy для сшивания строк оказалось вроде неплохим решением. Плюс переделана полностью логика обработки энкодера. Ну и естессно ШИМ и связь работают хорошо.

Я смотрю вам нравится набивать на клавиатуре одинаковый текст десятками строк.

По первому коду,

строка 114 процедура SH1106_init - не приходило в голову положить инициализацию экрана в массив и вызывать Wire.write(х) в цикле?

строка256 функция gpio_init() - 4 однотипных блока инита пина

строка 465 - набивать число 32 аж 126 раз рука не устала?

приходило. пока поленился.

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

вот тут если знаете, как заполнить его при объявлении более короткой записью - поделитесь, пожалуйста. Может ф-ия какая-нибудь есть… Наверное можно было memset вызывать после объявления, но не присвоить ничего при объявлении в поле структуры - тоже нельзя, пришлось бы объявить без заполнения, а потом все поля по отдельности писать.

прошу прощения, это касалось второго скетча, строки 368…380:

Можно ли здесь массив, являющийся полем структуры, заполнить более короткой записью?

Обнаружилась проблема: при подключении 18 сервоприводов проц греется до 120 градусов. Когда сервоприводов три, температура не выше 60 градусов. Это можно решить настройкой gpio? Вроде бы ограничение тока присутствует, может помочь? Или резисторы нужно паять на выходы?

UPD:

По всей видимости, ушатал одну из плат. Поставил новую, на том же скетче под 18-ю серво температура не выше 55. Правда добавил в настройки выходов gpio_set_drive_capability ((gpio_num_t)pinout[i], GPIO_DRIVE_CAP_0); уж не знаю, лучше сделал или напротив…

UPD2: коту явно не нравится результат моей деятельности

Из интересного, в качестве стаба напряжения использовал XL4015, заявленный на 5А всего лишь. И он холодный… Хотя я морально был готов даже к тому, что всё испустит волшебный дымок (есть запас железок). При том, что с 1 сервы на мультитестере удавалось выжать ампер, правда есть сомнения в адекватности замера.

Вот вопрос про конфиг выводов остается пока открытым. Уж не знаю, почему тот камень начал в 120+ выходить, может я его сам довел - были ошибки в подключении и не только. А может новую ждет то же самое ((

Очень живучие. Но китайцы бывает под видом XL4015 присылают на LM2596. Те от больших токов быстро дохнут.

Вот отсюда нормальные приходят:

1 лайк

это именно 4015

если не греется, это еще не означает, что всё ок?

Не понял вопроса. Если не греется (у меня по крайней мере) - то нет предпосылок для беспокойства. У меня платы с ограничением тока (покупал по ссылке выше, красные если память не изменяет) - вообще проблем нет. Без ограничения тока тоже имеются и тоже без проблем работают.

1 лайк

спасибо, именно этот вопрос беспокоил. Я не силен в схемотехнике и принципе работы этого DC-DC. Собсно, не имел понятия, что там могло сгореть, и предшествовал бы этому перегрев, или нет.

1 лайк

А, у меня еще для перестраховки на 4015 вот такого плана радиаторы наклеены (покупал специально для 4015, ссылка уже мертвая):

а я у этого https://aliexpress.ru/item/32675181727.html заказал про запас, там в комплекте радиаторы.

Кстати, тут на маркетплейсы ссылки не запрещено постить, ниче не будет?

Не запрещено. Даже тема есть отдельная:

:smiley:

1 лайк

В общем, одной из вероятных причин перегрева одной esp32-s3-nano (она до сих пор работает, но даже без периферии греется до 120 в первую минуту включения) вижу отсутствие ограничения тока на выходах. Вернее при значении по умолчанию 20ма, в сумме получается 360ма на выходы gpio. Не знаю, много это или мало, и могли ли сервоприводы взять этот ток на своих входах… Буду рад экспертному мнению, в т.ч. правильно ли использовать ограничение тока настройкой gpio_set_drive_capability или это вредительство

вредительство это подключать серву на пины контроллера

скорее всего много. Как правило, общий ток через плату не рассчитывается на случай. что все выводы будут отбирать максимальный ток - обычно предел в три-пять раз меньше.

Но вообще непонятно, о каком токе 20 мА вы говорите? Разделяйте цепь питания и цепь управления. Питание сервы должно быть внешним, не через ЕСП. К контроллеру подключается только цепь управления.
Управляющий ток сервы SG90 менее 1 мА

1 лайк