MAVLINKHUD

Overview

The RNGFND parameter group configures the Rangefinder (Lidar, Ultrasonic, or Radar) subsystem. Rangefinders provide precise altitude data (distance to ground) or obstacle distance.

ArduPilot supports up to 10 simultaneous rangefinder instances, which can be oriented in any direction (Down, Forward, Up, etc.).

Key Concepts

1. Distance Sensing Types (RNGFNDn_TYPE)

Defines the hardware protocol.

  • 1 (Analog): Old ultrasonic sensors.
  • 2 (MaxbotixI2C): I2C Ultrasonic.
  • 4 (LightWareI2C): High-end Lidar.
  • 15 (MAVLink): Distance data from a companion computer or separate MAVLink device.
  • 24 (DroneCAN): CAN-based sensors (e.g., HereFlow, Benewake CAN).

2. Orientation (RNGFNDn_ORIENT)

Determines which direction the sensor is pointing.

  • 25 (Down): Used for precision landing, terrain following, and automated takeoff/landing.
  • 0 (Forward): Used for simple obstacle avoidance.
  • 6 (Up): Used for ceiling avoidance or indoor altitude hold.

3. Scaling and Offsets

  • RNGFNDn_SCALING: Multiplier for analog sensors.
  • RNGFNDn_OFFSET: Physical distance (meters) between the sensor and the zero-point of the vehicle.
  • RNGFND_GNDCLEAR: (Down only) The distance from the sensor to the ground when the vehicle is physically resting on its landing gear. Critical for proper landing detection.

Parameter Breakdown

  • RNGFNDn_MIN / MAX: The valid operating range of the sensor (centimeters). Values outside this range are ignored by the EKF.
  • RNGFND_FILT: Cutoff frequency for the rangefinder data filter (Hz).

Integration Guide

Setting up a Downward Lidar

  1. Mount: Face the sensor straight down with a clear view of the ground.
  2. Enable: Set RNGFND1_TYPE to your sensor model.
  3. Orient: Set RNGFND1_ORIENT = 25.
  4. Measure: Measure the distance to the ground while landed and set RNGFND_GNDCLEAR.
  5. Verify: Check the sonar_range or rngfnd1 value in the GCS. It should read correctly as you lift the drone.

Developer Notes

  • Library: libraries/AP_RangeFinder.
  • Usage: Fused by AP_NavEKF3 to improve vertical position accuracy and for "Terrain Following" mission logic.

GNDCLEAR

cm
Default 10
Range 1 100

Rangefinder Ground Clearance (GNDCLEAR)

Description

GNDCLEAR tells the autopilot how high the Lidar sensor is sitting when the drone is on the ground.

When the drone is stationary on its landing gear, the Lidar reading isn't zero (because the sensor is usually a few centimeters off the dirt). This parameter allows the flight controller to subtract that height so that the reported "Altitude" is exactly zero on the ground.

Tuning & Behavior

  • Default Value: 10 cm.
  • Recommendation: Measure the distance from the sensor face to the floor and enter it here.

RNGFND1_ADDR

Default 0
Range 0 127

Rangefinder Address (RNGFND1_ADDR)

Description

RNGFND1_ADDR sets the unique identifier used to communicate with the sensor over a digital bus.

  • For I2C sensors: This is the 7-bit I2C address (e.g., 0x62 for LIDAR-Lite).
  • For DroneCAN sensors: This is the Node ID assigned to the sensor.
  • For Serial/Analog sensors: This parameter is generally ignored.

Tuning & Behavior

  • Default: 0 (Use the driver's default address).
  • Setup: Only change this if you have multiple identical sensors on the same bus and have reconfigured one to a non-default address.

RNGFND1_FUNCTION

Default 0
Range 0 2

Rangefinder Voltage Function (RNGFND1_FUNCTION)

Description

RNGFND1_FUNCTION defines the relationship between the sensor's output voltage and the actual physical distance. This is only used for Analog sensors.

  • 0: Linear (Standard). $\text{Dist} = (\text{Volt} - \text{Offset}) \times \text{Scaling}$. Used for most ultrasonic and infrared sensors.
  • 1: Inverted. $\text{Dist} = (\text{Offset} - \text{Volt}) \times \text{Scaling}$. Used for sensors where voltage decreases as distance increases.
  • 2: Hyperbolic. $\text{Dist} = \frac{\text{Scaling}}{\text{Volt} - \text{Offset}}$.

Tuning & Behavior

  • Default: 0 (Linear).
  • Recommendation: Check your sensor's data sheet. If the graph of "Distance vs Voltage" is a straight line, use Linear. If it's a curve, you may need Hyperbolic.

RNGFND1_OFFSET

V
Default 0
Range -1.0 1.0

Rangefinder Offset (RNGFND1_OFFSET)

Description

RNGFND1_OFFSET provides a linear correction to the distance measurement.

For Analog sensors, this is an electrical offset in Volts (e.g. the sensor outputs 0.2V even at 0cm). For PWM sensors, this is an additive offset in centimeters (e.g. to account for the sensor being mounted 10cm inside the fuselage).

$$ \text{Distance} = (\text{Voltage} \times \text{Scaling}) + \text{Offset} $$

Tuning & Behavior

  • Default: 0.
  • Calibration: Place the vehicle at a known distance from a wall. If the reported distance is consistently too short, increase the offset.

RNGFND1_ORIENT

Default 25
Range 0 25

Rangefinder orientation (RNGFND1_ORIENT)

Description

RNGFND1_ORIENT defines the pointing vector of the distance sensor.

Correct orientation is vital for the EKF and flight controllers to know whether they are measuring altitude (Down), distance to an obstacle (Forward/Side), or height above the vehicle (Up).

  • 25: Down. (Most common). Used for altitude hold and precision landing.
  • 0: Forward. Used for simple object avoidance.
  • 24: Up. Used for ceiling-following or indoor flight.

Tuning & Behavior

  • Default: 25 (Down).
  • Warning: If the orientation is set incorrectly (e.g., set to Forward when pointing Down), the drone may attempt to "climb" to avoid what it thinks is an obstacle in front of it.

RNGFND1_PIN

Default -1
Range -1 100

Rangefinder Pin (RNGFND1_PIN)

Description

RNGFND1_PIN sets the Analog Input pin used for Analog rangefinders (Type 1).

  • -1: Not used.
  • 0-9: Analog Pin Number. (e.g. 0 for A0).
  • Note: This parameter is only relevant if RNGFND1_TYPE = 1.

Tuning & Behavior

  • Default: -1

RNGFND1_PWRRNG

m
Default 0
Range 0 32767

Rangefinder Power Save Range (RNGFND1_PWRRNG)

Description

RNGFND1_PWRRNG allows the autopilot to turn off the distance sensor when the drone is flying high.

Some Lidar sensors consume significant power. If you are flying a long-range mapping mission at 100m altitude, but your Lidar only works up to 20m, keeping it active is wasteful. This parameter puts the sensor into a low-power "Sleep" state when the estimated terrain clearance exceeds this value.

  • 0: Disabled (Sensor is always ON).
  • Value (m): Altitude above terrain at which the sensor sleeps.

Tuning & Behavior

  • Default: 0.
  • Usage: Set to slightly less than your sensor's maximum effective range.
  • Note: This requires the sensor driver to support a low-power mode (e.g. Lightware).

RNGFND1_RMETRIC

Default 1
Range 0 1

Rangefinder Ratiometric Enable (RNGFND1_RMETRIC)

Description

RNGFND1_RMETRIC calibrates the autopilot's ADC (Analog-to-Digital Converter) behavior for Analog distance sensors.

  • 1: Yes (Standard). Most simple analog sensors change their output voltage relative to the 5V supply. If the 5V rail drops slightly, the sensor's output drops too. The autopilot compensates for this by comparing the sensor voltage to the rail voltage.
  • 0: No. Use this if the sensor has its own internal voltage regulator and outputs a constant voltage regardless of the input power (e.g. some high-end Lightware sensors).

Tuning & Behavior

  • Default: 1.
  • Recommendation: Leave at 1 unless your sensor's manual explicitly states it has an internal voltage regulator.

RNGFND1_SCALING

m/V
Default 3.0
Range 0 100

Rangefinder Scaling (RNGFND1_SCALING)

Description

RNGFND1_SCALING calibrates Analog rangefinders (Type 1). It defines how many meters of distance correspond to 1.0 Volt of output.

$$ \text{Distance} = (\text{Voltage} \times \text{Scaling}) + \text{Offset} $$

  • Example: If 1V = 1m, set Scaling to 1.0.
  • Example: Maxbotix EZ4 outputs ~3.3V at 7m. Scaling ≈ 2.12.

Tuning & Behavior

  • Default: 3.0
  • Calculation: Measure the voltage at a known distance. $Scaling = \frac{\text{Distance}}{\text{Voltage}}$.

RNGFND1_SNR_MIN

Default 0
Range 0 255

Rangefinder Minimum SNR (RNGFND1_SNR_MIN)

Description

RNGFND1_SNR_MIN defines the "Quality Threshold" for your distance sensor.

Digital rangefinders (like those using DroneCAN) often report the strength of the reflection (SNR). In environments with poor reflectivity (e.g. over tall grass or dark surfaces) or at the very edge of the sensor's range, the data can become noisy and unreliable. This parameter tells the autopilot to ignore any distance reading if its quality score falls below this limit.

Tuning & Behavior

  • Default: 0 (Trust all data).
  • Recommendation: If you see your altitude "flickering" or jumping when the drone is high up or over difficult terrain, increase this value to 10 or 20.
  • Note: Setting this too high will cause the rangefinder to "drop out" (status 0) even when it might still be reporting valid data.
  • Context: This is primarily used by DroneCAN/UAVCAN rangefinders.

RNGFND1_STOP_PIN

Default -1
Range -1 103

Rangefinder Stop Pin (RNGFND1_STOP_PIN)

Description

RNGFND1_STOP_PIN allows ArduPilot to turn the rangefinder sensor ON and OFF dynamically.

This is primarily used to save battery power or to prevent the sensor from producing noisy signals when the vehicle is flying too high for the sensor to work (Out of Range).

  • -1: Disabled (Sensor is always ON).
  • 0-103: Physical GPIO pin number used to control the sensor's enable/stop line.

Tuning & Behavior

  • Default: -1.
  • Usage: If a pin is configured, the autopilot will set the pin HIGH to enable the sensor and LOW to disable it when the estimated altitude is well beyond the sensor's maximum range.

RNGFND1_TYPE

Default 0
Range 0 42

Rangefinder Type (RNGFND1_TYPE)

Description

RNGFND1_TYPE enables the primary altitude/distance sensor.

  • 0: None. Disabled.
  • 1: Analog. Voltage-based sensors.
  • 2: Maxbotix I2C.
  • 4: PulsedLight I2C. (LIDAR-Lite).
  • 10: MavLink.
  • 15: TFmini. (Serial).
  • 24: DroneCAN.

Tuning & Behavior

  • Default: 0
  • Reboot Required: Yes.
  • Setup: After setting the type, you must reboot, then configure RNGFND1_MIN_CM and RNGFND1_MAX_CM.

RNGFND1_WSP_AVG

Default 2
Range 0 255

Wasp-LRF Multi-Pulse Average (RNGFND1_WSP_AVG)

Description

RNGFND1_WSP_AVG improves the accuracy of the Wasp-LRF laser rangefinder.

In this mode, the sensor fires a quick sequence of laser pulses and averages the results before sending a single distance value to the autopilot. This helps filter out "Outliers" or noise caused by dust, rain, or difficult surfaces.

  • Higher Value: More accurate, but reduces the effective update frequency.
  • Lower Value: Faster updates, but more sensitive to noise.

Tuning & Behavior

  • Default: 2.
  • Recommendation: Leave at 2 for general flight. Increase to 5 or 10 if you are performing slow-speed precision tasks (like automatic docking) where accuracy is more important than speed.
  • Dependency: Only active if RNGFND1_TYPE is set to 18 (WASP-LRF).

RNGFND1_WSP_BAUD

Default 0
Range 0 1

Wasp-LRF Baud Rate (RNGFND1_WSP_BAUD)

Description

RNGFND1_WSP_BAUD sets the UART speed for the Wasp-LRF laser sensor.

  • 0: Low Speed (115200). Standard for most telemetry ports.
  • 1: High Speed (921600). Required if you are using extremely high update frequencies (>1000 Hz).

RNGFND1_WSP_FRQ

Hz
Default 20
Range 20 10000

Wasp-LRF Measurement Frequency (RNGFND1_WSP_FRQ)

Description

RNGFND1_WSP_FRQ controls how many times per second the Wasp-LRF laser rangefinder takes a distance measurement.

This is a hardware-specific parameter for the WASP-LRF sensor. A higher frequency provides more data for the autopilot to filter, which is useful for high-speed terrain following.

Tuning & Behavior

  • Default: 20 Hz.
  • Maximum: Up to 10,000 Hz (if supported by the sensor and communication baud rate).
  • Dependency: Only active if RNGFND1_TYPE is set to 18 (WASP-LRF).

RNGFND1_WSP_MAVG

Samples
Default 4
Range 0 255

Wasp-LRF Moving Average (RNGFND1_WSP_MAVG)

Description

RNGFND1_WSP_MAVG defines the window size for a smoothing filter inside the Wasp-LRF sensor driver.

A higher number of samples in the average leads to more stable altitude readings but introduces a small amount of latency (lag) as the drone moves vertically.

RNGFND1_WSP_MEDF

Samples
Default 4
Range 0 255

Wasp-LRF Median Filter (RNGFND1_WSP_MEDF)

Description

RNGFND1_WSP_MEDF enables a Median Filter, which is excellent at removing "Spikes" from the data.

Unlike a standard average, a median filter picks the middle value in a set. This ensures that a single bad reading (e.g., a laser reflection from a leaf or a piece of dust) doesn't cause the altitude estimate to jump.

RNGFND1_WSP_THR

Default -1
Range -1 255

Wasp-LRF Sensitivity Threshold (RNGFND1_WSP_THR)

Description

RNGFND1_WSP_THR controls the "Gain" of the laser receiver.

  • Higher Value: Higher sensitivity. Can see farther or over darker surfaces, but more prone to false readings from fog or dust.
  • -1: Automatic threshold adjustment.

RNGFND2_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to RNGFND1_ADDR.

RNGFND2_FUNCTION

Default 0
Range null

Rangefinder function

Note: This parameter functions identically to RNGFND1_FUNCTION.

RNGFND2_OFFSET

V
Default 0.0f
Range null

rangefinder offset

Note: This parameter functions identically to RNGFND1_OFFSET.

RNGFND2_ORIENT

Default AP_RANGEFINDER_DEFAULT_ORIENTATION
Range null

Rangefinder orientation

Note: This parameter functions identically to RNGFND1_ORIENT.

RNGFND2_PIN

Default -1
Range null

Rangefinder pin

Note: This parameter functions identically to RNGFND1_PIN.

RNGFND2_PWRRNG

m
Default 0
Range 0 32767

Powersave range

Note: This parameter functions identically to RNGFND1_PWRRNG.

RNGFND2_RMETRIC

Default 1
Range null

Ratiometric

Note: This parameter functions identically to RNGFND1_RMETRIC.

RNGFND2_SCALING

m/V
Default 3.0f
Range null

Rangefinder scaling

Note: This parameter functions identically to RNGFND1_SCALING.

RNGFND2_STOP_PIN

Default -1
Range null

Rangefinder stop pin

Note: This parameter functions identically to RNGFND1_STOP_PIN.

RNGFND2_TYPE

Default 0
Range null

Rangefinder type

Note: This parameter functions identically to RNGFND1_TYPE.

RNGFND3_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to RNGFND1_ADDR.

RNGFND3_FUNCTION

Default 0
Range null

Rangefinder function

Note: This parameter functions identically to RNGFND1_FUNCTION.

RNGFND3_OFFSET

V
Default 0.0f
Range null

rangefinder offset

Note: This parameter functions identically to RNGFND1_OFFSET.

RNGFND3_ORIENT

Default AP_RANGEFINDER_DEFAULT_ORIENTATION
Range null

Rangefinder orientation

Note: This parameter functions identically to RNGFND1_ORIENT.

RNGFND3_PIN

Default -1
Range null

Rangefinder pin

Note: This parameter functions identically to RNGFND1_PIN.

RNGFND3_PWRRNG

m
Default 0
Range 0 32767

Powersave range

Note: This parameter functions identically to RNGFND1_PWRRNG.

RNGFND3_RMETRIC

Default 1
Range null

Ratiometric

Note: This parameter functions identically to RNGFND1_RMETRIC.

RNGFND3_SCALING

m/V
Default 3.0f
Range null

Rangefinder scaling

Note: This parameter functions identically to RNGFND1_SCALING.

RNGFND3_STOP_PIN

Default -1
Range null

Rangefinder stop pin

Note: This parameter functions identically to RNGFND1_STOP_PIN.

RNGFND3_TYPE

Default 0
Range null

Rangefinder type

Note: This parameter functions identically to RNGFND1_TYPE.

RNGFND4_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to RNGFND1_ADDR.

RNGFND4_FUNCTION

Default 0
Range null

Rangefinder function

Note: This parameter functions identically to RNGFND1_FUNCTION.

RNGFND4_OFFSET

V
Default 0.0f
Range null

rangefinder offset

Note: This parameter functions identically to RNGFND1_OFFSET.

RNGFND4_ORIENT

Default AP_RANGEFINDER_DEFAULT_ORIENTATION
Range null

Rangefinder orientation

Note: This parameter functions identically to RNGFND1_ORIENT.

RNGFND4_PIN

Default -1
Range null

Rangefinder pin

Note: This parameter functions identically to RNGFND1_PIN.

RNGFND4_PWRRNG

m
Default 0
Range 0 32767

Powersave range

Note: This parameter functions identically to RNGFND1_PWRRNG.

RNGFND4_RMETRIC

Default 1
Range null

Ratiometric

Note: This parameter functions identically to RNGFND1_RMETRIC.

RNGFND4_SCALING

m/V
Default 3.0f
Range null

Rangefinder scaling

Note: This parameter functions identically to RNGFND1_SCALING.

RNGFND4_STOP_PIN

Default -1
Range null

Rangefinder stop pin

Note: This parameter functions identically to RNGFND1_STOP_PIN.

RNGFND4_TYPE

Default 0
Range null

Rangefinder type

Note: This parameter functions identically to RNGFND1_TYPE.

RNGFND5_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to RNGFND1_ADDR.

RNGFND5_FUNCTION

Default 0
Range null

Rangefinder function

Note: This parameter functions identically to RNGFND1_FUNCTION.

RNGFND5_OFFSET

V
Default 0.0f
Range null

rangefinder offset

Note: This parameter functions identically to RNGFND1_OFFSET.

RNGFND5_ORIENT

Default AP_RANGEFINDER_DEFAULT_ORIENTATION
Range null

Rangefinder orientation

Note: This parameter functions identically to RNGFND1_ORIENT.

RNGFND5_PIN

Default -1
Range null

Rangefinder pin

Note: This parameter functions identically to RNGFND1_PIN.

RNGFND5_PWRRNG

m
Default 0
Range 0 32767

Powersave range

Note: This parameter functions identically to RNGFND1_PWRRNG.

RNGFND5_RMETRIC

Default 1
Range null

Ratiometric

Note: This parameter functions identically to RNGFND1_RMETRIC.

RNGFND5_SCALING

m/V
Default 3.0f
Range null

Rangefinder scaling

Note: This parameter functions identically to RNGFND1_SCALING.

RNGFND5_STOP_PIN

Default -1
Range null

Rangefinder stop pin

Note: This parameter functions identically to RNGFND1_STOP_PIN.

RNGFND5_TYPE

Default 0
Range null

Rangefinder type

Note: This parameter functions identically to RNGFND1_TYPE.

RNGFND6_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to RNGFND1_ADDR.

RNGFND6_FUNCTION

Default 0
Range null

Rangefinder function

Note: This parameter functions identically to RNGFND1_FUNCTION.

RNGFND6_OFFSET

V
Default 0.0f
Range null

rangefinder offset

Note: This parameter functions identically to RNGFND1_OFFSET.

RNGFND6_ORIENT

Default AP_RANGEFINDER_DEFAULT_ORIENTATION
Range null

Rangefinder orientation

Note: This parameter functions identically to RNGFND1_ORIENT.

RNGFND6_PIN

Default -1
Range null

Rangefinder pin

Note: This parameter functions identically to RNGFND1_PIN.

RNGFND6_PWRRNG

m
Default 0
Range 0 32767

Powersave range

Note: This parameter functions identically to RNGFND1_PWRRNG.

RNGFND6_RMETRIC

Default 1
Range null

Ratiometric

Note: This parameter functions identically to RNGFND1_RMETRIC.

RNGFND6_SCALING

m/V
Default 3.0f
Range null

Rangefinder scaling

Note: This parameter functions identically to RNGFND1_SCALING.

RNGFND6_STOP_PIN

Default -1
Range null

Rangefinder stop pin

Note: This parameter functions identically to RNGFND1_STOP_PIN.

RNGFND6_TYPE

Default 0
Range null

Rangefinder type

Note: This parameter functions identically to RNGFND1_TYPE.

RNGFND7_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to RNGFND1_ADDR.

RNGFND7_FUNCTION

Default 0
Range null

Rangefinder function

Note: This parameter functions identically to RNGFND1_FUNCTION.

RNGFND7_OFFSET

V
Default 0.0f
Range null

rangefinder offset

Note: This parameter functions identically to RNGFND1_OFFSET.

RNGFND7_ORIENT

Default AP_RANGEFINDER_DEFAULT_ORIENTATION
Range null

Rangefinder orientation

Note: This parameter functions identically to RNGFND1_ORIENT.

RNGFND7_PIN

Default -1
Range null

Rangefinder pin

Note: This parameter functions identically to RNGFND1_PIN.

RNGFND7_PWRRNG

m
Default 0
Range 0 32767

Powersave range

Note: This parameter functions identically to RNGFND1_PWRRNG.

RNGFND7_RMETRIC

Default 1
Range null

Ratiometric

Note: This parameter functions identically to RNGFND1_RMETRIC.

RNGFND7_SCALING

m/V
Default 3.0f
Range null

Rangefinder scaling

Note: This parameter functions identically to RNGFND1_SCALING.

RNGFND7_STOP_PIN

Default -1
Range null

Rangefinder stop pin

Note: This parameter functions identically to RNGFND1_STOP_PIN.

RNGFND7_TYPE

Default 0
Range null

Rangefinder type

Note: This parameter functions identically to RNGFND1_TYPE.

RNGFND8_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to RNGFND1_ADDR.

RNGFND8_FUNCTION

Default 0
Range null

Rangefinder function

Note: This parameter functions identically to RNGFND1_FUNCTION.

RNGFND8_OFFSET

V
Default 0.0f
Range null

rangefinder offset

Note: This parameter functions identically to RNGFND1_OFFSET.

RNGFND8_ORIENT

Default AP_RANGEFINDER_DEFAULT_ORIENTATION
Range null

Rangefinder orientation

Note: This parameter functions identically to RNGFND1_ORIENT.

RNGFND8_PIN

Default -1
Range null

Rangefinder pin

Note: This parameter functions identically to RNGFND1_PIN.

RNGFND8_PWRRNG

m
Default 0
Range 0 32767

Powersave range

Note: This parameter functions identically to RNGFND1_PWRRNG.

RNGFND8_RMETRIC

Default 1
Range null

Ratiometric

Note: This parameter functions identically to RNGFND1_RMETRIC.

RNGFND8_SCALING

m/V
Default 3.0f
Range null

Rangefinder scaling

Note: This parameter functions identically to RNGFND1_SCALING.

RNGFND8_STOP_PIN

Default -1
Range null

Rangefinder stop pin

Note: This parameter functions identically to RNGFND1_STOP_PIN.

RNGFND8_TYPE

Default 0
Range null

Rangefinder type

Note: This parameter functions identically to RNGFND1_TYPE.

RNGFND9_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to RNGFND1_ADDR.

RNGFND9_FUNCTION

Default 0
Range null

Rangefinder function

Note: This parameter functions identically to RNGFND1_FUNCTION.

RNGFND9_OFFSET

V
Default 0.0f
Range null

rangefinder offset

Note: This parameter functions identically to RNGFND1_OFFSET.

RNGFND9_ORIENT

Default AP_RANGEFINDER_DEFAULT_ORIENTATION
Range null

Rangefinder orientation

Note: This parameter functions identically to RNGFND1_ORIENT.

RNGFND9_PIN

Default -1
Range null

Rangefinder pin

Note: This parameter functions identically to RNGFND1_PIN.

RNGFND9_PWRRNG

m
Default 0
Range 0 32767

Powersave range

Note: This parameter functions identically to RNGFND1_PWRRNG.

RNGFND9_RMETRIC

Default 1
Range null

Ratiometric

Note: This parameter functions identically to RNGFND1_RMETRIC.

RNGFND9_SCALING

m/V
Default 3.0f
Range null

Rangefinder scaling

Note: This parameter functions identically to RNGFND1_SCALING.

RNGFND9_STOP_PIN

Default -1
Range null

Rangefinder stop pin

Note: This parameter functions identically to RNGFND1_STOP_PIN.

RNGFND9_TYPE

Default 0
Range null

Rangefinder type

Note: This parameter functions identically to RNGFND1_TYPE.

RNGFNDA_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to RNGFND1_ADDR.

RNGFNDA_FUNCTION

Default 0
Range null

Rangefinder function

Note: This parameter functions identically to RNGFND1_FUNCTION.

RNGFNDA_OFFSET

V
Default 0.0f
Range null

rangefinder offset

Note: This parameter functions identically to RNGFND1_OFFSET.

RNGFNDA_ORIENT

Default AP_RANGEFINDER_DEFAULT_ORIENTATION
Range null

Rangefinder orientation

Note: This parameter functions identically to RNGFND1_ORIENT.

RNGFNDA_PIN

Default -1
Range null

Rangefinder pin

Note: This parameter functions identically to RNGFND1_PIN.

RNGFNDA_PWRRNG

m
Default 0
Range 0 32767

Powersave range

Note: This parameter functions identically to RNGFND1_PWRRNG.

RNGFNDA_RMETRIC

Default 1
Range null

Ratiometric

Note: This parameter functions identically to RNGFND1_RMETRIC.

RNGFNDA_SCALING

m/V
Default 3.0f
Range null

Rangefinder scaling

Note: This parameter functions identically to RNGFND1_SCALING.

RNGFNDA_STOP_PIN

Default -1
Range null

Rangefinder stop pin

Note: This parameter functions identically to RNGFND1_STOP_PIN.

RNGFNDA_TYPE

Default 0
Range null

Rangefinder type

Note: This parameter functions identically to RNGFND1_TYPE.

RNGFND_FILT

Hz
Default 0.5
Range 0 5

Rangefinder Low-Pass Filter (RNGFND_FILT)

Description

RNGFND_FILT smooths the "Jitter" from your distance sensor.

Many rangefinders (especially ultrasonic or low-cost Lidars) produce noisy data that can bounce around by several centimeters even when the drone is stationary. This filter removes that high-frequency noise to provide a stable altitude for the flight controller.

  • Higher Frequency: More responsive to rapid terrain changes, but more "jittery" altitude hold.
  • Lower Frequency: Very smooth altitude, but the drone might react slowly to a sudden obstacle or drop in terrain.

Tuning & Behavior

  • Default: 0.5 Hz.
  • Recommendation: Leave at 0.5 Hz for most sensors. If your drone is "bobbing" up and down rapidly while using the rangefinder, try lowering this to 0.25 Hz.
  • Disabled: Setting this to 0 disables the filter (raw data is used directly).

RNGFND_GNDCLEAR

cm
Default RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT
Range 5 127

Distance (in cm) from the range finder to the ground

Note: This parameter functions identically to RNGFND1_GNDCLEAR.

RNGFND_LANDING

Default 0
Range 0 1

Enable Rangefinder (Phase Specific) (RNGFND_LANDING)

Description

RNGFND_LANDING is the master switch for integrating distance sensor data into the Plane and QuadPlane flight logic.

Even if a rangefinder is configured and reporting data, ArduPilot will not use it for altitude control during landing or takeoff unless this parameter is set. This provides an safety layer, allowing pilots to verify sensor health before trusting it for critical landing maneuvers.

  • 0: Disabled. Rangefinder data is logged but ignored for flight control.
  • 1: Enabled. Used for landing approach, final flare, and VTOL assist.

Tuning & Behavior

  • Default: 0.
  • Safety: Only enable this after verifying that your rangefinder reports accurate distances and doesn't "glitch" or drop out while the vehicle is in motion.

RNGFND_LND_ORNT

Default 25
Range 0 38

Rangefinder Landing Orientation (RNGFND_LND_ORNT)

Description

RNGFND_LND_ORNT tells the landing controller which way the "Ground" sensor is facing.

  • Standard Plane/Copter: Set to 25 (Pitch 270 / Down).
  • Tailsitter (Landing on tail): Set to 4 (Back).

Tuning & Behavior

  • Default: 25 (Down).
  • Significance: If you have multiple rangefinders (e.g. one pointing forward for obstacle avoidance and one pointing down for landing), this parameter ensures the landing logic only listens to the downward-facing one.

RNGFND_MAX_CM

cm
Default 700

RNGFND_MAX_CM: Rangefinder maximum distance

Description

Maximum distance in centimeters that rangefinder can reliably read.

Values

  • Units: cm
  • Increment: 1
  • Default: 700

Description

This parameter defines the "Range Limit" for the rangefinder.

  • Function: Any reading above this value is ignored. If the sensor reports a value higher than this, ArduPilot treats it as "Out of Range" (e.g., looking into clear sky).
  • Usage: Set this to slightly less than the maximum distance listed in your sensor's datasheet to ensure high reliability. If your sensor is rated for 10 meters, setting this to 900 (9m) can prevent the autopilot from acting on weak, noisy signals at the edge of the sensor's capability.
  • Altitude Limit: If the drone flies higher than this altitude, the EKF will stop using the rangefinder for terrain following or precision landing and switch back to Barometer/GPS altitude.

RNGFND_MAX_RATE

Hz
Default 50
Range 0 200

Rangefinder Max Update Rate (RNGFND_MAX_RATE)

Description

RNGFND_MAX_RATE acts as a "Data Limiter" for your distance sensor.

While high-end Lidars can report data hundreds of times per second, sending all that data over a CAN or MAVLink network can cause congestion (too much traffic). This parameter ensures that the sensor node only sends a fresh measurement at this maximum frequency, keeping the network efficient.

  • 0: No limit (Send as fast as possible).
  • 50 (Default): Sufficient for most navigation and landing tasks.

Tuning & Behavior

  • Default: 50 Hz.
  • Recommendation: Leave at 50 for most setups. If you have multiple distance sensors on a slow CAN bus, you might reduce this to 20 to free up bandwidth.
  • Note: This is primarily used on AP_Periph CAN nodes.

RNGFND_MIN_CM

cm
Default 20

RNGFND_MIN_CM: Rangefinder minimum distance

Description

Minimum distance in centimeters that rangefinder can reliably read.

Values

  • Units: cm
  • Increment: 1
  • Default: 20

Description

This parameter defines the "Blind Spot" of your rangefinder.

  • Function: Any distance reading reported by the sensor that is less than this value will be ignored by the autopilot and treated as "Out of Range."
  • Why it matters: Most Sonar and Lidar sensors have a physical limit where they cannot distinguish between zero distance and a very close object. If this value is set too low, the drone might think it is at ground level while still several inches in the air, leading to a premature motor cut or a hard landing.

RNGFND_POS

m
Default 0
Range -5 5

Rangefinder Position Offset (RNGFND_POS)

Description

RNGFND_POS (often appearing as RNGFND1_POS_X/Y/Z) tells the autopilot exactly where the sensor is mounted on the frame.

Correctly setting the Z-offset is particularly important for landing. If the sensor is mounted 10cm below the center of gravity but this is set to 0, the EKF will think the drone is 10cm higher than it actually is, potentially causing a hard landing.

  • X: Positive = Forward.
  • Y: Positive = Right.
  • Z: Positive = Down.

Tuning & Behavior

  • Default: 0.
  • Measurement: Measure from the flight controller (center) to the face of the sensor.

RNGFND_SQ_MIN

%
Default 0
Range 0 100

Rangefinder Minimum Signal Quality (RNGFND_SQ_MIN)

Description

RNGFND_SQ_MIN defines the "Certainty Threshold" for your distance measurements.

Many sensors (especially acoustics/sonars used in ArduSub) report a confidence level or signal quality. If the return signal is weak (due to bubbles, silt, or extreme angles), the sensor may report a "Confidence" percentage. This parameter tells the autopilot to reject any measurement if the sensor's own confidence is below this value.

  • 0: Trust all data (Default).
  • 50: Reject data if the sensor is less than 50% certain.

Tuning & Behavior

  • Recommendation: Set to 50% if you find your depth or altitude readings "glitching" in difficult environments.
  • Context: This is functionally similar to RNGFND1_SNR_MIN but uses a normalized percentage (0-100) instead of a raw SNR value.