Ардупилот на платах OpenPilot Revolution / RevoMini (записей: 1756)

  • Аватар профиля kozin Алексей Козин в 7 г., 2 мес. назад

    я встречал пару раз необъяснимое мне поведение в коде запускаемом по таймеру

    например если сделать вывод в дебаг вывод состояний из функции зарегистрированной в таймере так

    hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Camera::feedback_pin_timer, void));

    то при частоте вызовов 1кгц я в консоли получаю 1-символьные значения крайне нестабильно, раз у несколько сек.

    если в этой же функции стоит что либо быстрое например переброс выхода 0-1-0-1 то все отрабатывает - вижу на пине генерацию 500гц.

    из чего чисто теоретически делаю вывод что если функция не успела отработать за отведенный период ее прерывают и перезапускают.

    собственно кто таков этот функтор и в чем его специфика - для меня темный лес

    в доке другой пример http://ardupilot.org/dev/docs/learning-ardupilot-threading.html

    hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_Baro_MS5611::_update));

    кстати в олед индикаторе после того как тиджел его включил в свою версию - тоже стало все рассыпаться именно тогда когда он повесил обновление на таймер

     

  • Аватар профиля Night_Ghost Night_Ghost287 пунктов в 7 г., 2 мес. назад
    [2017-01-02 15:03:15] kozin писал(а): то при частоте вызовов 1кгц я в консоли получаю 1-символьные значения крайне нестабильно, раз у несколько сек.

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

    [2017-01-02 15:03:15] kozin писал(а): если функция не успела отработать за отведенный период ее прерывают и перезапускают

    Это вопросы реализации конкретного шедулера, я так не делаю.

     

    [2017-01-02 15:03:15] kozin писал(а): обственно кто таков этот функтор и в чем его специфика - для меня темный лес

    Просто обертка для того чтобы можно было унифицированно вызвать метод любого класса без возни с оператором ->*

    [2017-01-02 15:03:15] kozin писал(а): в доке другой пример

    Дока ни о чем, если в двух словах то нужны 2 дополнительных потока - высокого приоритета и желательно реалтайм, и низкого приоритета. Звязываться с настоящей многозадачностью было лениво, поэтому реалтайм поток реализован как и в АПМ на таймере, а низкоприоритетный на простой кооперативной многозадачности во время исполнения разнообразных dalay()

    [2017-01-02 15:03:15] kozin писал(а): тоже стало все рассыпаться именно тогда когда он повесил обновление на таймер

    Но у меня-то при -O0 работает! Хотя явно выполняется дольше чем без оптимизации.

  • Аватар профиля kozin Алексей Козин в 7 г., 2 мес. назад

    возможно у вас есть полная вспомогательная табличка соответствия названий портов проца и условных номеров портов используемых для этого хала

    https://github.com/night-ghost/ardupilot/blob/master/libraries/AP_HAL_REVOMINI/wirish/boards/revomini_MP32V1F4/revomini_MP32V1F4.h

    #define BOARD_USART5_RX_PIN 26 // PD2            т.е.  PD2 = 26

     хотел попробовать свои силы в том чтобы затестить ваш хал на f4by, но уперся в сопоставление портов

     

  • Аватар профиля kozin Алексей Козин в 7 г., 2 мес. назад

    у меня кстати ряд варнингов показывает эклипс

    втч https://github.com/night-ghost/ardupilot/blob/master/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp#L811

    Description    Resource    Path    Location    Type
    No break at the end of case    AP_InertialSensor_Invensense.cpp    /ardupilot/libraries/AP_InertialSensor    line 811    Code Analysis Problem

     

  • Аватар профиля Night_Ghost Night_Ghost287 пунктов в 7 г., 2 мес. назад
    [2017-01-03 07:17:40] kozin писал(а): табличка соответствия названий портов проца и условных номеров портов

    это PIN_MAP, находится в https://github.com/night-ghost/ardupilot/blob/master/libraries/AP_HAL_REVOMINI/wirish/boards/revomini_MP32V1F4/revomini_MP32V1F4.cpp

    [2017-01-03 07:36:44] kozin писал(а): ряд варнингов показывает эклипс

    Он ввобще дурной и умудряется найти проблемы там где из нет.UPD но таки да, тут баг похоже

  • Аватар профиля kozin Алексей Козин в 7 г., 2 мес. назад

    [pinmap] спасибо! классно!

    если я не надоел еще тут своим "нудежом" то какие есть мысли по DRDY.

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

    в ситуации когда используется drdy - идеально поставить легковесную функцию в аппаратное прерывание, для регистрации фронта импульса. Если же проверять пин DRDY циклически из таймера, то чтобы гарантировано попасть в момент близкий к фронту импульса состояние пина нужно проверять с частотой на порядок выше чем частота сигнала, т.е. при частоте измерения мпу 1кгц нужно опрашивать пин как минимум на 10 кгц. Причем в случае если фронт импульса зарегистрирован то важно не запускать повторные измерения пока пин в активном сотоянии, следует дождаться нового фронта. При этом можно установить таймер на паузу чуть меньше чем цикл измерения мпу, а затем проверять пин с высокой частотой.

    если же пин готовности мпу проверять тупо с частотой измерений, т.е. 1кгц то проверка пина может придтись не на начало импульса а гдето к его концу и велика вероятность что чтение  регистров может совпасть с процессом их переустановки в результате измерения. зы. я не знаток мпу, чисто по аналогии с другими спи устройствами

     

     

     

     

  • Аватар профиля Night_Ghost Night_Ghost287 пунктов в 7 г., 2 мес. назад

    Я совершенно согласен, но... если начать менять саму логику работы Ардупилота то с мыслью попасть в мейнстрим можно попрощаться. Хотя вся работа с железом там настолько через жо...

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

    Все что проверяется в ХАЛе уже и так опрашивается с частотой 8кгц

  • Аватар профиля Night_Ghost Night_Ghost287 пунктов в 7 г., 2 мес. назад

    Вдогонку про Пинмап. Есть еще таблица таймеров в pwm_in.c и еще одна таблица таймеров в timer.c. По уму их тоже надо бы в описатель платы засунуть, но вроде бы в пределах семейства они остаются неизменными

  • Аватар профиля kozin Алексей Козин в 7 г., 2 мес. назад

    вроде как тут регистрируется

    https://github.com/night-ghost/ardupilot/blob/master/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp#L465

    _dev->register_periodic_callback(1000, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_Invensense::_poll_data, bool));

    1кгц

  • Аватар профиля Night_Ghost Night_Ghost287 пунктов в 7 г., 2 мес. назад
    [2017-01-03 09:10:11] kozin писал(а): вроде как тут регистрируется

    Это да, как я уже сказал я стараюсь по максимуму не трогать код ВНЕ ХАЛа. 

  • Аватар профиля Night_Ghost Night_Ghost287 пунктов в 7 г., 2 мес. назад

    Если уж заниматься оптимизацией то ВЕСЬ опрос ВСЕХ  датчиков должен делаться внутри ХАЛ, а основной поток должен брать готовые даные из очереди - как это сделано с УАРТами. Тогда можно было бы и предывания юзать с пользой а не как сейчас, тупо дожидаясь окончания, и DMA, и прочие вкусности камня. 

  • Аватар профиля Night_Ghost Night_Ghost287 пунктов в 7 г., 2 мес. назад
    [2017-01-03 09:10:11] kozin писал(а): 1кгц

    Кстати о :) получение данных с МПУ совмещено с их не самой легкой обработкой, так что иногда эта _poll_data выполняется аж 1286uS - так что килогерц это весьма оптимистично.

  • Аватар профиля kozin Алексей Козин в 7 г., 2 мес. назад

    вот еще интересное наблюдение

    метод

    bool AP_InertialSensor_Invensense::_data_ready()
    {
        if (_drdy_pin) {
            return _drdy_pin->read() != 0;
        }
        uint8_t status = _register_read(MPUREG_INT_STATUS);
        return (status & BIT_RAW_RDY_INT) != 0;
    }

    используется только в инициализации

    https://github.com/night-ghost/ardupilot/blob/master/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp#L880

    по идее он конечно же публичный и может проверяться снаружи, но ненашел

  • Аватар профиля kozin Алексей Козин в 7 г., 2 мес. назад

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

    https://github.com/cleanflight/cleanflight/blob/master/src/main/drivers/accgyro_mpu.c#L216

     

  • Аватар профиля Night_Ghost Night_Ghost287 пунктов в 7 г., 2 мес. назад
    [2017-01-03 10:34:49] kozin писал(а): используется только в инициализации

    совершенно верно. Цикл опроса выбран так что данные гарантированно уже есть, так что толку от этой ноги около 0. 

    [2017-01-03 11:01:07] kozin писал(а): используют ли аппаратные прерывания в клинфлайте.

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

← Форум группы   Все форумы К последней записи
Постов на странице:

Вы автоматически вступите в эту группу, когда ответите в теме.

Добавить ответ:

-
Рейтинг@Mail.ru