sPion¶
- class pion.spion.Spion(ip: str = '10.1.100.114', mavlink_port: int = 5656, connection_method: str = 'udpout', position: ndarray[tuple[Any, ...], dtype[float64]] = array([0., 0., 0., 0., 0., 0.]), attitude: ndarray[tuple[Any, ...], dtype[float64]] = array([0., 0., 0., 0., 0., 0.]), combine_system: int = 0, count_of_checking_points: int = 2, name: str = 'simulator', mass: float = 0.3, dt: float = 0.1, logger: bool = False, checking_components: bool = True, accuracy: float = 2e-05, max_speed: float = 2.0, start_message_handler_from_init: bool = True)¶
Класс симулятор, повторяющий действия Pion в симуляции математической модели точки
- __init__(ip: str = '10.1.100.114', mavlink_port: int = 5656, connection_method: str = 'udpout', position: ndarray[tuple[Any, ...], dtype[float64]] = array([0., 0., 0., 0., 0., 0.]), attitude: ndarray[tuple[Any, ...], dtype[float64]] = array([0., 0., 0., 0., 0., 0.]), combine_system: int = 0, count_of_checking_points: int = 2, name: str = 'simulator', mass: float = 0.3, dt: float = 0.1, logger: bool = False, checking_components: bool = True, accuracy: float = 2e-05, max_speed: float = 2.0, start_message_handler_from_init: bool = True) None ¶
Конструктор дочернего класса, наследующегося от Pio и Simulator
- Параметры:
ip (str) – IP-адрес для подключения к дрону
mavlink_port (int) – Порт для MAVLink соединения
connection_method (str) – Метод соединения, например, „udpout“ для MAVLink.
position (Union[Array6, Array4, None]) – Начальное состояние дрона вида [x, y, z, vx, vy, vz] или [x, y, vx, vy]
attitude (Union[Array6, None]) – Начальное состояние дрона вида [roll, pitch, yaw, v_roll, v_pitch, v_yaw]
combine_system (int) – Системный код для комбинированной системы управления: 1, 2, 3
count_of_checking_points (int) – Количество последних точек, используемых для проверки достижения цели.
name (str) – Название экземпляра
mass (float) – Масса дрона
dt (float) – Период приема всех сообщений с дрона
logger (bool) – Включить логирование
checking_components (bool) – Параметр для проверки номеров компонентов. Отключается для в сторонних симуляторах во избежание ошибок
accuracy (float) – Максимальное отклонение от целевой позиции для функции goto_from_outside
max_speed (float) – Максимальная скорость дрона в режиме управления по скорости
start_message_handler_from_init (bool) – Старт message handler при создании объекта
- property attitude: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 6]¶
Метод вернет ndarray (6,) с координатами roll, pitch, yaw, rollspeed, pitchspeed, yawspeed
- Результат:
np.ndarray
- borders() None ¶
Метод накладывает границы симуляции для дрона
- Результат:
None
- goto(x: float, y: float, z: float, yaw: float, accuracy: float = 0.05) None ¶
Метод берет целевую координату и вычисляет необходимые скорости для достижения целевой позиции, посылая их в управление t_speed.
Максимальная скорость обрезается np.clip по полю self.max_speed
- Параметры:
x – координата по x
y – координата по y
z – координата по z
yaw – координата по yaw
accuracy – Погрешность целевой точки
- Результат:
None
- goto_body(body_target: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 3] | Annotated[ndarray[tuple[Any, ...], dtype[Any]], 4]) None ¶
Перемещает дрон в точку, заданную относительно системы координат, закрепленной за дроном.
Параметр body_target задаётся относительно нуля дрона в его собственной системе координат. Если вектор имеет длину 3, считается, что задаётся смещение [dx, dy, dz] (без изменения yaw), а если длина 4 – последний элемент добавляется к текущему yaw. После преобразования целевая точка вычисляется в инерциальных координатах и вызывается стандартный goto.
- Параметры:
body_target (Union[Array3, Array4]) – вектор смещения относительно тела дрона (например, [dx, dy, dz] или [dx, dy, dz, dyaw])
- Результат:
None
- goto_from_outside(x: float, y: float, z: float, yaw: float, accuracy: float = 0.05, wait: bool = True) None ¶
Запускает симуляцию движения дрона к заданной точке.
- Параметры:
x (float) – Целевая координата x
y (float) – Целевая координата y
z (float) – Целевая координата z
yaw (float) – Целевой угол рысканья
accuracy (float) – Точность достижения цели
wait (bool) – Ожидать завершения движения
- Результат:
None
- land() None ¶
Метод посадки дрона
- Результат:
None
- Тип результата:
None
- property position: ndarray[tuple[Any, ...], dtype[float64]]¶
Возвращает объединённый вектор: [x, y, z, vx, vy, vz]
- position_controller(position_xyz: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 4]) None ¶
Метод высчитывает необходимую скорость для достижения таргетной позицыы position_xyz_yaw
- Параметры:
position_xyz (Array4) – Таргетная позиция дрона
- Результат:
None
- Тип результата:
None
- send_rc_channels(channel_1: int = 1500, channel_2: int = 1500, channel_3: int = 1500, channel_4: int = 1500) None ¶
Управление по rc-каналам
- send_speed(vx: float, vy: float, vz: float, yaw_rate: float) None ¶
Метод задает вектор скорости дрону. Отсылать необходимо в цикле.
- Параметры:
vx (float) – скорость по оси x (м/с)
vy (float) – скорость по оси y (м/с)
vz (float) – скорость по оси z (м/с)
yaw_rate (float) – скорость поворота по оси z (рад/с)
- Результат:
None
- set_body_velocity(body_vel: Annotated[ndarray[tuple[Any, ...], dtype[Any]], 4]) None ¶
Устанавливает скорость дрона, заданную в системе координат, закрепленной за дроном.
Параметр body_vel задаёт скорость относительно тела дрона. Эта скорость преобразуется в инерциальную систему, с учётом текущего yaw дрона, после чего вызывается метод set_force.
- Параметры:
body_vel (NDArray[np.float64]) – скорость в системе координат дрона (например, [vx_body, vy_body, vz_body, v_yaw])
- Результат:
None
- property speed: ndarray[tuple[Any, ...], dtype[float64]]¶
Возвращает скорость как [vx, vy, vz] из state.
- start_message_handler() None ¶
Запуск потока _message_handler
- Результат:
None
- Тип результата:
None
- stop() None ¶
Останавливает все потоки, завершает симуляцию
- Результат:
None
- stop_message_handler() None ¶
Остановка потока _message_handler
- Результат:
None
- Тип результата:
None
- takeoff() None ¶
Метод взлета дрона
- Результат:
None
- Тип результата:
None
- velocity_controller() None ¶
Метод высчитывает необходимую силу для внутренней модели self.simulation_objects для достижения таргетной скорости из t_speed.
- Результат:
None
- Тип результата:
None