Данная статья включает в себя:
Видео демонстрация
Алгоритм, который мы использовали
Программирование Geoscan Pioneer max (небольшой туториал, будет интересен не всем)
Видео демонстрация
Конструкция из Система автоматической разгрузки и загрузки дрона (Часть 1 — конструкция) / Хабр (habr.com)
Для проверки работы в условиях приближенных к реальным, мы прикрепили наши посадочные места к имитации окна для определения необходимого расстояния от поверхности, к которой закреплено посадочное место, при использование автопилота (ветер не кто не отменял, дрон должен иметь возможность для экстренного манёвра). Ниже представлено видео после множественных тестовых полётов, которые помогли нам отладить систему и доработать конструкцию посадочного места (задержки перед каждой командой по 16 секунд (для того, чтобы контролировать весь полёт), поэтому мы ускорили видео):
Результат тестовых полётов:
Автопилоту сложно контролировать себя при залёте на горизонтальную площадку (решение-сократить площадь поверхности)
Вынести платформу ещё на 15 сантиметров от стены (выравниваясь, очень близко подлетает к вертикальной поверхности, и малейший ветерок прижмёт его к стене/окну)
Алгоритм, который мы использовали
Так как нам требовалось доработать конструкцию в условиях будущего, мы решили разработать алгоритм для автоматического полёта и провести тестирование нашей конструкции для "тупой машины". К счастью нам не понадобилось писать с нуля автопилот, так как у нашего дрона Geoscan Pioneer max, он есть встроенный, но не смотря на это нам всё равно понадобилось разработать алгоритм построения траектории движения, по двум вводимым точкам посадки (третья - стартовая точка).
Алгоритм (упрощённо):
Программирование Geoscan Pioneer max подключение сервопривода
Для начала мы подключили сервопривод, для этого нам понадобится Rapberry (так как встроенная система не умеет общаться с сервоприводом), подключаем Raspberry по инструкции в интернете и теперь встаёт вопрос куда подключать серво и что делать. Некоторые пины используются по умолчанию (но информацию об этом можно не найти на сайте геоскана) использование таких пинов может повредить сервопривод, поэтому мы рекомендуем использовать, например, пин GPIO25. Ну и конечно Ground и Power.
Ниже представлены программы для работы сервопривода, так как вряд ли вы будете использовать только сервопривод в одностороннем порядке, то в предложенных программах уже реализована двухсторонняя связь, НО ограничение на передачу 31 символ, всё составлялось на основе документации (Программирование на Lua — Документация Pioneer December update 2022 (geoscan.aero)), НО информация имеет особенности применения.
-----------------Lua код, загружается на дрон через Pioneer station-----------
local uart = Uart.new(4, 57600) -- объявляем uart для общения с pyhon кодом
local servo_stat = 'o' -- статус сервопривода(например 'o'(открыто),'c'(закрыто))
local rc = Sensors.rc -- подключаем пульт
local inp = '' -- переменная для хранения информации для отправки на Python
local rec = '' -- переменная для хранения ответа(для будущего применения)
local function rotate_servo_open() -- функция открытия сервопривода
servo_stat='o'
end
local function rotate_servo_close() -- функция закрытия сервопривода
servo_stat='c'
end
local function main() -- цикл
rc_chans = table.pack(rc()) -- получаем иинформацию с пульта
if rc_chans[8] < -0.8 then --открытие (канал посмотри на пульте)
rotate_servo_open()
elseif rc_chans[8] > 0.8 then --закрытие (канал посмотри на пульте)
rotate_servo_close()
end
inp = servo_stat..'\n' -- пусть разделитель '\n'
uart:write(inp, #inp) -- отправляем на Python
rec = uart:read(uart:bytesToRead()) -- принимаем данные с Python
end
t = Timer.new(0.08, main) --устанавливаем частоту цикла
---!ВРЕМЯ СИНХРОНИЗАЦИИ ДОЛЖНО БЫТЬ ОДИНАКОВО НА LUA и PYTHON!
t:start() -- начинаем цикл
----------!!!КОВЫЧКИ ОДИНАРНЫЕ ОБЯЗАТЕЛЬНО, ИНАЧЕ РАБОТАТЬ НЕ БУДЕТ !!!---------------
##########################Python код, загружается на Raspberry########################
import serial # библиотека для общения
from time import sleep # библиотека для синхронизации
import RPi.GPIO as GPIO # библиотека для общения
ser = serial.Serial("/dev/ttyS0", 57600, timeout=5) # открываем порт, бездумно не меняй
GPIO.setmode(GPIO.BCM) # объявляем для общения с сервоприводом
GPIO.setup(25, GPIO.OUT) # объявляем для общения с сервоприводом
sg = GPIO.PWM(25, 50) # объявляем сервопривод
sg.start(8.06) # объявляем задаём начальный угол
servo_opened = True # по умолчанию замок открыт
def uart_read(): # функция чтения с Lua
data = ser.readline().decode().replace('\n', "") # читаем, разделяем, убираем мусор
if ser.in_waiting > 20: # чтобы не зависало, бездумно не меняй
ser.reset_input_buffer() # чтобы не зависало, бездумно не меняй
print('Read data: ')
print(data)
return data
def uart_write(answer): # функция ответа для Lua
ser.write(answer.encode()) # кодируем, пишем
print('UART writed')
def servo_control(event): # функция управления сервоприводом
global servo_opened # подключаем глобальные переменные
global sg # подключаем глобальные переменные
if event == "c" and servo_opened: # закрываем серво если получили 'c'
sg.ChangeDutyCycle(2.5)
servo_opened = False
print('closed')
elif event == "o" and not (servo_opened): # открываем серво если получили 'o'
sg.ChangeDutyCycle(8.06)
servo_opened = True
print('opened')
def auto_p_control(data):
servo_event = data[0]
servo_control(servo_event) # вызов функции для поворота сервопривода
print("ANS : " + str(ans))
uart_write(ans) # отправка данных на Lua
sleep(0.08) # синхронизация
while True: # бесконечный цикл
uart_data = uart_read() # вызываем функцию чтения
if uart_data != ['']: #если прочитанные данные не пустые
auto_p_control(uart_data) # вызываем функцию ответа
Предыдущие публикации:
Система автоматической разгрузки и загрузки дрона (Часть 1 — конструкция) / Хабр (habr.com)
Планируется к опубликованию:
Система автоматической разгрузки и загрузки дрона (Часть 3 - замок)