Rangefinders/Distance Sensors
Rangefinders provide distance measurement that can be used for terrain following, precision hovering (e.g. for photography), warning of regulatory height limits, collision avoidance etc.
The sensors can usually be connected to either a serial (PWM) or I2C port (depending on driver support for the particular rangefinder), and the rangefinder is enabled on a port by setting a particular parameter.
This section lists the rangefinders supported by PX4 and the generic configuration information. More detailed documentation is linked for some rangefinders.
The drivers for less common rangefinders may not be present by default in all firmware. In this case you may need to add the driver into your cmake configuration file and build the firmware yourself. For more information see the PX4 Development Guide.
Supported Rangefinders
Lidar-Lite
The Lidar Lite can be used with either PWM or I2C. The rangefinder/port is enabled using SENS_EN_LL40LS:
- LIDAR-Lite v3 (5cm - 40m)
Pixhawk wiring information and Lidar-lite specific test instructions can be found here: Lidar lite (pixhawk.org).
The driver for this rangefinder is usually present in firmware (driver added as: drivers/ll40ls
).
PWM is recommended if using an older model (some older models do not behave reliably on I2C).
The Lidar-Lite v3 may be used in the The Intel® Aero Ready to Fly Drone (but is not recommended).
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 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, which can be configured using the parameters SENS_EN_SF0X and SENS_EN_SF1XX (respectively).
Wiring and other information for the I2C variants can be found in the topic Lightware SFxx Lidar.
Not all devices are supported for both serial and I2C; check the parameters for more information and supported models.
TeraRanger Rangefinders
TeraRanger provide a number of lightweight distance measurement sensor 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:
- TeraRanger One (0.2 - 14 m) (Requires an I2C adapter)
- TeraRanger Evo 60m (0.5 – 60 m)
- TeraRanger Evo 600Hz (0.75 - 8 m)
All TeraRanger sensors must be connected via the I2C bus. While TeraRanger One requires an I2C adapter any sensor from TeraRanger Evo series can be connected directly to the autopilot.
The sensors are enabled using the parameter SENS_EN_TRANGER (you can set the type of sensor or that PX4 should auto-detect the type).
If using auto-detect for Evo sensors the minimum and maximum values for the range are set to the lowest and highest possible readings across the Evo family (currently 0.5 - 60 m). In order to use the correct max/min values the appropriate model of the Evo sensor should be set in the parameter (instead of using autodetect).
The Terranger One is used in the Qualcomm Snapdragon Flight.
uLanding Radar
The Aerotenna uLanding altimeter 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).
The uLanding Radar is not present in "most" firmware by default and must be started by updating a configuration file (rather than by a parameter). More information can be found here: uLanding Radar.
LeddarOne
LeddarOne is small-size 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.
For setup/usage information see: LeddarOne.
TFmini
The Benewake TFmini LiDAR is a tiny, low cost, and low power LIDAR with 12m range.
This lidar is currently in master, and should appear in releases from PX4 v1.8.
In general the TFmini can be used by setting the parameter SENS_EN_TFMINI > 0 and connecting the sensor to the correct (board-specific) port:
Board | Port |
---|---|
Intel Aero | TELEMETRY |
Pixhawk PX4FMU_V3 | SERIAL 4/5 |
Other Pixhawk based boards | TELEM2. The SYS_COMPANION must be set to 0. |
To use the TFmini on other ports/boards, the driver can be started by using the following line in a shell or the extras.txt (startup) file located on your SD card (where <serial port>
is the port id):
tfmini start -d <serial port>
Most boards will already include the driver in firmware. If not, add the following line to the cmake config file that corresponds to the target board:
drivers/tfmini
Other
PX4 also supports the Bebop rangefinder.
Rangefinder Configuration
Setup
The rangefinder is configured using EKF2_RNG_* parameters. These configure information about the offset of the rangefinder from the centre of the vehicle body, the approximate delay of data reaching the estimator from the sensor, etc.
Enable/Use
The rangefinder can be enabled in two ways:
- Set EKF2_HGT_MODE to Range finder (
2
). This makes the rangefinder the primary source of height estimation (the default altitude sensor is the barometer). - Set EKF2_RNG_AID to
1
. This makes the vehicle use the rangefinder as the primary source when it is safe to use, but will otherwise use the sensor specified inEKF2_HGT_MODE
.- Specifically, the rangefinder is enabled when:
- velocity < EKF2_RNG_A_VMAX
- distance to ground < EKF2_RNG_A_HMAX
- Other parameters affecting "Range aid" are prefixed with
EKF2\_RNG\_A\_
.
- Specifically, the rangefinder is enabled when:
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:
Open the menu Widgets > Analyze:
- Select the message
DISTANCE_SENSOR.current_value
. The tool will then plot the result:
QGroundControl MAVLink Console
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 posix_sitl_default gazebo_iris_opt_flow
The typhoon_h480 includes a sonar rangefinder:
make posix_sitl_default 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>
Further Information
- Rangefinder (Pixhawk.org) - Rangefinders supported by Pixhawk