Skip to content

距离传感器(测距仪)

Distance sensors provide distance measurement that can be used for terrain following, terrain holding (i.e. precision hovering for photography), improved landing behaviour (conditional range aid), warning of regulatory height limits, collision prevention, etc.

This section lists the distance sensors supported by PX4 (linked to more detailed documentation), the generic configuration required for all rangefinders, testing, and Gazebo-Classic simulation information. 更详细的设置和配置信息在下方(和侧边栏)的主题链接中提供

Lidar Lite V3LightWare SF11/C LidarARK Flow

支持的测距仪

ARK Flow

ARK Flow is an open-source Time-of-Flight (ToF) and optical flow sensor module, which is capable of measuring distances from 8cm to 30m. 它可以通过CAN1接口连接至飞控,允许通过CAN2接口添加传感器。 It supports DroneCAN, runs PX4 DroneCAN Firmware, and is packed into a tiny form factor.

Holybro ST VL53L1X 激光雷达

The VL53L1X is a state-of-the-art, Time-of-Flight (ToF), laser-ranging sensor, enhancing the ST FlightSense™ product family. 它是市场上速度最快的微型 ToF 传感器,精确测距可达 4 m,快速测距频率可达 50 Hz。

它带有一个 JST GHR 4 针连接器,与 Pixhawk 4Pixhawk 5X和其他遵循 Pixhawk 连接器标准 的飞行控制器上的 I2C 端口兼容。

激光雷达精简版

激光雷达精简版 是一款紧凑、高性能的光学远距离测量测距仪。 它的传感器范围为 (5cm - 40m),可以连接到 PWM 或 I2C 端口。

MaxBotix I2CXL-MaxSonar-EZ

MaxBotix I2CXL-MaxSonar-EZ 测距 有许多基于声纳的相对短程测距仪 ,适用于辅助起飞/着陆和避免碰撞。 这些可以使用 I2C 端口连接。

测距仪通过使用参数SENS_EN_MB12XX启用。

Lightware LIDARs

Lightware SFxx Lidar 提供一个宽范围的轻量级激光高度计,适用于许多无人机应用。

PX4 支持: SF11/c 和 SF/LW20. PX4 也可用于一下停产的型号: SF02, SF10/a, SF10/b, SF10/c.

PX4 also supports the LightWare LiDAR SF45 Rotating Lidar for collision prevention applications.

TeraRanger 测距仪

TeraRanger 提供了一些基于红外光飞行时间(ToF)技术的轻量级距离测量传感器。 他们通常比声纳更快、范围更大、比基于激光的系统更小、更轻。

PX4 提供以下通过 I2C总线连接的型号:TeraRanger One, TeraRanger Evo 60m 和 TeraRanger Evo 600Hz。

Ainstein US-D1 标准雷达高度计

The Ainstein US-D1 Standard Radar Altimeter is compact microwave rangefinder that has been optimised for use on UAVs. 它有大约50米的感测范围。 该产品的一个特别优势是它可以在所有天气条件下和所有地形类型(包括水)上有效运行。

LeddarOne

LeddarOne 是一种小型激光雷达模块,具有窄而漫反射的光束,在一个坚固、可靠、经济高效的组件中提供出色的整体探测范围和性能。 它的遥感范围从1厘米到40米不等,需要与UART/串行总线连接。

TFmini

Benewake TFmini Lidar 是一个的小巧、低成本、低功率的激光测距拥有 12m 的测量范围

PSK-CM8JL65-CC5

The Lanbao PSK-CM8JL65-CC5 ToF Infrared Distance Measuring Sensor is a very small (38 mm x 18mm x 7mm, <10g) IR distance sensor with a 0.17m-8m range and millimeter resolution. It must be connected to a UART/serial bus.

Avionics Anonymous UAVCAN 激光高度计接口

The Avionics Anonymous UAVCAN Laser Altimeter Interface allows several common rangefinders (e.g. Lightware SF11/c, SF30/D, etc) to be connected to the CAN bus via DroneCAN, a more robust interface than I2C.

配置/设置

测距仪通常连接到串口(PWM)或者 I2C 接口(取决于设备驱动),并通过设置特定的参数在端口上启用。

The hardware and software setup that is specific to each distance sensor is covered in their individual topics.

The generic configuration that is common to all distance sensors, covering both the physical setup and usage, is given below.

常规配置

The common rangefinder configuration is specified using EKF2_RNG_* parameters. 这些包括(非详尽):

  • EKF2_RNG_POS_X, EKF2_RNG_POS_Y, EKF2_RNG_POS_Z - 测距仪在 X、Y、Z 方向上与车辆重心的偏移量。
  • EKF2_RNG_PITCH - 0 度值(默认值)对应于测距仪与车辆垂直轴精确对齐(即垂直向下),而 90 度表示测距仪指向前方。 如果使用非零间距,则使用简单的三角法计算到地面的距离。
  • EKF2_RNG_DELAY - 数据从传感器到达估计器的近似延迟。
  • EKF2_RNG_SFE - Range finder range dependent noise scaler.
  • EKF2_RNG_NOISE - 测距仪融合的测量噪声

测试

测试测距仪最简单的方法是改变距离并与 PX4 检测到的值进行比较 以下部分显示了一些获取测量范围的方法。

The QGroundControl MAVLink Inspector lets you view messages sent from the vehicle, including DISTANCE_SENSOR information from the rangefinder. The main difference between the tools is that the Analyze tool can plot values in a graph.

The messages that are sent depend on the vehicle configuration. DISTANCE_SENSOR只有在联网车辆安装了测距仪并发布传感器值时,您才会收到消息。

查看测距仪输出:

  1. Open the menu Q > Select Tool > Analyze Tools:

    Menu for QGC Analyze Tool

  2. 选择消息DISTANCE_SENSOR,然后选中plot复选框current_distance。 工具将会绘制结果: QGC Analyze DISTANCE_SENSOR value

You can also use the QGroundControl MAVLink Console to observe the distance_sensor uORB topic:

sh
listener distance_sensor 5

The QGroundControl MAVLink Console works when connected to Pixhawk or other NuttX targets, but not the Simulator. 在模拟器上可以直接在终端中运行命令。

For more information see: Development > Debugging/Logging > Sensor/Topic Debugging using the Listener Command.

Gazebo-Classic Simulation

Lidar and sonar rangefinders can be used in the Gazebo Classic simulator. 要做到这一点,你必须在启动模拟器时使用一个拥有测距仪的机体模型。

iris 光流模型包括激光雷达测距仪:

sh
make px4_sitl gazebo-classic_iris_opt_flow

typhoon_h480 包括一个声纳测距仪:

sh
make px4_sitl gazebo-classic_typhoon_h480

如果你需要使用一个不同的车辆,你可以在它的配置文件中包含此模型。 你可以看到如何在相应的 Iris 和 Typhoon 配置文件:

  • iris_opt_flow.sdf

    xml
      <include>
        <uri>model://lidar</uri>
        <pose>-0.12 0 0 0 3.1415 0</pose>
      </include>
      <joint name="lidar_joint" type="revolute">
        <child>lidar::link</child>
        <parent>iris::base_link</parent>
        <axis>
          <xyz>0 0 1</xyz>
          <limit>
            <upper>0</upper>
            <lower>0</lower>
          </limit>
        </axis>
      </joint>
  • typhoon_h480.sdf

    xml
      <include>
        <uri>model://sonar</uri>
      </include>
      <joint name="sonar_joint" type="revolute">
        <child>sonar_model::link</child>
        <parent>typhoon_h480::base_link</parent>
        <axis>
          <xyz>0 0 1</xyz>
          <limit>
            <upper>0</upper>
            <lower>0</lower>
          </limit>
        </axis>
      </joint>