Первый автономный полет

Данное руководство описывает полный цикл действий: от входа в систему до запуска БВС. Мы напишем скрипт, который заставит БВС взлететь, пролететь в заданную точку и приземлиться.

Программирование происходит на языке Python, обязательно указывайте соответствующее расширение файлов “.py”.

Шаг 1. Вход в среду разработки (Butterfly)

  • Включить аппаратуру управления
  • Установите БВС на точку взлета
  • Подключите АКБ к БВС
  • Дождитесь полного включения БВС

БВС полностью включен, если Wi-Fi сеть появилась для подключения

  • На аппаратуре управления переведите стики в центральное положение переключатель SB в положение Position
  • Отойдите от БВС

Шаг 2. Создание файла программы

  • Выберите папку, где будет храниться скрипт (обычно /home/pi/catkin_ws/src/clover/clover/examples или корень /home/pi)
  • Для создания файла используйте команду nano
  • Назовите файл, например, fly_mission.py Пример строки для создания файла:

    nano fly_mission.py
    

Шаг 3. Подготовка основного кода (Инициализация)

В открывшийся файл вставьте базовый блок кода для подключения библиотек и сервисов. Это "фундамент", необходимый для управления БВС.

1. Импорты

  import rospy
  import math
  from clover import srv
  from std_srvs.srv import Trigger

2. Инициализация

  rospy.init_node('flight')

### 3. Объявление сервисов управления

  ```bash
  navigate = rospy.ServiceProxy('navigate', srv.Navigate)
  get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
  land = rospy.ServiceProxy('land', Trigger)

4. Объявление вспомогательной функции, которая вызывает сервис 'navigate' и ждёт, пока БВС приблизится к цели

  def navigate_wait(x=0, y=0, z=0, yaw=float('nan'), speed=0.5, frame_id="aruco_map", auto_arm=False, tolerance=0.2):
  navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm)

      # Ждем, пока БВС долетит до цели
      while not rospy.is_shutdown():
          # Получаем текущую позицию относительно целевой точки
          telem = get_telemetry(frame_id='navigate_target')
          if math.sqrt(telem.x ** 2 + telem.y ** 2 + telem.z ** 2) < tolerance:
              break
  rospy.sleep(0.2)

Шаг 4. Программирование взлета

Для взлета используется функция navigate_wait, эта функция ожидает, пока БВС долетит до целевой точки.

Добавьте эту строку ниже:

navigate_wait(z=1.5, speed=0.5, frame_id='body', auto_arm=True)
  • Взлет на высоту 1.5 метра по координатной оси z;
  • frame_id='body': означает, что БВС взлетит вертикально относительно своего корпуса (оттуда, где он стоит);
  • auto_arm=True: эта команда принудительно включает моторы (арминг).

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

Шаг 5. Добавление задержки

Если во время выполнения полетной миссии дрону необходимо зависнуть над точкой, используйте функцию с указанием времени ожидания в секундах:

rospy.sleep(3)

Это означает ожидание в 3 секунды

Шаг 6. Полет в точку по маркерам

Теперь отправим БВС в конкретную точку над полем с ArUco-маркерами. Добавьте в код:

navigate_wait(x=1, y=1, z=1.5, speed=1, frame_id='aruco_map')
  • Полет в точку 1 метр по координатной оси x , 1 метр по координатной оси y, высота 1.5.
  • Снова ждем, пока БВС долетит
  • frame_id='aruco_map': система координат теперь привязана к карте маркеров на полу.
  • Координаты: Убедитесь, что координаты (x=1, y=1) находятся в пределах вашего полетного поля (например, если поле 4x4 метра, не ставьте значения больше 4).
  • Таймер: Время rospy.sleep(3) рассчитывается исходя из расстояния и скорости.

Шаг 7. Посадка

Завершаем программу командой посадки

land()

БВС совершит посадку и выключит моторы

Итоговый код программы

Ваш файл fly_mission.py должен выглядеть так:

import rospy
from clover import srv
from std_srvs.srv import Trigger

rospy.init_node('flight')

navigate = rospy.ServiceProxy('navigate', srv.Navigate)
get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
land = rospy.ServiceProxy('land', Trigger)
def navigate_wait(x=0, y=0, z=0, yaw=float('nan'), speed=0.5, frame_id='', auto_arm=False, tolerance=0.2):
navigate(x=x, y=y, z=z, yaw=yaw, speed=speed, frame_id=frame_id, auto_arm=auto_arm)

    while not rospy.is_shutdown():
        telem = get_telemetry(frame_id='navigate_target')
        if math.sqrt(telem.x ** 2 + telem.y ** 2 + telem.z ** 2) < tolerance:
            break
rospy.sleep(0.2)


# 1. Взлет
navigate_wait(x=0, y=0, z=1.5, speed=0.5, frame_id='body', auto_arm=True)
rospy.sleep(3)

# 2. Полет в точку (1, 1)
navigate_wait(x=1, y=1, z=1.5, speed=1, frame_id='aruco_map')
rospy.sleep(3)

# 3. Посадка
land()

Шаг 8. Сохранение

  • Нажмите Ctrl+X, чтобы сохранить файл
  • Система спросит хотите ли вы сохранить. Нажмите Y для сохранения
  • Нажмите Enter

Шаг 9. Запуск

rosrun clover selfcheck.py
  • При корректной работе систем запустите программу командой:
python3 fly_mission.py

Если все шаги сделаны верно, то БВС автономно выполнит взлет, полет в точку и посадку

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

Перехват управления:

  • Держите левый стик (Throttle) в центральном положении;
  • Смените положения переключателя SB с положения Position на положение Altitude;
  • Для посадки плавно опустите левый стик (Throttle) вниз до полной посадки БВС;
  • Нажмите и отпустите кнопку SA (Disarm);

Кнопка должна выйти из заблокированного положения

  • В целях безопасности нажмите и отпустите кнопку SD (Kill Switch);

Кнопка должна заблокироваться в нажатом положении

  • Отключите АКБ от БВС
  • Выключите аппаратуру управления.

results matching ""

    No results matching ""