ROS2 / 无人机 / 遥感 · 2025年 12月 29日 5

PX4+Gazebo仿真,自定义world场景和无人机传感器model及属性

更新最频繁的一集,我靠这篇累死我。环境为Ubuntu 22.04.5,PX4 1.16.0,Gazebo Sim 8 (Harmonic)。本文xml含量极高。

worlds添加与配置

PX4自带的世界都在clone仓库的路径里:~/PX4-Autopilot/Tools/simulation/gz/worlds,px4启动时默认的世界就是default.sdf。这里以baylands.sdf为例:

<sdf version='1.9'>
  <world name='baylands'>
    <physics type="ode">
      <max_step_size>0.004</max_step_size>
      <real_time_factor>1.0</real_time_factor>
      <real_time_update_rate>250</real_time_update_rate>
    </physics>
    <gravity>0 0 -9.8</gravity>
    <magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
    <atmosphere type='adiabatic'/>
    <scene>
      <ambient>0.8 0.5 1</ambient>
      <grid>false</grid>
      <sky>
        <clouds>true</clouds>
      </sky>
      <shadows>1</shadows>
    </scene>
    <light name='sunUTC' type='directional'>
      <pose>0 0 500 0 -0 0</pose>
      <cast_shadows>false</cast_shadows>
      <intensity>1</intensity>
      <direction>0.001 0.625 -0.78</direction>
      <diffuse>0.904 0.904 0.904 1</diffuse>
      <specular>0.271 0.271 0.271 1</specular>
      <attenuation>
        <range>2000</range>
        <linear>0</linear>
        <constant>1</constant>
        <quadratic>0</quadratic>
      </attenuation>
    </light>
    <include>
      <uri>
        https://fuel.gazebosim.org/1.0/OpenRobotics/models/baylands
      </uri>
      <name>park</name>
      <pose>205 155 -1 0 0 0</pose>
    </include>
    <include>
      <uri>
        https://fuel.gazebosim.org/1.0/OpenRobotics/models/Coast Water
      </uri>
      <pose>0 0 -2 0 0 0
        <relative_to>park</relative_to>
      </pose>
    </include>
    <spherical_coordinates>
      <surface_model>EARTH_WGS84</surface_model>
      <world_frame_orientation>ENU</world_frame_orientation>
      <latitude_deg>37.412173071650805</latitude_deg>
      <longitude_deg>-121.998878727967</longitude_deg>
      <elevation>38</elevation>
    </spherical_coordinates>
  </world>
</sdf>

其实能发现一个sdf的结构还是很清晰的,physics标签定义了物理仿真模式和刷新速度等,下面还有重力、磁场、大气、环境、太阳光。中间插入了两个建模,baylands和Coast Water,并且链接到gazebo官方的模型库网站,所以第一次运行这个世界的话,程序会先自动下载需要的模型,保存在隐藏文件夹~/.simulation-gazebo/中。最后的spherical_coordinates标签内则是一些定位信息。这里面的重力、磁场、大气、定位等信息都是仿真飞控需要的,没配置好会导致不允许起飞。

前段时间在学校倾斜摄影了校史馆,模型建出来还不赖,问题来了SCAU为什么不去建酸奶的模。注意自己的模型最好是dae格式,要用blender编辑的话我这用的是长期维护的4.2的最新版。

接下来把模型包装成一个本地的gazebo世界。我在home下创建了一个myDAEs的模型根目录,然后在该模型的目录下有三样东西,meshes里面是模型文件以及贴图,另外两个都是必要的配置文件。配置文件和目录的名称要注意匹配一下,具体有什么规定我也忘了()

此处的sdf文件,注意这个sdf和前面那个sdf功能并不一样,这里主要是定义模型和碰撞箱:

<?xml version="1.0" ?>
<sdf version="1.9">
  <model name="HistoryM">
    <static>true</static>
    
    <link name="link">
      <visual name="visual">
        <geometry>
          <mesh>
            <uri>model://HistoryM/meshes/HistoryM20251211.dae</uri>
            <scale>1.0 1.0 1.0</scale>
          </mesh>
        </geometry>
      </visual>

      <collision name="collision">
        <geometry>
          <mesh>
            <uri>model://HistoryM/meshes/HistoryM20251211.dae</uri>
            <scale>1.0 1.0 1.0</scale>
          </mesh>
        </geometry>
        </collision>
    </link>
  </model>
</sdf>

model.config:

<?xml version="1.0"?>
<model>
  <name>HistoryM</name>
  <version>1.0</version>
  <sdf version="1.9">HistoryM.sdf</sdf>

  <author>
    <name>Evil KT</name>
    <email>xxx@163.com</email>
  </author>

  <description>
  SCAU History Museum.
  </description>
</model>

为什么要配置这么多,问px4和gazebo的人去。接下来要配置环境变量,gedit ~/.bashrc一下,然后把这句加到最后一行,这样以后我自己的世界模型都放在这个文件夹里,gazebo也能直接访问到:

export GZ_SIM_RESOURCE_PATH=$GZ_SIM_RESOURCE_PATH:~/myDAEs

再回到PX4的worlds路径中,再创建一个配置文件,我这是HistoryM.sdf,仿照前面baylands写如下内容:

<sdf version='1.9'>
  <world name='historyM'>
    <physics type="ode">
      <max_step_size>0.001</max_step_size>
      <real_time_factor>1.0</real_time_factor>
      <real_time_update_rate>1000</real_time_update_rate>
    </physics>
    <gravity>0 0 -9.8</gravity>
    <magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
    <atmosphere type='adiabatic'/>
    <scene>
      <ambient>0.8 0.5 1</ambient>
      <grid>false</grid>
      <sky>
        <clouds>true</clouds>
      </sky>
      <shadows>1</shadows>
    </scene>
    <light name='sunUTC' type='directional'>
      <pose>0 0 500 0 -0 0</pose>
      <cast_shadows>false</cast_shadows>
      <intensity>1</intensity>
      <direction>0.001 0.625 -0.78</direction>
      <diffuse>0.904 0.904 0.904 1</diffuse>
      <specular>0.271 0.271 0.271 1</specular>
      <attenuation>
        <range>2000</range>
        <linear>0</linear>
        <constant>1</constant>
        <quadratic>0</quadratic>
      </attenuation>
    </light>
    
    <include>
      <uri>model://HistoryM</uri>
      <name>HistoryM</name>
      <pose>0 0 -2 0 0 0</pose>
    </include>
    
    <spherical_coordinates>
      <surface_model>EARTH_WGS84</surface_model>
      <world_frame_orientation>ENU</world_frame_orientation>
      <latitude_deg>23.159806</latitude_deg>
      <longitude_deg>113.343986</longitude_deg>
      <elevation>30</elevation>
    </spherical_coordinates>
  </world>
</sdf>

注意有几项修改。实验的时候发现在自己的世界下,无人机罗盘会一直找方向一直转,似乎是因为自己的模型比较大,物理刷新没跟上还是怎么,max_step_size改成0.001之后基本就正常了,然后real_time_update_rate改成1000,这两者相乘要等于中间的real_time_factor,这个是相对于现实世界的时间快慢,此处1代表与现实时间流速一致。下面的模型换成自己的,因为设定了环境变量,uri写model://HistoryM就行。定位改到了这个建模的实际位置。

启动仿真,添加一个无人机初始位置参数和一个选world的参数就可以了。这里开的云台相机,话题发布略。

PX4_GZ_MODEL_POSE=-17.7,3.2,1.4,0,0,0 PX4_GZ_WORLD=historyM make px4_sitl gz_x500_gimbal

无人机传感器模型配置

跟world类似,无人机相关的模型文件在~/PX4-Autopilot/Tools/simulation/gz/models,并且建模和其他配置文件都放这儿就行,里面有所有自带的机架和各种传感器,基本上仿照着写。不过后面还有个为新无人机注册的流程。

PX4自带的激光雷达只有1d和2d的,也就是一个点或者水平面上一条线。所以我来从lidar_2d_v2的基础上按照livox mid-360激光雷达,改个新的无人机。复制lidar_2d_v2改名livox_mid_360文件夹,修改model.sdf:

<?xml version="1.0" ?>
<sdf version="1.6">
  <model name="livox_mid_360">
    <link name="lidar_link">
      <pose>0 0 0 0 0 0</pose>

      <inertial>
        <pose>0 0 0.030 0 0 0</pose> <mass>0.265</mass> <inertia>
          <ixx>0.00018</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.00018</iyy>
          <iyz>0</iyz>
          <izz>0.00016</izz>
        </inertia>
      </inertial>

      <collision name="collision_box">
        <pose>0 0 0.030 0 0 0</pose> <geometry>
          <box>
            <size>0.065 0.065 0.060</size> </box>
        </geometry>
      </collision>
      <visual name="visual">
        <geometry>
          <mesh>
            <uri>model://livox_mid_360/meshes/livox_mid_360.dae</uri>
          </mesh>
        </geometry>
      </visual>

      <sensor name="lidar" type="gpu_lidar">
        <pose>0 0 0.09 0 0 0</pose> <ray>
          <scan>
            <horizontal>
              <samples>720</samples> <resolution>1</resolution>
              <min_angle>0</min_angle>
              <max_angle>6.283185</max_angle> </horizontal>
            <vertical>
              <samples>64</samples> 
              <resolution>1</resolution>
              <min_angle>-0.122173</min_angle> <max_angle>0.907571</max_angle> </vertical>
          </scan>
          <range>
            <min>0.1</min> <max>70</max> <resolution>0.01</resolution>
          </range>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.02</stddev> 
          </noise>
        </ray>
        
        <always_on>1</always_on>
        <update_rate>10</update_rate> <visualize>false</visualize>
      </sensor>
    </link>
  </model>
</sdf>

这里稍微改了下碰撞箱,然后sensor标签改成mid360实际的一些参数,还有噪声等等。model.config里面就改改name什么的好了,反正照着给的示例来好啦。

然后仿照x500_lidar_2d的配置,写个x500_livox配置,我主要把激光雷达位置放到了无人机中央,然后顺便把自带的深度相机配置也给塞了进来(喜)。

注册步骤:再来到路径~/PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/airframes,依旧仿照4013_gz_x500_lidar_2d创建了个4022_gz_x500_livox。再打开CMakeLists.txt,把4022_gz_x500_livox添加到4021无人机的后一位。现在清理掉之前的编译文件,再重新编译启动即可:

make clean
PX4_GZ_MODEL_POSE=-17.7,3.2,1.4,0,0,0 PX4_GZ_WORLD=historyM make px4_sitl gz_x500_livox

gz topic -l查询现有的gz话题,把激光雷达点云、深度相机点云和图像桥接到ROS2:

ros2 run ros_gz_bridge parameter_bridge /world/historyM/model/x500_livox_0/link/lidar_link/sensor/lidar/scan/points@sensor_msgs/msg/PointCloud2@gz.msgs.PointCloudPacked

ros2 run ros_gz_bridge parameter_bridge /depth_camera/points@sensor_msgs/msg/PointCloud2@gz.msgs.PointCloudPacked

ros2 run ros_gz_bridge parameter_bridge /world/historyM/model/x500_livox_0/link/camera_link/sensor/IMX214/image@sensor_msgs/msg/Image@gz.msgs.Image

启动rviz2之后如果fixed_frame不正常(有点玄学),需要手动发布静态坐标转换,ros2 topic echo /world/historyM/model/x500_livox_0/link/lidar_link/sensor/lidar/scan/points这样的指令可以获取话题的frame_id,其实就是在gazebo右下角的传感器路径。发布两个变换,要重新定义相对坐标,这里的base_link相当于是新建的坐标系,名称无所谓,也可以用map等。

ros2 run tf2_ros static_transform_publisher 0 0 0.26 0 0 0 base_link x500_livox_0/lidar_link/lidar

ros2 run tf2_ros static_transform_publisher .12 .03 .242 0 0 0 base_link x500_livox_0/camera_link/StereoOV7251

呃,这图是还没加深度相机时候的截图……哦雷达模型也因为路径写错隐藏了。反正后来是正常的。

关于仿真器坐标系和静态tf的问题,附在github上发的神秘仙家issue:https://github.com/PX4/PX4-Autopilot/issues/26129#event-21618582560

睦头:从来没有觉得搞仿真开心过……