Pioneer-SDK2

Pioneer-SDK2 - это библиотека для управления квадрокоптерами «Пионер» и взаимодействия с микрокомпьютерами (Пионер Мини 2, RaZero, PiZero).

Примечание

Обратите внимание, что библиотека Pioneer-SDK2 встроена в образ Pioneer OS для «Radxa Zero 3W» и «Пионер Мини 2». Дополнительно устанавливать ничего не требуется. Для модуля Raspberry Pi Zero требуется установить Pioneer-SDK2!

Автоматический контроль последовательности команд

SDK автоматически отслеживает состояние полета дрона и контролирует допустимость выполнения команд в текущем состоянии. Цикл состояний: ON_LAND → ARMED → IN_SKY → ON_LAND.

Логика контроля (работает только при „wait_callback=True“ и „safety_command=True“):

  • При попытке выполнить команду из предыдущего состояния - команда игнорируется (возвращает False или ничего)

  • При попытке пропустить обязательный этап - выбрасывается исключение RuntimeError

  • Только команды для текущего состояния выполняются успешно

Отключение контроля: Контроль последовательности команд отключается, если хотя бы один из параметров `wait_callback` или `safety_command` установлен в `False`. При этом все команды выполняются без проверки состояния полета. Используйте отключение контроля только если вы полностью контролируете последовательность команд самостоятельно.

Работа с классом Pioneer

Экземпляр класса Pioneer

pioneer = Pioneer()
Описание класса:

Класс Pioneer является основным интерфейсом взаимодействия с библиотекой

Аргументы класса

Тип данных

Значение по умолчанию

Описание аргумента

serial

str

_

Подключаемый последовательный порт

tcp

str

127.0.0.1:20556

TCP адрес и порт

baudrate

int

57600

Скорость передачи данных

wait_callback

bool

True

Флаг включения блокирования методов на ожидание выполнения callback-функций

safety_command

bool

True

Флаг включения проверки разрешенных команд в зависимости от состояния полета

logger

bool

True

Флаг включения логирования

Подсказка

Обратите внимание, что используя модуль Raspberry Pi Zero, требуется обязательно указать tcp:

  • Если вы подключаетесь к модулю используйте:

tcp="10.42.0.1:20556"
  • Если модуль подключается к вам через точку доступа, то используйте tcp указанный в свойствах системы

Важно

Примечание

  • Возможно использование лишь одного из методов serial или tcp.

  • Контроль последовательности команд работает только при `wait_callback=True` и `safety_command=True`

Методы класса Pioneer

arm(timeout=5, retries=0)
Описание метода:

Запуск моторов квадрокоптера

Аргументы метода:
  • timeout - задержка перед запуском моторов

  • retries - количество повторных попыток запуска моторов

Тип данных:

bool

Возвращает:

True, если команда успешно выполнена, иначе False

Примечание:

Ожидает события ENGINES_STARTED при параметре Pioneer.wait_callback=True

disarm()
Описание метода:

Выключение моторов квадрокоптера

Тип данных:

bool

Возвращает:

True, если команда успешно выполнена, иначе False

takeoff()
Описание метода:

Запуск процесса взлёта

Тип данных:

bool

Возвращает:

True, если команда успешно выполнена, иначе False

Примечание:

Ожидает события TAKEOFF_COMPLETE при параметре wait_callback=True

land()
Описание метода:

Запуск процесса посадки

Тип данных:

bool

Возвращает:

True, если команда успешно выполнена, иначе False

Примечание:

Ожидает события COPTER_LANDED при параметре wait_callback=True

go_to_local_point(x, y, z, yaw, time=0)
Описание метода:

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

Аргументы метода:
  • x (float) - Координата X в метрах

  • y (float) - Координата Y в метрах

  • z (float) - Координата Z в метрах

  • yaw (float) - Угол рысканья в градусах

  • time (int) - Желательное время достижения целевой точки

go_to_local_point_body_fixed(x, y, z, yaw, time=0)
Описание метода:

Перемещает квадрокоптер в указанную координату относительно текущей позиции квадрокоптера. Работает только для LPS

Аргументы метода:
  • x (float) - Смещенение по оси X в метрах

  • y (float) - Смещенение по оси Y в метрах

  • z (float) - Смещенение по оси Z в метрах

  • yaw (float) - Угол рысканья в градусах

  • time (int) - Желательное время достижения целевой точки

go_to_global_point(latitude, longitude, altitude, yaw=0)
Описание метода:

Перемещает квадрокоптер в указанную координату относительно глобальной системы координат. Работает только для GPS

Аргументы метода:
  • latitude (float) - Широта целевой точки в градусах

  • longitude (float) - Долгота целевой точки в градусах

  • altitude (float) - Высота над уровнем моря в метрах

  • yaw (float) - Угол рысканья (азимут) в градусах

Тип данных:

bool

Возвращает:

True, если команда успешно отправлена, иначе False

go_to_global_point_relative(latitude_offset, longitude_offset, altitude_offset, yaw)
Описание метода:

Перемещает квадрокоптер в указанную координату относительно текущей позиции квадрокоптера. Работает только для GPS

Аргументы метода:
  • latitude_offset (float) - Смещение по широте в градусах относительно текущей позиции

  • longitude_offset (float) - Смещение по долготе в градусах относительно текущей позиции

  • altitude_offset (float) - Смещение по высоте в метрах относительно текущей позиции

  • yaw (float) - Угол рысканья (азимут) в градусах

Тип данных:

bool

Возвращает:

True, если команда успешно отправлена, иначе False

set_manual_speed(vx, vy, vz, yaw_rate, interval=1.0)
Описание метода:

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

Аргументы метода:
  • vx (float) - Скорость по оси X в м/с

  • vy (float) - Скорость по оси Y в м/с

  • vz (float) - Скорость по оси Z в м/с

  • yaw_rate (float) - Скорость рысканья в рад/с

  • interval=1.0 (float) - Время в секундах, в течение которого метод активен

set_manual_speed_body_fixed(vx, vy, vz, yaw_rate, interval=1.0)
Описание метода:

Перемещает квадрокоптер с указанной скоростью относительно текущей позиции квадрокоптера

Аргументы метода:
  • vx (float) - Скорость по оси X в м/с

  • vy (float) - Скорость по оси Y в м/с

  • vz (float) - Скорость по оси Z в м/с

  • yaw_rate (float) - Скорость рысканья в рад/с

  • interval=1.0 (float) - Время в секундах, в течение которого метод активен

set_yaw(yaw)
Описание метода:

Устанавливает угол рыскания

Аргументы метода:
  • yaw (float) - Угол рыскания в градусах

Тип данных:

bool

Возвращает:

True, если команда успешно отправлена, иначе False

Подсказка

только при wait_callback=True и safety_command=True:

  • При вызове в состоянии ON_LAND команда игнорируется (возвращает False)

  • При вызове в состоянии ARMED выбрасывается RuntimeError (пропуск обязательного этапа)

rtl()
Описание метода:

Возвращение в домашнюю координату (место взлета)

Тип данных:

bool

Возвращает:

True, если команда успешно отправлена, иначе False

led_control(led_id=255, r=0, g=0, b=0)
Описание метода:

Устанавливает цвет для указанного светодиода

Аргументы метода:
  • led_id (int) - Номер светодиода. (255 - все светодиоды)

  • r (float) - Яркость красного цвета от 0 до 1 (0% - 100%)

  • g (float) - Яркость зеленого цвета от 0 до 1 (0% - 100%)

  • b (float) - Яркость синего цвета от 0 до 1 (0% - 100%)

Тип данных:

bool

Возвращает:

True, если команда успешно отправлена, иначе False

set_logger(value=True)
Описание метода:

Разрешает (True) или запрещает (False) вывод информации о выполнении методов в консоль

Тип данных:

bool

connect()
Описание метода:

Устанавливает соединение с квадрокоптером

Примечание:

Автоматически выполняется при инициализации объекта класса «Pioneer»

close_connection()
Описание метода:

Закрывает соединение с квадрокоптером

Примечание:

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

reboot_board()
Описание метода:

Перезагружает плату автопилота, закрывает соединение и ждет 5 секунд, ожидается повторное подключение

Тип данных:

bool

Возвращает:

True, если перезагрузка разрешена и успешно выполнена, иначе False

Примечание:

Данный метод работает только с модулем Raspberry Pi Zero и Radxa Zero

get_battery_status()
Описание метода:

Возвращает текущий статус заряда батареи

Тип данных:

tuple[float, float] | None

Возвращает:

Напряжение и температуру аккумулятора | None, если ошибка

get_orientation()
Описание метода:

Возвращает ориентацию дрона по углам крена(roll), тангажа(pitch), рыскания(yaw)

Тип данных:

tuple[float, float, float] | None

Возвращает:

Углы крена (roll), тангажа (pitch) и рыскания (yaw) | None, если ошибка

get_accel()
Описание метода:

Возвращает ускорение квадрокоптера по осям X, Y, Z

Тип данных:

tuple[float, float, float] | None

Возвращает:

Ускорение по осям X, Y, Z | None, если ошибка

get_gyro()
Описание метода:

Возвращает угловую скорость по осям X, Y, Z в рад/с

Тип данных:

tuple[float, float, float] | None

Возвращает:

Угловая скорость по осям X, Y, Z в рад/с | None, если ошибка

get_mag()
Описание метода:

Возвращает показания магнитометра по осям X, Y, Z

Тип данных:

tuple[float, float, float] | None

Возвращает:

Угловая скорость по осям X, Y, Z | None, если ошибка

Примечание:

Только для GPS

get_altitude()
Описание метода:

Возвращает высоту с барометра

Тип данных:

float | None

Возвращает:

Высота над поверхностью в метрах | None, если ошибка

get_dist_sensor_data()
Описание метода:

Возвращает высоту с лазерного дальномера

Тип данных:

float | None

Возвращает:

Высота над поверхностью в метрах | None, если ошибка

get_motors_rpm()
Описание метода:

Возвращает обороты каждого из 4 моторов квадрокоптера

Тип данных:

list[float | None]

Возвращает:

Список из 4 значений оборотов (RPM) для каждого двигателя, или None для каждого двигателя, если произошла ошибка.

grab_open(movement_time=0, velocity=100)
Описание метода:

Открывает захват дрона

Аргументы метода:
  • movement_time (float) - Время открытия захвата (0 - открывает до упора)

  • velocity (int) - Скорость открытия (0% - 100%)

Тип данных:

bool

Возвращает:

True, если выполнено, иначе False

grab_close(movement_time=0, velocity=100)
Описание метода:

Закрывает захват дрона

Аргументы метода:
  • movement_time (float) - Время закрытия захвата (0 - открывает до упора)

  • velocity (int) - Скорость закрытия (0% - 100%)

Тип данных:

bool

Возвращает:

True, если выполнено, иначе False

grab_stop()
Описание метода:

Останавливает движение захвата

Тип данных:

bool

Возвращает:

True, если выполнено, иначе False

Возвращает данные с дальномеров модуля Ranger (Только для Мини 2)
Описание метода:

Возвращает данные с модуля Ranger

Тип данных:

tuple[float, float, float, float, float] | tuple[None, None, None, None, None]

Возвращает:

Кортеж из пяти значений, в метрах [право, лево, вперед, назад, сверху/снизу] | None, если ошибка

Примечание:

Только для квадрокоптера «Пионер Мини 2»

Класс NavSystem, предоставляет константы для видов навигации дрона.

GPS # Глобальная система навигации ГНСС.
LPS # Локальная система навигации Локус (УЗ), ИК.
OPT # Оптическая система навигации.

Класс NavStatus, предоставляющий константы состояния системы навигации дрона.

NO_DATA # Нет данных с модуля
CANNOT  # Невозможно оценить позицию
LOW     # Малое доверие к оценке
OK      # Успешная оценка
get_nav_system(update=False)
Описание метода:

Возвращает активную систему навигации квадрокоптера

Аргументы метода:
  • update (bool) - True, принудительно обновит значение параметра из автопилота, иначе вернет кэшированное значение

Возвращает:
  • NavSystem.GPS - Активна система GPS навигации

  • NavSystem.LPS - Активна система LPS навигации

  • NavSystem.OPT - Активна система OPT навигации

get_nav_status_lps()
Описание метода:

Возвращает статус LPS навигации квадрокоптера

Возвращает:
  • NavStatus.NO_DATA - Нет данных с модуля

  • NavStatus.CANNOT - Невозможно оценить позицию

  • NavStatus.LOW - Низкое доверие к оценке позиции

  • NavStatus.OK - Позиция определена

get_local_position_lps()
Описание метода:

Возвращает координаты по осям X, Y, Z в метрах

Тип данных:

tuple[float, float, float] | None

Возвращает:

Позицию по осям X, Y, Z в метрах | None, если ошибка

get_local_velocity_lps()
Описание метода:

Возвращает скорость по осям X, Y, Z в м/с

Тип данных:

tuple[float, float, float] | None

Возвращает:

Скорость по осям X, Y, Z в м/с | None, если ошибка

get_local_yaw_lps()
Описание метода:

Возвращает текущий угол рыскания

Тип данных:

float | None

Возвращает:

Угол рыскания в градусах (-180; +180) | None, если ошибка

get_optical_data()
Описание метода:

Возвращает данные оптического потока

Тип данных:

tuple[int, int, float] | None

Возвращает:

Данные оптического потока | None, если ошибка

get_nav_status_gps()
Описание метода:

Возвращает статус GPS навигации квадрокоптера

Возвращает:
  • NavStatus.NO_DATA - Нет данных с модуля

  • NavStatus.CANNOT - Невозможно оценить позицию

  • NavStatus.LOW - Низкое доверие к оценке позиции

  • NavStatus.OK - Позиция определена

get_global_position_gps()
Описание метода:

Возвращает координаты квадрокоптера по GPS

Тип данных:

tuple[int, int, float] | None

Возвращает:

Кортеж в градусах и метрах [широта, долгота, высота] | None, если ошибка

get_global_velocity_gps()
Описание метода:

Возвращает скорость дрона по GPS

Тип данных:

tuple[int, int, float] | None

Возвращает:

Кортеж, скорость в м/с [северная, восточная, вертикальная] | None, если ошибка

get_satellites_count()
Описание метода:

Возвращает количество обнаруженных спутников GPS и ГЛОНАСС

Тип данных:

tuple[int, int] | None

Возвращает:

Кортеж [GPS спутники, ГЛОНАСС спутники] | None, если ошибка

time()
Описание метода:

Возвращает время работы квадрокоптера в секундах с момента начала GPS-эпохи

Тип данных:

float | None

Возвращает:

Время в секундах с начала GPS-эпохи | None, если ошибка

uptime()
Описание метода:

Возвращает время в секундах, прошедшее с момента идентификации в системе навигации

Тип данных:

int | None

Возвращает:

Время в секундах | None, если ошибка

flight_time()
Описание метода:

Возвращает время с начала полёта квадрокоптера в секундах

Тип данных:

float | None

Возвращает:

Время полета в секундах | None, если ошибка

Для реализации не блокирующего фунционала управления можно самостоятельно подписываться на события и ожидать их получения от автопилота. Список событий описан в классе Event и содержит следующие поля:

События

Описание события

COPTER_LANDED

Посадка дрона на землю

LOW_VOLTAGE1

Низкий заряд АКБ, но заряда хватит, чтобы вернуться домой

LOW_VOLTAGE2

Низкий заряд АКБ, начата экстренная посадка

LOW_CHARGE

Критически низкий заряд АКБ

POINT_DECELERATION

Замедления дрона перед целевой координатой

POINT_REACHED

Достижение целевой координаты

TAKEOFF_COMPLETE

Взлет завершен

ENGINES_STARTED

Моторы запущены

SHOCK

Сильный удар

subscribe(callback, event)
Описание метода:

Подписка на события

Аргументы метода:
  • callback (callable) - Функция обратного вызова при получении события

  • event (Event) - Событие для подписки

Пример подписки на событие «Взлет»:
from pioneer_sdk2 import Pioneer, Event

def takeoff_callback(event):
    pass

pioneer = Pioneer()
pioneer.subscribe(takeoff_callback, Event.TAKEOFF_COMPLETE)
unsubscribe(callback, event)
Описание метода:

Отписка от события

Аргументы метода:
  • callback (callable) - Функция обратного вызова при получении события

  • event (Event) - Событие для отписки

point_deceleration()
Описание метода:

Проверяет, достиг ли квадрокоптер координаты близкой к целевой

Тип данных:

bool

Возвращает:

True, если квадрокоптер начал замедление, иначе False

point_reached()
Описание метода:

Проверяет, достиг ли квадрокоптер целевой координаты

Тип данных:

bool

Возвращает:

True, если координата достигнута, иначе False

Важно

Для управления RC каналами требуется выставить параметры АП:

  • Copter_man_rcMode0=6.0

  • Copter_man_rcMode1=3.0

  • Copter_man_rcMode2=3.0

  • Copter_flyWithoutRc=1.0

  • SensorMux_rc=2.0

send_rc_channels(channel_1=0, channel_2=0, channel_3=0, channel_4=0, channel_5=1, channel_6=0, channel_7=1, channel_8=0)
Описание метода:

Имитация значений RC каналов

Аргументы метода:
  • channel_1 (float) - Правый стик (влево -1, центр 0, вправо 1)

  • channel_2 (float) - Правый стик (вперед -1, центр 0, назад 1)

  • channel_3 (float) - Левый стик (вниз -1, центр 0, вверх 1)

  • channel_4 (float) - Левый стик (влево 1, центр 0, вправо -1)

  • channel_5-8 (float) - Дополнительные каналы (тумблеры)

Тип данных:

bool

Возвращает:

True, если команда успешно отправлена, иначе False

Примечание:

Требуется постоянная отправка RC каналов для поддержания связи.

rc_sdk1_to_sdk2(channel_1=0, channel_2=0, channel_3=0, channel_4=0, channel_5=2000)
Описание метода:

Конвертация команд из SDK1 в SDK2

Аргументы метода:
  • channel_1-4 (float) - Значения каналов SDK1

  • channel_5 (float) - Значение канала режима SDK1

Тип данных:

tuple[float, float, float, float, float]

Возвращает:

Кортеж из 5 значений для каналов управления

get_rc_channel()
Описание метода:

Возвращает значение 8 канала

Тип данных:

int | None

Возвращает:

Значение 8 канала | None, если ошибка

set_rc_trigger(callback)
Описание метода:

Устанавливает функцию обратного вызова для триггера RC-канала

Аргументы метода:
  • callback (callable) - Функция обратного вызова, будет вызвана при срабатывании триггера

set_param(name, value)
Описание метода:

Устанавливает значение выбранному параметру автопилота

Аргументы метода:
  • name (str) - Имя параметра

  • value (float | int) - Устанавливаемое значение

Тип данных:

bool

Возвращает:

True, если выполнено, иначе False

get_param(name, update=False)
Описание метода:

Возвращает значение выбранного параметра автопилота

Аргументы метода:
  • name (str) - Имя параметра

  • update (bool) - True, считает значение из автопилота, иначе вернет кэшированное значение (при первом подключении)

Тип данных:

float | None

Возвращает:

Значение параметра | None, если ошибка

Работа с камерой

Для работы с камерой используются классы Camera и ImageViewer, а также ServoCamera для квадрокоптера «Пионер Мини2». Классы Camera и ImageViewer динамически импортируются в SDK в зависимости от драйвера камеры, указанного в файле конфигурации платы (board_config.json).

Поддерживаемые драйверы камер:

  • gstreamer: Использует GStreamer для захвата видео из shared memory (/tmp/). Поддерживает несколько камер одновременно.

  • rtsp: Использует RTSP-поток для захвата видео. Требует указания IP-адреса камеры.

Класс Camera

Класс Camera используется для захвата видеокадров и предоставления их через очередь, данный класс можно использовать с «Пионер Мини 2», «Radxa Zero», «Raspberry Pi Zero».

Подсказка

Обратите внимание, что используя модуль Raspberry Pi Zero, требуется указать дополнительный аргумент camera_ip и порт 8554:

Инициализация:

camera = Camera(camera_type=CameraType.MAIN)
Аргументы класса:
  • camera_type (CameraType) - Тип камеры для захвата (например, CameraType.MAIN или CameraType.OPT).

  • camera_ip(str) - IP-адрес и порт камеры (по умолчанию «10.42.0.1:8554»). Используется только для драйвера rtsp.

Примечание:

Примечание: CameraType генерируется динамически на основе секции cameras файла конфигурации платы board_config.json (ключи, отличные от driver).

# Для драйвера gstreamer
camera = Camera(camera_type)

# Для драйвера rtsp
camera = Camera(camera_type, camera_ip="10.42.0.1:8554")
get_cv_frame(timeout=5.0)
Описание метода:

Возвращает следующий доступный кадр из очереди

Аргументы метода:
  • timeout (float) - Время ожидания кадра в секундах

Возвращает:

Кадр в формате BGR

stop()
Описание метода:

Завершает поток захвата кадров

Класс ImageViewer (только для Мини 2, Radxa Zero)

Класс для трансляции numpy-кадров по RTSP через GStreamer

viewer = ImageViewer()
Примечание:

Класс ImageViewer доступен только при использовании драйвера камеры gstreamer

imshow(name, frame, fps=30)
Описание метода:

Отправляет кадр в трансляцию

Аргументы метода:
  • name (str) - Название трансляции

  • frame (numpy.ndarray) - Изображение в формате BGR для трансляции

  • fps (int) - Кол-во кадров в секунду при передаче видео

Примечание

Метод imshow запускает транcляцию. Она будет доступна в бараузере по адресу:

  • Если подключаетесь к wifi сети модуля / дрона

    10.42.0.1:8889/name # 10.42.0.1 - ip дрона по умолчанию, 8889 - порт трансляции, name - название трансляции
    
  • Если модуль подключается к вашей точке доступа

    ip:8889/name #ip скопировать из раздела хот-спот на компьютере, 8889 - порт трансляции, name - название трансляции
    
close()
Описание метода:

Уничтожает все gstreamer пайплайны.

Класс ServoCamera (только для Мини 2)

Класс для управления сервоприводом камеры, позволяющий устанавливать угол поворота. Только для Мини 2.

servo_camera = ServoCamera()

:Примечание: Проверяет поддержку сервомотора камеры бортом при инициализации
set_angle(angle, priority=ServoPriority.LOW)
Описание метода:

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

Аргументы метода:
  • angle (float) - Угол в градусах, диапазон от -90 до 30 градусов

  • priority (ServoPriority) - Приоритет команды сервопривода (HIGH, MEDIUM, LOW)

Тип данных:

bool

Возвращает:

True, если команда успешно отправлена, иначе False

Except:

ValueError, если угол выходит за пределы допустимого диапазона (от -90 до 30 градусов)