MAVLINKHUD

Overview

The BCN parameter group configures the Indoor Beacon positioning system. This driver allows ArduPilot to use range-based beacon systems (like Pozyx, Marvelmind, or Nooploop) as a substitute for GPS in indoor or GPS-denied environments.

The EKF (State Estimator) fuses distance measurements from the vehicle to known fixed beacons to calculate position (PosHold, Loiter, Auto).

Key Concepts

1. Beacon Origin

Unlike GPS, beacons operate in a local coordinate frame (X, Y, Z relative to a "Master" beacon). To fly missions, you often need to anchor this local frame to a global Geodetic coordinate (Lat/Lon).

  • BCN_LATITUDE / BCN_LONGITUDE / BCN_ALT: Sets the global position of the system origin (usually the 0,0,0 point of the beacon network).

2. Alignment (BCN_ORIENT_YAW)

You must tell the autopilot how the beacon network's "North" aligns with True North (or the frame's heading 0).

  • If the beacon system's X-axis points East, you must set the orientation offset so the EKF aligns correctly.

Parameter Breakdown

  • BCN_TYPE: Driver selection (0=Disabled, 1=Pozyx, 2=Marvelmind, etc.).
  • BCN_ORIENT_YAW: Rotation of the beacon network relative to True North.

Integration Guide

Setup

  1. Place Beacons: Set up your anchors/beacons in the room.
  2. Map: Use the manufacturer's software to map the beacon positions and freeze the map.
  3. Config: Set BCN_TYPE and EK3_SRC1_POSXY = Beacon.
  4. Align: Use a compass or known heading to align the vehicle and check if the reported position on the GCS map moves in the correct direction when you move the drone.

Developer Notes

  • Library: libraries/AP_Beacon
  • Usage: Fused by AP_NavEKF3 as a range or position source.

BCN_ALT

m
Default 0
Range 0 10000

Beacon origin's altitude above sealevel in meters (BCN_ALT)

Description

This parameter sets the Altitude above Mean Sea Level (AMSL) in meters for the beacon system's local origin $(0, 0, 0)$.

This establishes the vertical reference ("Z" axis anchor) for the indoor positioning system. By knowing the real-world altitude of the floor (or wherever the beacon zero-point is defined), the autopilot can report accurate AMSL altitude to the Ground Control Station and other systems.

The Mathematics

$$ Alt\_{global} = BCN\_ALT + Z\_{local} $$

(Note: The sign of $Z\_{local}$ depends on whether the beacon system uses NED (North-East-Down) or NEU (North-East-Up) coordinates, but the driver typically handles this normalization).

The Engineer's View

In AP_Beacon::get_origin(), this value is multiplied by 100 to convert it to centimeters (int32_t cm) used by ArduPilot's Location class for altitude.

Tuning & Behavior

  • Default Value: 0
  • Range: 0 to 10000 meters
  • Setting: Set this to the known AMSL altitude of the beacon origin.
  • Dependencies: Works in tandem with BCN_LATITUDE and BCN_LONGITUDE.

BCN_LATITUDE

deg
Default 0
Range -90 90

Beacon origin's latitude (BCN_LATITUDE)

Description

This parameter sets the global Latitude (in degrees) that corresponds to the local origin $(0, 0, 0)$ of the beacon system.

Beacon systems typically operate in a local coordinate frame (X/Y in meters). By providing the real-world GPS coordinates of the beacon system's origin, the autopilot can convert these local measurements into global Latitude and Longitude. This allows you to fly autonomous missions using GPS waypoints even when navigating purely via indoor beacons.

The Mathematics

The autopilot uses this value as the reference point for a Local-to-Global projection (typically an Equirectangular projection or WGS84 calculation depending on the library used).

$$ Lat\_{global} = BCN\_LAT + \Delta Lat(Y\_{local}) $$

The Engineer's View

In AP_Beacon::get_origin(), this value is multiplied by $1.0 \times 10^7$ to convert it to the internal integer format (int32_t scaled by 1e7) used by ArduPilot's Location class.

It is critical that this value is non-zero if you want AP_Beacon::get_origin() to return true, which is often a prerequisite for the EKF to accept the beacon data as an absolute position source.

Tuning & Behavior

  • Default Value: 0
  • Range: -90 to +90 Degrees
  • Setting: Set this to the precise latitude of the Beacon System's (0,0) point. You can measure this by placing a GPS-equipped phone or drone at the origin point outdoors, or by using Google Maps satellite view.
  • Dependencies: Works in tandem with BCN_LONGITUDE and BCN_ALT.

BCN_LONGITUDE

deg
Default 0
Range -180 180

Beacon origin's longitude (BCN_LONGITUDE)

Description

This parameter sets the global Longitude (in degrees) that corresponds to the local origin $(0, 0, 0)$ of the beacon system.

Together with BCN_LATITUDE, it anchors the local Cartesian coordinate system (X, Y) of the indoor positioning system to the Earth's geodetic frame. This allows the EKF (Extended Kalman Filter) to output a global position estimate even when relying on local beacons.

The Mathematics

The autopilot uses this value as the reference point for a Local-to-Global projection.

$$ Lon\_{global} = BCN\_LONG + \Delta Lon(X\_{local}) $$

Note that longitude scaling varies with latitude ($ \cos(Lat) $), which the internal projection functions handle automatically.

The Engineer's View

In AP_Beacon::get_origin(), this value is multiplied by $1.0 \times 10^7$ to convert it to the internal integer format (int32_t scaled by 1e7) used by ArduPilot's Location class.

Tuning & Behavior

  • Default Value: 0
  • Range: -180 to +180 Degrees
  • Setting: Set this to the precise longitude of the Beacon System's (0,0) point.
  • Dependencies: Works in tandem with BCN_LATITUDE and BCN_ALT.

BCN_ORIENT_YAW

deg
Default 0
Range -180 +180

Beacon systems rotation from north in degrees (BCN_ORIENT_YAW)

Description

This parameter defines the orientation of the beacon system's local "X" axis relative to True North.

If your beacon system is set up such that its "Forward" (X-axis) points East instead of North, you would set this to 90 degrees. This aligns the local coordinate grid with the global compass directions, ensuring that "Flying North" in the beacon frame corresponds to "Flying North" in the real world.

The Mathematics

The autopilot applies a 2D rotation matrix to the beacon's local (X, Y) coordinates before adding them to the global origin.

$$ \begin{bmatrix} X\_{aligned} \ Y\_{aligned} \end{bmatrix} = \begin{bmatrix} \cos(\theta) & -\sin(\theta) \ \sin(\theta) & \cos(\theta) \end{bmatrix} \begin{bmatrix} X\_{raw} \ Y\_{raw} \end{bmatrix} $$

Where $ \theta $ is BCN_ORIENT_YAW.

The Engineer's View

In AP_Beacon_Backend::correct_position(), this yaw rotation is applied to the raw position reported by the driver. It allows for arbitrary alignment of the physical beacon anchors without needing to reinstall them to face exactly North.

Tuning & Behavior

  • Default Value: 0 (Beacon X-axis points North)
  • Range: -180 to +180 Degrees
  • Positive Value: Rotates the system Clockwise (e.g., +90 means X points East).
  • Negative Value: Rotates the system Counter-Clockwise (e.g., -90 means X points West).
  • Tuning: If your vehicle flies sideways when you command it forward (in Loiter/PosHold), or if the "Map" position moves incorrectly, this parameter is likely 90 or 180 degrees off.

BCN_TYPE

Option
Default 0
Range 0 10

Beacon based position estimation device type (BCN_TYPE)

Description

This parameter enables the Beacon driver and selects the specific hardware vendor connected to the autopilot. Beacon systems (often called Indoor GPS) provide high-precision position data (X, Y, Z) for environments where standard GPS is unavailable, such as indoors or under heavy canopy.

Setting this parameter allocates the necessary driver memory and starts the communication backend.

The Mathematics

The value maps directly to a driver backend instantiation factory:

  • 0: None (Disabled)
  • 1: Pozyx (UWB)
  • 2: Marvelmind (Ultrasound)
  • 3: Nooploop (UWB)
  • 10: SITL (Software In The Loop simulation)

The Engineer's View

In AP_Beacon::init(), this parameter is read to switch-case the construction of _driver.

  • Type::Pozyx -> AP_Beacon_Pozyx
  • Type::Marvelmind -> AP_Beacon_Marvelmind
  • etc.

If set to 0, AP_Beacon::enabled() returns false, effectively bypassing the entire library.

Tuning & Behavior

  • Reboot Required: Yes. Changing this parameter requires a reboot to initialize the correct driver and allocate resources.
  • Dependencies: Enabling this is the first step. You must also configure the beacon's Origin (BCN_LATITUDE, etc.) if you want the vehicle to report global coordinates, or use EK3_SRCx parameters to tell the EKF to use Beacons as a position source.