Distance Sensors (Rangefinders)

Distance sensors provide distance measurement that can be used for terrain following, terrain holding (i.e. precision hovering for photography), improved landing behaviour (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 simulation information. More detailed setup and configuration information is provided in the topics linked below (and sidebar).

Lidar Lite V3LightWare SF11/C LidarAerotenna uLanding

Supported Rangefinders

Lidar-Lite

Lidar-Lite is a compact, high-performance optical distant measurement rangefinder. It has a sensor range from (5cm - 40m) and can be connected to either PWM or I2C ports.

MaxBotix I2CXL-MaxSonar-EZ

The MaxBotix I2CXL-MaxSonar-EZ range has a number of relatively short-ranged sonar based rangefinders that are suitable for assisted takeoff/landing and collision avoidance. These can be connected using an I2C port.

The rangefinders are enabled using the parameter SENS_EN_MB12XX.

Lightware LIDARs

Lightware SFxx Lidar provide a range of lightweight "laser altimeters" that are suitable for many drone applications:

  • SF02
  • SF10/A (25 m)
  • SF10/B (50 m)
  • SF10/C (100m) (Discontinued)
  • SF11/C (120 m)
  • SF/LW20 (100 m) - Waterproofed (IP67) with servo for sense-and-avoid applications

Drivers exist for both I2C and serial ports (not all devices are supported for both serial and I2C).

TeraRanger Rangefinders

TeraRanger provide a number of lightweight distance measurement sensors based on infrared Time-of-Flight (ToF) technology. They are typically faster and have greater range than sonar, and smaller and lighter than laser-based systems.

PX4 supports the following models connected via the I2C bus: TeraRanger One, TeraRanger Evo 60m and TeraRanger Evo 600Hz.

uLanding Radar

The Aerotenna uLanding Radar is compact microwave rangefinder that has been optimised for use on UAVs. It has a sensing range of 45m. A particular advantages of this product are that it can operate effectively in all weather conditions and over all terrain types (including water).

LeddarOne

LeddarOne is small Lidar module with a narrow, yet diffuse beam that offers excellent overall detection range and performance, in a robust, reliable, cost-effective package. It has a sensing range from 1cm to 40m and needs to be connected to a UART/serial bus.

TFmini

The Benewake TFmini Lidar is a tiny, low cost, and low power LIDAR with 12m range.

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.

Other

PX4 also supports the Bebop rangefinder.

Configuration/Setup

Rangefinders are usually connected to either a serial (PWM) or I2C port (depending on the device driver), and are enabled on the port by setting a particular parameter.

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.

Generic Configuration

The common rangefinder configuration is specified using EKF2_RNG_* parameters. These include (non exhaustively):

  • EKF2_RNG_POS_X, EKF2_RNG_POS_Y, EKF2_RNG_POS_Z - offset of the rangefinder from the vehicle centre of gravity in X, Y, Z directions.
  • EKF2_RNG_PITCH - A value of 0 degrees (default) corresponds to the range finder being exactly aligned with the vehicle vertical axis (i.e. straight down), while 90 degrees indicates that the range finder is pointing forward. Simple trigonometry is used to calculate the distance to ground if a non-zero pitch is used.
  • EKF2_RNG_DELAY - approximate delay of data reaching the estimator from the sensor.
  • EKF2_RNG_SFE - Range finder range dependant noise scaler.
  • EKF2_RNG_NOISE - Measurement noise for range finder fusion

Testing

The easiest way to test the rangefinder is to vary the range and compare to the values detected by PX4. The sections below show some approaches to getting the measured range.

QGroundControl Analyze Tool

The QGroundControl Analyze Tool tool and QGroundControl MAVLink Inspector let 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. You will only get DISTANCE_SENSOR messages if the connected vehicle has a rangefinder installed and is publishing sensor values.

To view the rangefinder output:

  1. Open the menu Widgets > Analyze:

    Menu for QGC Analyze Tool

  2. Select the message DISTANCE_SENSOR.current_value. The tool will then plot the result: QGC Analyze DISTANCE_SENSOR value

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

listener distance_sensor 5

The QGroundControl MAVLink Console works when connected to Pixhawk or other NuttX targets, but not the Simulator. On the Simulator you can run the commands directly in the terminal.

For more information see: Sensor/Topic Debugging using the Listener Command (PX4 Development Guide).

Simulation

Lidar and sonar rangefinders can be used in the Gazebo Simulator (PX4 Development Guide). To do this you must start the simulator using a vehicle model that includes the rangefinder.

The iris optical flow model includes a Lidar rangefinder:

make px4_sitl gazebo_iris_opt_flow

The typhoon_h480 includes a sonar rangefinder:

make px4_sitl gazebo_typhoon_h480

If you need to use a different vehicle you can include the model in its configuration file. You can see how in the respective Iris and Typhoon configuration files:

  • iris_opt_flow.sdf
      <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>
    
  • typhoon_h480.sdf
      <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>
    
© PX4 Dev Team. License: CC BY 4.0            Updated: 2020-10-28 22:06:47

results matching ""

    No results matching ""