Выжимаем из Omnibus v3 PRO все
Каждый выжимает по-своему, я как любитель полетов на самолетах, с коптерами же предпочитаю долбаться ради изучения чего-то нового и необычного. В итоге за пару вечеров собрал вот такое
Все как обычно, рама Х, 4 мотора, ну полетник, ESC… Снизу хрень какая-то.
Так вот, многие знают о переводе ArduPilot на ChbiOS, благодаря чему все плюшки автопилота стали доступны на недорогих F4/F7 полетных контроллерах. Кто не знает, может детально ознакомиться тут. Там буквально первое сообщение темы раскрывает всю суть, принципы прошивки и использования. У меня речь немного о другом. Захотелось в мелкую раму (до 150мм) уместить что-то особенное (заядлые рейсеры скажут - барахло ненужное, и будут со своей колокольни правы) и интересное на данный момент для меня. А именно:
- Как ведет себя Omnibus под ArduCopter (ArduPlane на этом ПК я испытал еще летом - просто замечательно)
- Obstacle Avoidance (Избежание столкновений)
- Optical Flow (Для навигации в GPS denied условиях)
- Поковыряться с кодом ArduPilot
Комплектующие:
- Рама Hskrc-3-140
- Моторы 1105-6000KV
- ESC 20A 4in1 s2-4S BLHeli-S
- ПК OMNIBUS STM32F4-F4-Pro-V3-OSD
- Батарея Gaoneng-650-11-1-80C-160C-3-s-XT30
- Пропы Gemfan-3025
- ToF датчики VL53L1
- OpticalFlow я использовал Bitcrase FlowDeck (SPI) можно брать с UART подключением от Cheerson CX-OF
- Магнитометр HMC5883
Железо
Соединено как показано на схеме вверху. Как видно, на шине i2c находится компас и ToF сенсор VL53L0X который присутствует в модуле FlowDeck и смотрит вниз. В новой версии этого модуля применяется улучшенный вариант этого сенсора VL53L1X, который измеряет расстояния до 4х метров.
OpticalFlow PMW3901MB подключен по шине SPI.
Разработанный мною модуль PROX_ToF содержит до 9-ти датчиков расстояния VL53L1X, имеет интерфейс подключения модуля компаса и представляет собой ту самую коробочку прикрепленную снизу к коптеру. На фото модуль PROX_ToF еще с временным компасом
Вся информация по PROX_ToF - прошивки, схема, печатка выложена тут. По большому счету модуль опрашивает датчики расстояния и генерирует MAVLINK DISTANCE MESSAGE (в зависимости от ориентации каждого из датчиков), которые передаются по UART в ПК.
Программное обеспечение
Для того чтобы использовать нестандартное оборудования (OF), понятное дело нужно изменить настройки под ПК и перекомплировать прошивку. После установки Toolchain и последующего git clone прошивки с github.com/ArduPilot/ardupilot единственный файл который нужно было изменить \libraries\AP_HAL_ChibiOS\hwdef\omnibusf4pro\hwdef.dat:
- Находим дефайны CS пинов (строка #67) и добавляем строку
PD2 FLOW_CS CS
b) Находим таблицу устройств SPI и комментируем строку определяющую SPI для OSD (SPI3 DEVID4). Да OSD не пригодится 😃. Так что вместо OSD добавляем устройство optical flow:
SPIDEV pixartflow SPI3 DEVID4 FLOW_CS MODE3 2MHZ 2MHZ
env DEFINES HAL_HAVE_PIXARTFLOW_SPI - Нужно закомментировать и дейфайны относящиеся к OSD (строка #135)
#define OSD_ENABLED ENABLED
#define HAL_OSD_TYPE_DEFAULT 1
После этих изменений конфигурируем и делаем билд для copter. Прошивем Omnibus
Настройка полетника
Проверяем в руках правильно ли коптер реагирует на возмущения. Понятное дело, будет перерегулирование, так как настройки по-умолчнию подходят для 400-500мм коптеров, а для мелочи параметры сильно завышены. Привожу скрин Extended Tuning. Тут внимательно, на этом экране не все параметры удастся занизить до таких величин, поэтому для изменения параметров нужно пользоваться Full Parameters List / Tree. Обратите внимание, что необходимо занизить почти в два раза и Throttle Accel (Accel to motor)
Эти параметры Ardupilot нужно поменять через MissionPlanner после того как убедились, что в Acro и Stabilize коптер ведет себя идеально:
EK2_ALT_SOURCE = 1 #Используем датчик расстояния
EK2_GPS_TYPE = 3 #Используем OF
FLOW_ENABLE = 1
RNGFND_TYPE = 16
RNGFND_MAX_CM = 140
AVOID_ENABLE = 3
PRX_TYPE = 2
AVOID_BEHAVE = 1
AVOID_DIST_MAX = 3
Проверяем что видят датчики: нажимаем ctrl+F в MissionPlanner и выбираем Proximity. Должен появиться “радар” с расстояниями
После этого можно испытать работу Obstacle Avoidance в действии. Работа модуля зависит от полетного режима: в AltHold коптер шарахается от препятствий в том числе и от подвижных, но у пилота есть возможность положить … на мнение Obsticle Avoidance, то есть попросту додавить стиком в сторону препятствия и порубить его винтами. В режиме Loiter (так же и в Guided) коптер учитывает скорость своего движения при определении расстояния до препятствия и соответственно не дает пилоту влететь в него. То есть можно сколько угодно давить стик в сторону препятствия коптер игнорирует эти команды. Однако, если у коптера х-у скорость равна 0, то на подвижное препятствие он не реагирует 😦
Планы
- Поправить параметры, код модуля Obstacle Avoidance ибо коптер наотрез отказывается пролетать в дверные проемы
- Проверить возможность получения карты помещения в оффлайне/онлайне на основе датчиков расстояния и вычисления местоположения по OpticalFlow
- Добавить Linux miniPC на котором будет крутиться уже привычный mavproxy с dronekit и таким образом коптер станет полностью автономным.
Пока все, вроде должно быть продолжение