MAVLINKHUD

Overview

The PRX parameter group configures the Proximity Sensors used for obstacle detection and avoidance. This library supports 360-degree scanners (Lidar), simple rangefinders used as proximity sensors, and virtual proximity data from companion computers.

The data from these sensors is fed into the AVOID and OA (Object Avoidance) libraries to prevent collisions.

Key Concepts

1. Sensor Types (PRXn_TYPE)

ArduPilot supports up to 5 proximity sensor instances.

  • 1 (LightWareSF40): 360-degree scanning Lidar.
  • 2 (RPLidarA2/A3): Popular scanning Lidars.
  • 4 (DroneCAN): CAN-based proximity sensors.
  • 15 (RangeFinder): Converts a standard downward or forward-facing Lidar (RNGFND_) into a proximity source.

2. Ignore Zones (PRXn_IGN_...)

Often, the drone's own frame, landing gear, or antennas might block the sensor's field of view, causing false obstacle detections.

  • PRXn_IGN_ANG: The center angle of the zone to ignore.
  • PRXn_IGN_WID: The width (degrees) of the zone to ignore.

3. Vertical Limits (PRX_ALT_MIN)

Defines the minimum altitude required for the sensors to be active, preventing the ground from being seen as an obstacle during takeoff.

Parameter Breakdown

  • PRX1_TYPE: Driver selection for first sensor.
  • PRX1_MAX: Maximum effective range (meters).
  • PRX_FILT: Low-pass filter for proximity data (Hz).

Integration Guide

  1. Hardware: Mount the Lidar on top or bottom with a clear 360-degree view.
  2. Enable: Set PRX1_TYPE.
  3. Clean View: Look at the "Proximity" window in Mission Planner. If you see "phantom" obstacles that move with the drone, use IGN_ANG to mask out the propeller arms or frame.

Developer Notes

  • Library: libraries/AP_Proximity.
  • Output: Generates the "Proximity" MAVLink message and logs to the PRX dataflash message.

PRX1_ADDR

Default 0
Range 0 127

Proximity Sensor Bus Address (PRX1_ADDR)

Description

PRX1_ADDR identifies the unique "Hardware Address" of your proximity sensor on the shared I2C or DroneCAN bus.

This allows you to connect multiple sensors of the same type to the same bus without conflict.

  • 0: Auto-detection.
  • 1-127: Specific hardware address.

PRX1_IGN_ANG1

deg
Default 0
Range 0 360

Proximity Ignore Angle (PRX1_IGN_ANG1)

Description

PRX1_IGN_ANG1 (and ANG2-ANG4) defines the center of a "Blind Zone" for your proximity sensor.

This is used to prevent the drone from reacting to its own structure (like landing gear, arms, or GPS masts) that might be in the sensor's line of sight. By telling the autopilot to "ignore" a specific angle, you avoid false obstacle detections.

  • Units: Degrees (0 to 360).
  • Reference: 0 is forward, 90 is right, 180 is back, 270 is left.

Tuning & Behavior

  • Default: 0.
  • Integration: Use this in combination with PRX1_IGN_WID1 to define the width of the excluded sector.

PRX1_IGN_ANG2

deg
Default 0
Range 0 360

Proximity sensor ignore angle 2

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX1_IGN_ANG3

deg
Default 0
Range 0 360

Proximity sensor ignore angle 3

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX1_IGN_ANG4

deg
Default 0
Range 0 360

Proximity sensor ignore angle 4

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX1_IGN_WID1

deg
Default 0
Range 0 127

Proximity Ignore Width (PRX1_IGN_WID1)

Description

PRX1_IGN_WID1 defines the size of the "Blind Zone" sector centered on PRX1_IGN_ANG1.

If you have a 10-degree wide arm in the sensor's path, you would set the center angle to the arm's position and this width to 10. The autopilot will then ignore any data reported within 5 degrees on either side of the center.

Tuning & Behavior

  • Default: 0.
  • Safety: Do not set the width unnecessarily large, as you might hide real obstacles from the avoidance system.

PRX1_IGN_WID2

deg
Default 0
Range 0 127

Proximity sensor ignore width 2

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX1_IGN_WID3

deg
Default 0
Range 0 127

Proximity sensor ignore width 3

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX1_IGN_WID4

deg
Default 0
Range 0 127

Proximity sensor ignore width 4

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX1_MAX

m
Default 0
Range 0 500

Proximity Maximum Range (PRX1_MAX)

Description

PRX1_MAX defines the "Horizon" for your drone's obstacle avoidance system.

If the sensor reports an object farther away than this value, the autopilot ignores it. This is important to filter out noise at the edge of the sensor's capability or to ignore distant objects that aren't a threat.

  • 0: Use sensor default. (Recommended for most digital sensors).
  • 1-500: Range in meters.

Tuning & Behavior

  • Default: 0.
  • Recommendation: If you notice your drone "jerking" or reacting to "ghost" obstacles in the distance, set this to 80% of the sensor's physical max range (e.g., set to 16 for a 20m Lidar).

PRX1_MIN

m
Default 0
Range 0 500

Proximity Minimum Range (PRX1_MIN)

Description

PRX1_MIN defines the "Blind Spot" around your drone.

If the sensor reports an object closer than this value, the autopilot ignores it. This is critical to prevent the drone from being "scared" of its own frame, propellers, or mounting brackets if they are within the sensor's field of view.

  • 0: Use sensor default. (Recommended).
  • Value (m): Set this to slightly more than the distance from the sensor to the edge of your drone's props.

Tuning & Behavior

  • Default: 0.
  • Safety: Setting this too low may cause the drone to detect its own frame as an obstacle, preventing it from moving.

PRX1_ORIENT

Default 0
Range 0 1

Proximity Orientation (PRX1_ORIENT)

Description

PRX1_ORIENT tells ArduPilot if your 360-degree Lidar is mounted normally or upside down.

  • 0: Default (Right-side up).
  • 1: Upside Down.

Tuning & Behavior

  • Default: 0.
  • Action: If your obstacle avoidance seems to react to objects on the wrong side (left instead of right), your sensor might be mounted upside down without this parameter being set correctly.

PRX1_RECV_ID

Default 0
Range 0 255

Proximity MAVLink System ID (PRX1_RECV_ID)

Description

PRX1_RECV_ID specifies the source of the proximity data when using a MAVLink-based sensor (like an OpenMV or a specialized companion computer script).

It tells the autopilot: "Only listen to DISTANCE_SENSOR messages from this specific MAVLink system ID."

  • 0 (Default): Listen to all MAVLink proximity sources.
  • 1-255: Listen only to this specific System ID.

PRX1_TYPE

Default 0
Range 0 18

Proximity type (PRX1_TYPE)

Description

PRX1_TYPE enables a 360-degree Lidar or Radar for Object Avoidance.

Unlike a Rangefinder (which is usually a 1D single-point distance sensor), a Proximity sensor scans a sector or a full circle to build a map of obstacles around the vehicle. This data is used by the AVOID (Object Avoidance) library to stop before hitting objects or path-plan around them.

  • 0: None.
  • 2: MAVLink. Data sent from a Companion Computer.
  • 4: RangeFinder. Uses an existing RNGFND instance (turned into a proximity sensor).
  • 5: RPLidarA2. Common 360 Lidar.
  • 6: TeraRangerTowerEvo. 8-zone ToF array.
  • 14: DroneCAN.
  • 16: LD06. Inexpensive 360 Lidar.

The Engineer's View

Defined in AP_Proximity.
Enabling this allocates the driver. The driver then populates the AP_Proximity_Boundary_3D structure, which the Avoidance library (AC_Avoid) queries during flight.

Tuning & Behavior

  • Default Value: 0 (Disabled).
  • Reboot Required: Yes.
  • Orientation: 360-degree Lidars must be mounted flat. Check PRX1_ORIENT if mounted upside down.

PRX1_YAW_CORR

deg
Default 0
Range -180 180

Proximity Sensor Yaw Correction (PRX1_YAW_CORR)

Description

PRX1_YAW_CORR allows you to digitally "Rotate" your proximity sensor if it wasn't mounted perfectly straight.

For obstacle avoidance to work, the autopilot must know exactly which direction each sensor reading corresponds to. If your Lidar is mounted 90 degrees to the right, you set this to 90 so the autopilot knows to shift all incoming data accordingly.

Tuning & Behavior

  • Default: 0.
  • Calibration: Point your drone at a known obstacle (like a wall) and check the proximity radar in your GCS. If the wall appears to the side instead of directly in front, adjust this parameter until they match.
  • Significance: Critical for accurate avoidance maneuvers; if this is off, the drone might steer into an obstacle while trying to avoid it.

PRX2_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to PRX1_ADDR.

PRX2_IGN_ANG1

deg
Default 0
Range 0 360

Proximity sensor ignore angle 1

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX2_IGN_ANG2

deg
Default 0
Range 0 360

Proximity sensor ignore angle 2

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX2_IGN_ANG3

deg
Default 0
Range 0 360

Proximity sensor ignore angle 3

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX2_IGN_ANG4

deg
Default 0
Range 0 360

Proximity sensor ignore angle 4

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX2_IGN_WID1

deg
Default 0
Range 0 127

Proximity sensor ignore width 1

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX2_IGN_WID2

deg
Default 0
Range 0 127

Proximity sensor ignore width 2

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX2_IGN_WID3

deg
Default 0
Range 0 127

Proximity sensor ignore width 3

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX2_IGN_WID4

deg
Default 0
Range 0 127

Proximity sensor ignore width 4

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX2_MAX

m
Default 0.0f
Range 0 500

Proximity maximum range

Note: This parameter functions identically to PRX1_MAX.

PRX2_MIN

m
Default 0.0f
Range 0 500

Proximity minimum range

Note: This parameter functions identically to PRX1_MIN.

PRX2_ORIENT

Default 0
Range null

Proximity sensor orientation

Note: This parameter functions identically to PRX1_ORIENT.

PRX2_TYPE

Default 0
Range null

Proximity type

Note: This parameter functions identically to PRX1_TYPE.

PRX2_YAW_CORR

deg
Default 0
Range -180 180

Proximity sensor yaw correction

Note: This parameter functions identically to PRX1_YAW_CORR.

PRX3_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to PRX1_ADDR.

PRX3_IGN_ANG1

deg
Default 0
Range 0 360

Proximity sensor ignore angle 1

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX3_IGN_ANG2

deg
Default 0
Range 0 360

Proximity sensor ignore angle 2

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX3_IGN_ANG3

deg
Default 0
Range 0 360

Proximity sensor ignore angle 3

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX3_IGN_ANG4

deg
Default 0
Range 0 360

Proximity sensor ignore angle 4

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX3_IGN_WID1

deg
Default 0
Range 0 127

Proximity sensor ignore width 1

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX3_IGN_WID2

deg
Default 0
Range 0 127

Proximity sensor ignore width 2

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX3_IGN_WID3

deg
Default 0
Range 0 127

Proximity sensor ignore width 3

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX3_IGN_WID4

deg
Default 0
Range 0 127

Proximity sensor ignore width 4

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX3_MAX

m
Default 0.0f
Range 0 500

Proximity maximum range

Note: This parameter functions identically to PRX1_MAX.

PRX3_MIN

m
Default 0.0f
Range 0 500

Proximity minimum range

Note: This parameter functions identically to PRX1_MIN.

PRX3_ORIENT

Default 0
Range null

Proximity sensor orientation

Note: This parameter functions identically to PRX1_ORIENT.

PRX3_TYPE

Default 0
Range null

Proximity type

Note: This parameter functions identically to PRX1_TYPE.

PRX3_YAW_CORR

deg
Default 0
Range -180 180

Proximity sensor yaw correction

Note: This parameter functions identically to PRX1_YAW_CORR.

PRX4_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to PRX1_ADDR.

PRX4_IGN_ANG1

deg
Default 0
Range 0 360

Proximity sensor ignore angle 1

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX4_IGN_ANG2

deg
Default 0
Range 0 360

Proximity sensor ignore angle 2

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX4_IGN_ANG3

deg
Default 0
Range 0 360

Proximity sensor ignore angle 3

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX4_IGN_ANG4

deg
Default 0
Range 0 360

Proximity sensor ignore angle 4

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX4_IGN_WID1

deg
Default 0
Range 0 127

Proximity sensor ignore width 1

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX4_IGN_WID2

deg
Default 0
Range 0 127

Proximity sensor ignore width 2

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX4_IGN_WID3

deg
Default 0
Range 0 127

Proximity sensor ignore width 3

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX4_IGN_WID4

deg
Default 0
Range 0 127

Proximity sensor ignore width 4

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX4_MAX

m
Default 0.0f
Range 0 500

Proximity maximum range

Note: This parameter functions identically to PRX1_MAX.

PRX4_MIN

m
Default 0.0f
Range 0 500

Proximity minimum range

Note: This parameter functions identically to PRX1_MIN.

PRX4_ORIENT

Default 0
Range null

Proximity sensor orientation

Note: This parameter functions identically to PRX1_ORIENT.

PRX4_TYPE

Default 0
Range null

Proximity type

Note: This parameter functions identically to PRX1_TYPE.

PRX4_YAW_CORR

deg
Default 0
Range -180 180

Proximity sensor yaw correction

Note: This parameter functions identically to PRX1_YAW_CORR.

PRX5_ADDR

Default 0
Range 0 127

Bus address of sensor

Note: This parameter functions identically to PRX1_ADDR.

PRX5_IGN_ANG1

deg
Default 0
Range 0 360

Proximity sensor ignore angle 1

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX5_IGN_ANG2

deg
Default 0
Range 0 360

Proximity sensor ignore angle 2

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX5_IGN_ANG3

deg
Default 0
Range 0 360

Proximity sensor ignore angle 3

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX5_IGN_ANG4

deg
Default 0
Range 0 360

Proximity sensor ignore angle 4

Note: This parameter functions identically to PRX1_IGN_ANG1.

PRX5_IGN_WID1

deg
Default 0
Range 0 127

Proximity sensor ignore width 1

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX5_IGN_WID2

deg
Default 0
Range 0 127

Proximity sensor ignore width 2

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX5_IGN_WID3

deg
Default 0
Range 0 127

Proximity sensor ignore width 3

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX5_IGN_WID4

deg
Default 0
Range 0 127

Proximity sensor ignore width 4

Note: This parameter functions identically to PRX1_IGN_WID1.

PRX5_MAX

m
Default 0.0f
Range 0 500

Proximity maximum range

Note: This parameter functions identically to PRX1_MAX.

PRX5_MIN

m
Default 0.0f
Range 0 500

Proximity minimum range

Note: This parameter functions identically to PRX1_MIN.

PRX5_ORIENT

Default 0
Range null

Proximity sensor orientation

Note: This parameter functions identically to PRX1_ORIENT.

PRX5_TYPE

Default 0
Range null

Proximity type

Note: This parameter functions identically to PRX1_TYPE.

PRX5_YAW_CORR

deg
Default 0
Range -180 180

Proximity sensor yaw correction

Note: This parameter functions identically to PRX1_YAW_CORR.

PRX_ALT_MIN

m
Default 1.0
Range 0 10

Proximity Minimum Altitude (PRX_ALT_MIN)

Description

PRX_ALT_MIN defines the "Activation Floor" for object avoidance.

Proximity sensors (like 360-degree Lidars) can sometimes "see" the ground when the drone is very low or during takeoff/landing, causing false obstacle detections. This parameter tells the autopilot to ignore all proximity data until the drone has climbed above this altitude.

  • Default Value: 1.0 meter.
  • Safety: This ensures the drone doesn't try to "dodge" the grass or its own landing pad during the critical phases of flight.

Tuning & Behavior

  • Default: 1.0.
  • Note: This requires a valid downward-facing Rangefinder (Lidar/Sonar) to know the altitude accurately. If no rangefinder is present, this parameter may not function as expected.

PRX_BAUDRATE

Default 0
Range 1 1000000

Proximity Sensor Baud Rate (PRX_BAUDRATE)

Description

PRX_BAUDRATE sets the communication speed for proximity sensors (like Lidars) that connect via a Serial (UART) port.

This parameter is primarily found on AP_Periph nodes that are being used as CAN bridges for serial sensors.

Tuning & Behavior

  • Default: 0 (Use driver default).
  • Common Values: 115200 (Most common), 921600 (High speed).
  • Reboot Required: Yes.

PRX_FILT

Hz
Default 0.25
Range 0 20

Proximity Data Low-Pass Filter (PRX_FILT)

Description

PRX_FILT smooths out the "noisy" data from proximity sensors (like Lidars).

Lidars often report small, random fluctuations in distance. Without filtering, these fluctuations can cause the drone to twitch or make small steering corrections even when stationary. This filter removes that high-frequency noise, providing a stable "Boundary" for the obstacle avoidance algorithm to work with.

  • Higher Frequency: Faster reaction to obstacles, but more twitchy.
  • Lower Frequency (Default): Very smooth movement, but may react slightly slower to a fast-moving object.

Tuning & Behavior

  • Default: 0.25 Hz.
  • Recommendation: Leave at 0.25 Hz for most setups. If you find your drone is too slow to stop for obstacles, try increasing to 1.0 Hz.

PRX_IGN_GND

Default 0
Range 0 1

Proximity Ignore Ground (PRX_IGN_GND)

Description

PRX_IGN_GND prevents the drone from being "Scared" of the floor.

When a drone is close to the ground, its Lidar often sees reflections from the dirt, grass, or landing pad as "Obstacles." This can prevent the drone from landing or cause it to jump away during takeoff. When enabled, this feature uses a downward rangefinder to determine exactly where the ground is and ignores any proximity data that is too close to that surface.

PRX_LOG_RAW

Default 0
Range 0 1

Proximity Raw Data Logging (PRX_LOG_RAW)

Description

PRX_LOG_RAW is a developer and troubleshooting tool.

When enabled, the autopilot records every individual measurement from the proximity sensor (e.g. all 360 degrees of data from a Lidar) into the internal DataFlash log.

  • 0: Disabled (Default). Only the processed "Boundary" data is logged.
  • 1: Enabled. Logs the full raw data stream.

Tuning & Behavior

  • Warning: This creates extremely large log files.
  • Usage: Only enable this if you are debugging a sensor issue or verifying that your ignore sectors (PRX1_IGN_ANG1) are correctly configured.

PRX_PORT

Default 0
Range 0 10

Proximity Sensor Port (PRX_PORT)

Description

PRX_PORT is used on AP_Periph nodes to map a physical UART port to the proximity sensor driver.

If you are using a CAN-based peripheral node to bridge a serial Lidar to the main flight controller, this parameter tells the peripheral node which of its own serial ports is connected to the Lidar.

Tuning & Behavior

  • Default: 0.
  • Setup: Refer to the wiring diagram for your specific AP_Periph hardware (e.g., Matek or CUAV CAN nodes) to find the correct port number.
  • Reboot Required: Yes.

PRX_MAX_RATE: Proximity Sensor max rate

Description

This is the maximum rate we send Proximity Sensor data in Hz. Zero means no limit.

Values

  • Range: 0 to 200
  • Units: Hz
  • Default: 50

Description

This parameter limits the frequency of proximity data messages sent by the AP_Periph device.

  • Purpose: Prevents high-speed Lidar sensors from flooding the CAN bus or telemetry link with too much data.
  • 50Hz (Default): A good balance for obstacle avoidance.
  • 0: Sends data as fast as the sensor can read (can be >1000Hz for some Lidars, which may choke the bus).

Source Code

ardupilot/Tools/AP_Periph/Parameters.cpp