Pio

class pion.pio.DroneBase(ip: str = '10.1.100.114', mavlink_port: int = 5656, name: str = 'baseclass', mass: float = 0.3, position: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 6] | None = None, attitude: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 6] | None = None, count_of_checking_points: int = 20, logger: bool = False, checking_components: bool = True, accuracy: float = 0.05, dt: float = 0.1, max_speed: float = 2.0, max_acceleration: float = 10)

Абстрактный класс с частичной реализацией методов, служит для сокращения кода в дочерних классах

__init__(ip: str = '10.1.100.114', mavlink_port: int = 5656, name: str = 'baseclass', mass: float = 0.3, position: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 6] | None = None, attitude: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 6] | None = None, count_of_checking_points: int = 20, logger: bool = False, checking_components: bool = True, accuracy: float = 0.05, dt: float = 0.1, max_speed: float = 2.0, max_acceleration: float = 10)

Абстрактный класс с частичной реализацией методов, служит для сокращения кода в дочерних классах

Параметры:
  • ip (str) – IP-адрес для подключения к дрону.

  • mavlink_port (int) – Порт для MAVLink соединения.

  • count_of_checking_points (int) – Количество последних точек, используемых для проверки достижения цели.

  • name (str) – Название экземпляра

  • mass (float) – Масса дрона

  • position (Array6) – Начальное состояние дрона вида [x, y, z, vx, vy, vz]

  • attitude (Optional[Array6]) – Начальное состояние дрона вида [roll, pitch, yaw, v_roll, v_pitch, v_yaw]

  • dt (float) – Период приема всех сообщений с дрона или шаг времени в симуляции в Spion

  • logger (bool) – Включить логирование

  • checking_components (bool) – Параметр для проверки номеров компонентов. Отключается для в сторонних симуляторах во избежание ошибок.

  • accuracy (float) – Максимальное отклонение от целевой позиции для функции goto_from_outside

  • max_speed (float) – Максимальная скорость дрона в режиме управления по скорости

arm() None

Включает двигатели

Результат:

None

property attitude: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 6] | Annotated[ndarray[tuple[Any, ...], dtype[Any]], 4]

Метод вернет ndarray (6,) с координатами roll, pitch, yaw, rollspeed, pitchspeed, yawspeed

Результат:

np.ndarray

attitude_write() None

Метод для записи траектории в numpy массив. Записывается только уникальная координата

Результат:

None

check_battery() None

Проверяет статус батареи

Результат:

None

disarm() None

Отключает двигатели

Результат:

None

goto_yaw(yaw: float | int = 0, accuracy: float | int = 0.087) None

Берет целевую координату по yaw и вычисляет необходимые скорости для достижения целевой позиции, посылая их в управление t_speed.

Для использования необходимо включить цикл v_while для посылки вектора скорости дрону. Максимальная скорость обрезается np.clip по полю self.max_speed.

Параметры:
  • yaw – координата по yaw (радианы)

  • accuracy – Погрешность целевой точки

Результат:

None

heartbeat() None

Метод проверки heartbeat дрона

Результат:

None

land() None

Посадка дрона

Результат:

None

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

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

Параметры:
  • led_id (int) – Идентификатор светодиода, который нужно управлять. Допустимые значения: 0, 1, 2, 3, 255. 255 — для управления всеми светодиодами одновременно.

  • r (int) – Значение интенсивности красного канала (от 0 до 255).

  • g (int) – Значение интенсивности зеленого канала (от 0 до 255).

  • b (int) – Значение интенсивности синего канала (от 0 до 255).

Исключение:

ValueError – Если переданы недопустимые значения для параметра led_id или для значений r, g, b.

Результат:

None

property position: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 6] | Annotated[ndarray[tuple[Any, ...], dtype[Any]], 4]

Метод вернет ndarray (6,) с координатами x, y, z, vx, vy, vz

Результат:

np.ndarray

position_controller(position_xyz: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 3] | Annotated[ndarray[tuple[Any, ...], dtype[Any]], 2], dt: float) None

Фнкция формирования управляющего сигнала в сторону position_xyz

Параметры:
  • position_xyz (Union[Array3, Array2]) – Целевая координата

  • dt (float) – шаг времени расчета

Результат:

None

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

None

print_information() None

Метод обновляет словарь с логами self.logs

Результат:

None

print_latest_logs(log_dict: dict, n: int = 5, name: str = 'Название') None

Метод обновляет результаты в таблице логов

Параметры:
  • log_dict (dict) – Словарь с логами заполнения таблицы

  • n (int) – Количество логов из словаря, которые попадут в таблицу

  • name (str) – Заголовок таблицы

Результат:

None

reboot_board() None

Метод для перезагрузки дрона

Результат:

None

save_data(file_name: str = 'data.npy', path: str = '') None

Метод для сохранения траектории в файл.

columns=[„x“, „y“, „z“, „vx“, „vy“, „yaw“, „pitch“, „roll“,“Vyaw“, „Vpitch“, „Vroll“, „vxc“, „vyc“, „vzc“, „v_yaw_c“, „t“]

Параметры:
  • file_name – название файла

  • path – путь сохранения

Результат:

None

send_rc_channels(channel_1: int = 1500, channel_2: int = 1500, channel_3: int = 1500, channel_4: int = 1500) None

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

set_v() None

Создает поток, который вызывает функцию v_while() для параллельной отправки вектора скорости

Результат:

None

sland(hight_of_disarm: float = 0.3) None

Умная посадка дрона, выключает двигатели автоматически, если высота меньше hight_of_disarm

Параметры:

hight_of_disarm (float) – высота выключения двигателей

Результат:

None

stakeoff(hight: float = 1.5) None

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

Параметры:

hight (float) – Высота взлета

Результат:

None

takeoff() None

Взлет дрона

Результат:

None

property xyz: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 3] | Annotated[ndarray[tuple[Any, ...], dtype[Any]], 2]

Метод вернет ndarray (6,) с координатами x, y, z, vx, vy, vz

Результат:

np.ndarray

property yaw: float

Геттер вернет yaw

Результат:

float