本文记录 Gazebo + PX4 SITL 仿真环境的基础启动流程,包括加载仓库世界、启动普通无人机、启动搭载 MID360 的无人机,以及将 MID360 点云桥接到 ROS 2。
一、启动 Gazebo 世界
打开第一个终端,进入 PX4 工程并加载 Gazebo 环境:
1 2 3
| cd ~/PX4-Autopilot source build/px4_sitl_default/rootfs/gz_env.sh gz sim -r Tools/simulation/gz/worlds/warehouse_world.sdf
|
该命令会启动 warehouse_world 仓库仿真场景。
二、启动普通无人机
打开第二个终端,启动带下视相机的 X500 无人机:
1 2 3 4 5 6 7 8
| cd ~/PX4-Autopilot
PX4_GZ_STANDALONE=1 \ PX4_GZ_WORLD=warehouse_world \ PX4_SYS_AUTOSTART=4014 \ PX4_SIM_MODEL=gz_x500_mono_cam_down \ PX4_GZ_MODEL_POSE="0,0,0.2,0,0,0" \ ./build/px4_sitl_default/bin/px4 -i 0
|
其中 PX4_GZ_STANDALONE=1 表示 Gazebo 已经单独启动,PX4 只负责加载模型并运行 SITL。
三、启动搭载 MID360 的无人机
如果需要激光雷达点云数据,改用搭载 MID360 的无人机模型:
1 2 3 4 5 6 7 8 9 10 11 12
| cd ~/PX4-Autopilot
PX4_GZ_STANDALONE=1 \ PX4_GZ_WORLD=warehouse_world \ PX4_GZ_MODELS=$PWD/Tools/simulation/gz/worlds \ PX4_GZ_WORLDS=$PWD/Tools/simulation/gz/worlds \ GZ_SIM_RESOURCE_PATH=$PWD/Tools/simulation/gz/worlds:$PWD/Tools/simulation/gz/models:$GZ_SIM_RESOURCE_PATH \ PX4_SYS_AUTOSTART=4014 \ PX4_SIM_MODEL=gz_x500_mono_cam_down_mid360 \ PX4_GZ_MODEL_POSE="0,0,0.2,0,0,0" \ PX4_PARAM_NAV_DLL_ACT=0 \ ./build/px4_sitl_default/bin/px4 -i 0
|
这里需要额外配置 PX4_GZ_MODELS、PX4_GZ_WORLDS 和 GZ_SIM_RESOURCE_PATH,确保 Gazebo 能找到自定义世界和模型资源。
四、桥接 MID360 点云
打开第三个终端,将 Gazebo 中的 MID360 点云桥接到 ROS 2:
1 2 3 4 5
| GZ_LIDAR_TOPIC=/world/warehouse_world/model/x500_mono_cam_down_mid360_0/link/lidar_sensor_link/sensor/lidar/scan/points
ros2 run ros_gz_bridge parameter_bridge \ "${GZ_LIDAR_TOPIC}@sensor_msgs/msg/PointCloud2[gz.msgs.PointCloudPacked" \ --ros-args -r "${GZ_LIDAR_TOPIC}:=/mid360/points"
|
桥接成功后,ROS 2 中会得到点云话题:
可以用下面的命令确认话题是否正常发布:
1 2
| ros2 topic list | grep mid360 ros2 topic echo /mid360/points --once
|
五、启动顺序
推荐按下面的顺序启动:
1 2 3 4
| 1. 启动 Gazebo 世界 2. 启动 PX4 SITL 无人机 3. 桥接 MID360 点云 4. 启动后续算法节点,例如 FAST-LIO2、EGO-Planner
|