Skip to main content

SDK for control and programming Geoscan Pioneer Drones

Project description

Pioneer SDK 2

Общее описание

Pioneer SDK 2 - это Python SDK для управления дронами Pioneer (Pioneer Mini 2, Pizero и др.). Класс Pioneer является главным интерфейсом взаимодействия.

Поддерживаемые платформы

  • Windows: 10, 11
  • Linux: любые дистрибутивы c поддержкой Python 3.12
  • macOS: только на процессорах Apple Silicon (протестировано на macOS 26, macOS 26.1)

Примечание: macOS на процессорах Intel не поддерживается.

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

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

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

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

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

Важно:

  • Состояния корректно отслеживаются только в рамках одной программы
  • При запуске нескольких полетных программ часть состояний может быть не считана
  • Рекомендуется использовать wait_callback=True и safety_command=True (по умолчанию) для безопасной работы

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

pioneer = Pioneer()

Параметры:

  • serial (str): Подключаемый последовательный порт
  • tcp (str): TCP адрес и порт (по умолчанию "127.0.0.1:20556")
  • baudrate (int): Скорость передачи данных (по умолчанию 57600)
  • wait_callback (bool): Флаг включения блокирования методов на ожидание выполнения callback-функций (по умолчанию True)
  • safety_command (bool): Флаг включения проверки разрешенных команд в зависимости от состояния полета (по умолчанию True). При False проверка команд отключается.
  • logger (bool): Флаг включения логирования (по умолчанию True)

Примечание:

  • Возможно использование лишь одного из методов serial или tcp
  • Контроль последовательности команд работает только при wait_callback=True и safety_command=True

Основные методы управления

Управление полетом. Класс Pioneer

arm(timeout = 5, retries = 0)

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

Параметры:

  • timeout (int): Время ожидания (в секундах) для запуска моторов.
  • retries (int): Количество повторных попыток ARM при неудаче (0 = без повторов).

Тип результата: bool

Результат: True, если команда успешно выполнена, иначе False

Примечание (только при wait_callback=True и safety_command=True):

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

disarm()

Отключение моторов дрона

Тип результата: bool

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

takeoff()

Запускает процесс взлёта и ждёт его завершения Ожидает события TAKEOFF_COMPLETE при параметре wait_callback=True

Тип результата: bool

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

Примечание (только при wait_callback=True и safety_command=True):

  • Доступна только после успешного выполнения arm()
  • При вызове в состоянии ON_LAND команда игнорируется (возвращает False)
  • При вызове в состоянии IN_SKY выбрасывается RuntimeError (пропуск обязательного этапа)

land()

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

Тип результата: bool

Результат: True, если команда успешно выполнена, иначе False

go_to_local_point(x, y, z, yaw, time=0)

Перемещает дрон к локальной точке

Параметры:

  • x (int): Координата X в метрах
  • y (int): Координата Y в метрах
  • z (int): Координата Z в метрах
  • yaw (float): Угол рысканья в градусах
  • time (int): Желательное время достижения целевой точки. Если равен 0, дрон перемещается с текущей скоростью.

Примечание (только при wait_callback=True и safety_command=True):

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

go_to_local_point_body_fixed(x, y, z, yaw, time=0)

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

Параметры:

  • x (float): Смещение по оси X в метрах
  • y (float): Смещение по оси Y в метрах
  • z (float): Смещение по оси Z в метрах
  • yaw (float): Угол рысканья в градусах
  • time (int): Желательное время достижения целевой точки. Если равен 0, дрон перемещается с текущей скоростью.

Примечание (только при wait_callback=True и safety_command=True):

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

go_to_global_point(latitude, longitude, altitude, yaw=0)

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

Параметры:

  • latitude (float): Широта целевой точки в градусах
  • longitude (float): Долгота целевой точки в градусах
  • altitude (float): Высота над уровнем моря в метрах
  • yaw (int): Угол рысканья (азимут) в градусах (по умолчанию 0)

Тип результата: bool

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

Примечание (только при wait_callback=True и safety_command=True):

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

go_to_global_point_relative(latitude_offset, longitude_offset, altitude_offset, yaw)

Перемещает дрон к глобальной точке, заданной смещениями относительно текущего положения. Только для системы навигации GPS.

Параметры:

  • latitude_offset (float): Смещение по широте в градусах относительно текущей позиции
  • longitude_offset (float): Смещение по долготе в градусах относительно текущей позиции
  • altitude_offset (float): Смещение по высоте в метрах относительно текущей позиции
  • yaw (int): Угол рысканья (азимут) в градусах

Тип результата: bool

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

Примечание (только при wait_callback=True и safety_command=True):

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

set_manual_speed(vx, vy, vz, yaw_rate, interval=1.0)

Полёт с заданной скоростью относительно системы координат. Доступна только в состоянии IN_SKY (после взлёта).

Параметры:

  • vx (float): Скорость по оси X в м/с
  • vy (float): Скорость по оси Y в м/с
  • vz (float): Скорость по оси Z в м/с
  • yaw_rate (float): Скорость рысканья в рад/с
  • interval (float): Время в секундах, в течение которого команда управления скоростью считается активной (по умолчанию 1.0)

Примечание (только при wait_callback=True и safety_command=True):

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

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 (float): Время в секундах, в течение которого команда управления скоростью считается активной (по умолчанию 1.0)

Примечание (только при wait_callback=True и safety_command=True):

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

rtl()

Возвращение домой (Return To Launch).

Тип результата: bool

Результат: True, если успешно, иначе False.

Дополнительные функции

get_battery_status()

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

Тип результата: tuple[float, float] | None

Результат: Кортеж с напряжением и температурой батареи в Вольтах или None, если ошибка

set_logger(value=True)

Устанавливает флаг логирования

Параметры:

  • value (bool): Значение флага логирования (по умолчанию True)

connect()

Устанавливает соединение с устройством. Автоматически выполняется при инициализации объекта класса Pioneer.

close_connection()

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

reboot_board()

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

Тип результата: bool

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

point_deceleration()

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

Тип результата: bool

Результат: True, если замедление осуществлено, иначе False

point_reached()

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

Тип результата: bool

Результат: True, если точка достигнута, иначе False

Управление ориентацией

set_yaw(yaw)

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

Параметры:

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

Тип результата: bool

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

Примечание (только при wait_callback=True и safety_command=True):

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

get_orientation()

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

Тип результата: tuple[float, float, float] | None

Результат: Кортеж с ориентацией дрона по углу крена (roll), тангажа (pitch) и рыскания (yaw) или None, если ошибка

Получение данных с датчиков

get_accel()

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

Тип результата: tuple[float, float, float] | None

Результат: Ускорение по осям или None, если ошибка

get_gyro()

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

Тип результата: tuple[float, float, float] | None

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

get_mag()

Возвращает показания магнитометра по осям X, Y и Z. Только для GPS.

Тип результата: tuple[float, float, float] | None

Результат: Кортеж с угловой скоростью по осям X, Y и Z или None, если ошибка

get_altitude()

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

Тип результата: float | None

Результат: Высота в метрах или None, если ошибка

get_dist_sensor_data()

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

Тип результата: float | None

Результат: Дальность в метрах или None, если ошибка

get_motors_rpm()

Возвращает текущие обороты каждого из 4 двигателей дрона.

Тип результата: list[float | None]

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

get_ranger_data()

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

Тип результата: tuple[float, float, float, float, float] | tuple[None, None, None, None, None]

Результат: Кортеж из пяти значений (в метрах): (право, лево, вперед, назад, сверху/снизу). Если модуль не поддерживается или не установлен — кортеж из None.

Управление LED

led_control(led_id=255, r=0., g=0., b=0.)

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

Параметры:

  • led_id (int): Номер светодиода. Если 255, устанавливается для всех светодиодов.
  • r (float): Значение красного цвета от 0 до 1.
  • g (float): Значение зеленого цвета от 0 до 1.
  • b (float): Значение синего цвета от 0 до 1.

Тип результата: bool

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

Управление захватом

Доступен только для Мини 2.

grab_open(movement_time=0, velocity=100)

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

Параметры:

  • movement_time (float): Время движения в секундах. Если 0, открытие захвата происходит до упора (по умолчанию 0).
  • velocity (int): Скорость движения в процентах от 0 до 100 (по умолчанию 100).

Тип результата: bool

Результат: True, если успешно, иначе False

grab_close(movement_time=0, velocity=100)

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

Параметры:

  • movement_time (float): Время движения в секундах. Если 0, закрытие захвата происходит до упора (по умолчанию 0).
  • velocity (int): Скорость движения в процентах от 0 до 100 (по умолчанию 100).

Тип результата: bool

Результат: True, если успешно, иначе False

grab_stop()

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

Тип результата: bool

Результат: True, если успешно, иначе False

Управление магнитным захватом груза

Доступно только для Базового Пионера.

cargo_set(grab)

Устанавливает состояние магнитного захвата груза (вкл/выкл).

Параметры:

  • grab (bool): True — включить магнитный захват, False — выключить.

Тип результата: bool

Результат: True, если успешно, иначе False

cargo_grab()

Включает магнитный захват груза.

Тип результата: bool

Результат: True, если успешно, иначе False

cargo_release()

Выключает магнитный захват груза.

Тип результата: bool

Результат: True, если успешно, иначе False

Работа с параметрами

get_param(name, update=False)

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

Параметры:

  • name (str): Имя параметра
  • update (bool): Если True, принудительно обновит значение параметра из автопилота, иначе вернет кэшированное значение.

Тип результата: float | None

Результат: Значение параметра или None, если ошибка

set_param(name, value)

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

Параметры:

  • name (str): Имя параметра
  • value (float | int): Значение параметра

Тип результата: bool

Результат: True, если успешно, иначе False

Состояние полета

Класс FlyState, предоставляет константы для состояний полета дрона в цикле: ON_LAND → ARMED → IN_SKY → ON_LAND.

ON_LAND  # Коптер на земле, моторы выключены. Доступна команда: arm()
ARMED    # Коптер заармлен, моторы запущены. Доступна команда: takeoff()
IN_SKY   # Коптер в воздухе, выполняет полет. Доступны команды полета

get_fly_state()

Возвращает текущее состояние полета дрона

Тип результата: FlyState

Результат: Текущее состояние полета (ON_LAND, ARMED или IN_SKY)

Работа с системой навигации

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

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

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

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

get_nav_system(update=False)

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

Параметры:

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

Тип результата: NavSystem

Результат: Текущая система навигации (GPS, LPS или OPT).

get_nav_status_lps()

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

Тип результата: NavStatus | None

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.0; +180.0) или None, если ошибка

get_optical_data()

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

Тип результата: tuple[int, int, float] | None

Результат: данные оптического потока или None, если ошибка.

Результат: Статус системы навигации дрона или None, если ошибка

get_nav_status_gps()

Возвращает статус навигационной системы дрона (только для GPS)

Тип результата: NavStatus | None

Результат: Статус системы навигации дрона или None, если ошибка

get_global_position_gps()

Возвращает текущие глобальные координаты дрона по данным GPS (только для GPS)

Тип результата: tuple[float, float, float] | None

Результат: Кортеж (широта, долгота, высота) в градусах и метрах, либо None, если модуль навигации не установлен

get_global_velocity_gps()

Возвращает скорость дрона в системе координат GPS (только для GPS)

Тип результата: tuple[float, float, float] | None

Результат: Кортеж (северная скорость, восточная скорость, вертикальная скорость) в м/с или None, если модуль навигации не установлен

get_satellites_count()

Возвращает количество спутников GPS и ГЛОНАСС, видимых дрону (только для GPS)

Тип результата: tuple[int, int] | None

Результат: Кортеж (число GPS-спутников, число ГЛОНАСС-спутников), либо None, если модуль навигации не установлен

Временные функции

time()

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

Тип результата: float | None

Результат: Время в секундах с начала эпохи GPS или None, если ошибка.

uptime()

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

Тип результата: int | None

Результат: Время в секундах или None, если ошибка

flight_time()

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

Тип результата: float | None

Результат: Время полёта в секундах или None, если ошибка

Обработка событий

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

ALL                # Пустое событие
COPTER_LANDED      # Событие посадки дрона на землю.
LOW_VOLTAGE1       # Низкий заряд АКБ, но заряда хватит, чтобы вернуться домой.
LOW_VOLTAGE2       # Низкий заряд АКБ, начата экстренная посадка
POINT_REACHED      # Событие достижения целевой точки.
POINT_DECELERATION # Событие замедления дрона перед целевой точкой.
TAKEOFF_COMPLETE   # Событие завершения взлета.
ENGINES_STARTED    # Событие запуска моторов.
SHOCK              # Сильный удар, возможна потеря управления
LOW_CHARGE         # Критически низкий заряд АКБ

subscribe(callback, event)

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

Параметры:

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

unsubscribe(callback, event)

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

Параметры:

  • callback (callable): Функция обратного вызова
  • event (Event): Событие для отписки

Управление RC-каналами

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

  • Copter_man_rcMode0=6.0
  • Copter_man_rcMode1=3.0
  • Copter_man_rcMode2=3.0
  • Copter_flyWithoutRc=1.0
  • SensorMux_rc=2.0

Отправка RC каналов

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 (float): Режим управления
  • channel_6-8 (float): Дополнительные каналы

Тип результата: bool

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

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()

Возвращает значение RC-канала.

Тип результата: int | None

Результат: Значение RC-канала или None, если произошла ошибка.

set_rc_trigger(callback)

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

Параметры:

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

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

Классы Camera и ImageViewer динамически импортируются в SDK в зависимости от драйвера камеры, указанного в файле конфигурации платы (board_config.json).

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

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

Класс Camera

Класс для захвата видеокадров и предоставления их через очередь.

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

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

# Для драйвера rtsp
camera = Camera(camera_type, camera_ip="10.42.0.1:8554")

Параметры:

  • camera_type (CameraType): Тип камеры для захвата (например, CameraType.MAIN или CameraType.OPT).
  • camera_ip (str): IP-адрес и порт камеры (по умолчанию "10.42.0.1:8554"). Используется только для драйвера rtsp.

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

Методы

get_cv_frame(timeout=5.0)

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

Параметры:

  • timeout (float): Время ожидания в секундах.

Тип результата: numpy.ndarray

Результат: Кадр в формате BGR.

stop()

Останавливает GStreamer-пайплайн и завершает поток захвата.

Класс ImageViewer

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

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

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

viewer = ImageViewer()

Методы

imshow(name, frame, fps=30)

Отправляет кадр в соответствующий RTSP-поток.

Параметры:

  • name (str): Идентификатор потока.
  • frame (numpy.ndarray): Изображение в формате BGR для трансляции.
  • fps (int): кадров в секунду при передаче видео (по умолчанию 30)

close()

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

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

Класс ServoCamera

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

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

servo_camera = ServoCamera()

Примечание: Проверяет поддержку сервомотора камеры бортом при инициализации.

Методы

set_angle(angle, priority=ServoPriority.LOW)

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

Параметры:

  • angle (float): Угол в градусах, должен быть в диапазоне от -80 до 30.
  • priority (ServoPriority): Приоритет команды сервопривода (HIGH, MEDIUM, LOW).

Тип результата: bool

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

Исключения: ValueError: Если угол выходит за пределы допустимого диапазона (-80 до 30 градусов).

Project details


Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distributions

No source distribution files available for this release.See tutorial on generating distribution archives.

Built Distribution

If you're not sure about the file name format, learn more about wheel file names.

pioneer_sdk2-0.12.0-py3-none-any.whl (1.1 MB view details)

Uploaded Python 3

File details

Details for the file pioneer_sdk2-0.12.0-py3-none-any.whl.

File metadata

  • Download URL: pioneer_sdk2-0.12.0-py3-none-any.whl
  • Upload date:
  • Size: 1.1 MB
  • Tags: Python 3
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.2.0 CPython/3.10.20

File hashes

Hashes for pioneer_sdk2-0.12.0-py3-none-any.whl
Algorithm Hash digest
SHA256 72328e4bb4fd4728894c3353f599c9a5bf10b9110e2cf2a54a51dfefd2e81a72
MD5 7ea9c520831bdc49ff7144c9b6c34564
BLAKE2b-256 bf26c430e3bc319d84b2e5c9c53476b5726a44ef2a5ed660bb0814e74fb5f840

See more details on using hashes here.

Supported by

AWS Cloud computing and Security Sponsor Datadog Monitoring Depot Continuous Integration Fastly CDN Google Download Analytics Pingdom Monitoring Sentry Error logging StatusPage Status page