Рухомі засоби Gazebo
Цей розділ перераховує/показує рухомі засоби, що підтримуються PX4 симуляцією Gazebo, та команди make
необхідні для того щоб їх запустити (команди запускаються з термінала в директорії PX4-Autopilot).
Моделі включені у PX4 як підмодуль який отримується з Репозиторію моделей Gazebo.
Supported vehicle types include: mutirotor, VTOL, Plane, Rover.
WARNING
Дивіться Рухомі засоби Gazebo Classic для засобів, що працюють зі старішою Симуляцією Gazebo "Classic". Зверніть увагу, що моделі засобів не взаємозамінні між двома версіями симулятору: засоби на цій сторінці будуть працювати тільки з (новим) Gazebo.
Мультикоптер
Квадрокоптер X500
sh
make px4_sitl gz_x500
Квадрокоптер X500 з візуальною одометрією
sh
make px4_sitl gz_x500_vision
X500 Quadrotor with Depth Camera (Front-facing)
This model has a forward-facting depth camera attached, modelled on the OAK-D.
sh
make px4_sitl gz_x500_depth
Квадрокоптер X500 з монокулярною камерою
This model has a simple monocular camera sensor attached (there is no physical camera visualization on the model itself).
sh
make px4_sitl gz_x500_mono_cam
INFO
Ця камера поки що не може використовуватись для трансляції відео або захоплення зображень у QGroundControl. Використовуйте PX4-Autopilot#22563 для відстеження додаткової роботи, необхідної для повної реалізації цих випадків використання.
X500 Quadrotor with Monocular Camera (Down-facing)
This model has a simple monocular camera sensor attached facing down (there is no physical camera visualization on the model itself).
This can be used with the Aruco world to test precision landing.
sh
make px4_sitl gz_x500_mono_cam_down
X500 Quadrotor with 1D LIDAR (Down-facing)
This model have a LIDAR attached to the bottom, modelled on the Lightware LW20/C.
It has a range between 0.1 and 100m.
The model can be used for testing rangefinder use cases like landing or terrain following.
sh
make px4_sitl gz_x500_lidar_front
X500 Quadrotor with 1D LIDAR (Front-facing)
This model have a LIDAR attached to the front, modelled on the Lightware LW20/C.
It has a range between 0.2 and 100m.
The model can be used for testing Collision Prevention.
sh
make px4_sitl gz_x500_lidar_front
X500 Quadrotor with 2D LIDAR
This model have a 2D LIDAR attached, modelled on the Hokuyo UTM-30LX. It has a range between 0.1 and 30m, and scans in a 270° arc. The model can be used for testing Collision Prevention.
sh
make px4_sitl gz_x500_lidar_2d
INFO
The sensor information is written to the ObstacleDistance UORB message used by collision prevention.
Літак/Фіксоване крило
Стандартний літак
sh
make px4_sitl gz_rc_cessna
Покращений літак
PX4 v1.15sh
make px4_sitl gz_advanced_plane
INFO
The difference between the Advanced Plane and the "regular plane" lies in the Lift Physics that the two models use:
- Можна налаштувати плагін покращеної піднімної сили що використовуються моделлю для точнішої відповідності певному засобу використовуючи Інструмент "Покращена піднімна сила".
- Для отримання додаткової інформації про розрахунки піднімної сили для покращеного літака, дивіться PX4-SITL_gazebo-classic/src/liftdrag_plugin/index.md
ВЗІП
Стандартний ВЗІП
sh
make px4_sitl gz_standard_vtol
Rover
Differential Rover
Differential Rover uses the rover world by default.
sh
make px4_sitl gz_r1_rover
Ackermann Rover
Ackermann Rover uses the rover world by default.
sh
make px4_sitl gz_rover_ackermann