MAVLINKHUD

Overview

The BRD parameter group contains Hardware Abstraction Layer (HAL) settings. These parameters configure the low-level behavior of the flight controller board itself, independent of the vehicle type (Copter/Plane/Rover).

It handles IO processor communication, safety switches, internal heating, SD card speeds, and board-specific voltage monitoring.

Key Concepts

1. Safety Switch (BRD_SAFETY_DEFLT / BRD_SAFETY_MASK)

Controls the behavior of the hardware Safety Switch (often on the GPS module).

  • Default: Determines if the safety switch is active at boot.
  • Mask: Allows specific channels (e.g., landing gear, gimbal) to move even when the safety switch is active (safe).

2. IMU Heater (BRD_HEAT_...)

Many high-end boards (Cube, Durandal) have internal heating resistors to keep the IMU at a constant temperature (usually 45-60°C) for consistent calibration.

  • Tuning: BRD_HEAT_P/I controls the PID loop for the heater.

3. IO Processor (BRD_IO_ENABLE)

Some boards (Pixhawk 1/Cube) use a separate co-processor (IOMCU) for PWM output safety.

  • BRD_IO_ENABLE: Must be 1 to use the MAIN/AUX output split on IOMCU-equipped boards.

4. SD Card (BRD_SD_SLOWDOWN)

If you have logging issues or bad SD cards, this parameter can slow down the SPI clock to the card to improve reliability (at the cost of speed).

Parameter Breakdown

  • BRD_TYPE: Autodetected board ID. Read-only.
  • BRD_SERIAL_NUM: Unique ID of the board.
  • BRD_BOOT_DELAY: Delays bootup to allow peripherals (sensors) to power up and stabilize.
  • BRD_PWM_VOLT_SEL: Selects 3.3V or 5V for servo rail output (if supported by hardware hardware).

Integration Guide

Disabling the Safety Switch

If you don't have a switch installed and the board refuses to arm ("Hardware Safety Switch"):

  1. Set BRD_SAFETY_DEFLT = 0.
  2. Reboot.

SD Card Issues

If you see "No SD Card" or logging gaps:

  1. Try BRD_SD_SLOWDOWN = 1 or higher.

Developer Notes

  • Library: libraries/AP_HAL_ChibiOS (mostly).
  • Scope: These are often set by hwdef.dat at compile time but can be overridden.

BRD_ALT_CONFIG

Default 0
Range 0 10

Alternative HW config (BRD_ALT_CONFIG)

Description

Selects pre-defined alternative pin assignments or hardware options for specific boards. Refer to your board's documentation for valid values.

BRD_BOOT_DELAY

ms
Default 0
Range 0 10000

Boot delay (BRD_BOOT_DELAY)

Description

Delays the main autopilot initialization process on startup. This is helpful if certain external sensors or peripherals (like some GPS modules) need more time to power up before ArduPilot attempts to communicate with them.

BRD_HEAT_I

Default 0.1
Range 0 1

Board Heater I gain (BRD_HEAT_I)

Description

Compensates for long-term temperature steady-state errors in the IMU heater.

BRD_HEAT_IMAX

Default 100
Range 0 100

Board Heater IMAX (BRD_HEAT_IMAX)

Description

Limits the maximum authority of the heater's integral term to prevent "wind-up" and overheating.

BRD_HEAT_LOWMGN

degC
Default 0
Range 0 20

Board heater temp lower margin (BRD_HEAT_LOWMGN)

Description

Safety margin for heater-based arming checks. The aircraft will refuse to arm until the IMU has reached at least (BRD_HEAT_TARG - BRD_HEAT_LOWMGN).

BRD_HEAT_P

Default 50
Range 1 500

Board Heater P gain (BRD_HEAT_P)

Description

Determines how aggressively the heater reacts to temperature deviations from the target.

BRD_HEAT_TARG

degC
Default -1
Range -1 80

Board heater temperature target (BRD_HEAT_TARG)

Description

Target temperature for the integrated IMU heater. Keeping the IMU at a constant temperature reduces thermal drift and improves sensor accuracy, especially in cold environments.

BRD_IO_DSHOT

Default 0
Range 0 1

Load DShot FW on IO (BRD_IO_DSHOT)

Description

Enables DShot digital ESC protocol support on the primary I/O outputs (channels 1-8) by loading specialized firmware onto the IOMCU.

BRD_IO_ENABLE

Default 1
Range 0 2

Enable IO co-processor (BRD_IO_ENABLE)

Description

Controls the integrated I/O co-processor (IOMCU) found on many flight controllers (e.g., Pixhawk). The IOMCU handles low-level PWM output and safety switch logic.

Tuning & Behavior

  • Default Value: 1 (Enabled)
  • Values: 0:Disabled, 1:Enabled, 2:EnableNoFWUpdate
  • Requires reboot to take effect.

BRD_OPTIONS

Default 0

Board options (BRD_OPTIONS)

Description

Bitmask for low-level hardware configuration options and developer features.

Tuning & Behavior

  • Default Value: 0 (Standard)
  • Bitmask:
    • Bit 0: Enable hardware watchdog
    • Bit 1: Disable MAVftp
    • Bit 3: Enable Debug Pins
    • Bit 7: Skip board validation

BRD_PWM_VOLT_SEL

V
Default 0
Range 0 1

Set PWM Out Voltage (BRD_PWM_VOLT_SEL)

Description

Selects the logic voltage level (3.3V or 5V) for the PWM output pins. Using 5V can improve signal integrity and reduce the impact of electrical noise on long servo wires.

BRD_RADIO_ABLVL

Default 0
Range 0 31

Internal Radio Auto-Bind RSSI Level (BRD_RADIO_ABLVL)

Description

BRD_RADIO_ABLVL is a security filter for the BRD_RADIO_ABTIME feature.

It defines how close a transmitter must be before the drone will allow itself to be bound to it. By requiring a high signal strength (high RSSI), it ensures that your drone only binds to the transmitter you are holding in your hand, rather than someone else's transmitter in a nearby field.

Tuning & Behavior

  • Default: 0 (Any strength accepted - Least secure).
  • Recommendation: Set this to a value that requires the transmitter to be within 1-2 meters of the drone during binding.
  • Usage: Only used when the radio is actively in Auto-Bind mode.

BRD_RADIO_ABTIME

s
Default 0
Range 0 120

Internal Radio Auto-Bind Timeout (BRD_RADIO_ABTIME)

Description

BRD_RADIO_ABTIME determines how long the integrated receiver waits for its "known" transmitter before it gives up and enters Auto-Bind mode.

This is a convenience feature for consumer drones. If you lose or replace your transmitter, you can power on the drone and wait for this timeout to expire. The drone will then start looking for a new transmitter to bind with.

  • 0 (Default): Auto-bind is disabled. You must trigger binding manually (usually via a button or MAVLink command).
  • 1-120: Wait time in seconds.

Tuning & Behavior

  • Default: 0.
  • Usage: Set to 10 or 20 if you want the drone to automatically enter bind mode if you power it on before your transmitter.

BRD_RADIO_BZOFS

Default 25
Range 0 40

Internal Radio Buzzer Offset (BRD_RADIO_BZOFS)

Description

BRD_RADIO_BZOFS allows for a fine-tuning adjustment of the pitch of the buzzer inside the handheld transmitter (when using integrated SPI radios like SkyViper).

Due to manufacturing tolerances in the tiny piezo buzzers used in these controllers, some might sound higher or lower than intended. This parameter allows the user to shift the frequency up or down so that the status beeps and melodies sound correct.

Tuning & Behavior

  • Default: 25.
  • Adjustment: Change this value if your transmitter's beeps sound "flat" or "off-key." Higher values increase the frequency (higher pitch).

BRD_RADIO_DEBUG

Default 0
Range 0 4

Internal Radio Debug Level (BRD_RADIO_DEBUG)

Description

BRD_RADIO_DEBUG is a troubleshooting tool for flight controllers with integrated SPI-based radio receivers (like SkyViper).

It controls how much information about the wireless link (packet loss, signal timing, binding status) is sent to the flight controller's internal console or MAVLink GCS.

  • 0: Disabled (Default).
  • 1-4: Increasing levels of diagnostic data.

Tuning & Behavior

  • Warning: Higher debug levels can flood the communication ports and may cause slight performance hits. Only enable this if you are actively diagnosing a "No RC Link" issue with an integrated radio.

BRD_RADIO_DISCRC

Default 0
Range 0 1

Internal Radio Disable RX CRC (BRD_RADIO_DISCRC)

Description

BRD_RADIO_DISCRC is a low-level developer tool for debugging integrated SPI radios.

CRC is a mathematical check that ensures a packet wasn't corrupted during its flight through the air. Normally, if a packet fails this check, it is thrown away. By disabling this check, the autopilot will attempt to process every signal it receives, even if it is garbage.

  • 0: Enabled (Safe/Default). Corrupt packets are ignored.
  • 1: Disabled (DANGEROUS). Corrupt packets are accepted.

Tuning & Behavior

  • Warning: NEVER enable this for flight. Accepting corrupt packets can lead to "Phantom Stick Movements" where the drone suddenly receives a command to full throttle or hard roll due to a bit-flip in the air.
  • Usage: Only used on the bench to see if a radio link is "almost" working but failing due to slight noise issues.

BRD_RADIO_FCCTST

Default 0
Range 0 100

Internal Radio FCC Test Mode (BRD_RADIO_FCCTST)

Description

BRD_RADIO_FCCTST is used for regulatory compliance testing (FCC/CE).

When set to a non-zero value, the integrated radio will lock onto that specific frequency channel and transmit a continuous signal (or specific test pattern). This is required by labs to measure things like "Occupied Bandwidth" and "Max Power."

Tuning & Behavior

  • 0: Disabled (Default). Normal flight operation.
  • 1-100: Sets the radio to transmit on the corresponding channel.
  • Warning: RC input is disabled while this mode is active. You cannot fly while this parameter is non-zero.

BRD_RADIO_PPSCH

Default 0
Range 0 16

Internal Radio PPS Channel (BRD_RADIO_PPSCH)

Description

BRD_RADIO_PPSCH allows you to monitor the "Frame Rate" of your radio link in real-time.

It maps the number of packets received per second (PPS) to a virtual RC channel. You can then view this value on your OSD or GCS to see if the link is slowing down (indicating interference or range limits) or staying at its full operational speed.

  • 0: Disabled.
  • 1-16: The RC channel number used to report PPS.

Tuning & Behavior

  • Recommendation: Set to an unused channel (e.g. 15) to monitor link health during long-range flights.
  • Context: Used for integrated SPI radios where the autopilot has direct access to low-level packet statistics.

BRD_RADIO_PROT

Default 0
Range 0 2

Internal Radio Protocol (BRD_RADIO_PROT)

Description

BRD_RADIO_PROT defines the communication standard used between the drone's internal receiver and your handheld transmitter. This is used on flight controllers with integrated SPI radios (like the SkyViper).

  • 0: Auto (Recommended). The autopilot will attempt to detect if the transmitter is using DSM2 or DSMX.
  • 1: DSM2. Legacy Spektrum protocol.
  • 2: DSMX. Current Spektrum protocol (more robust against interference).

Tuning & Behavior

  • Default: 0.
  • Recommendation: Leave at 0 (Auto) unless you have a transmitter that is known to only support one specific protocol.

BRD_RADIO_SIGCH

Default 0
Range 0 16

Internal Radio RSSI Channel (BRD_RADIO_SIGCH)

Description

BRD_RADIO_SIGCH allows you to monitor the health of your wireless link by injecting the RSSI (Received Signal Strength Indicator) into a virtual RC channel.

This allows standard OSDs and Ground Control Stations to display the signal strength of the integrated SPI radio just like a traditional receiver.

  • 0: Disabled.
  • 1-16: The RC channel number where RSSI data will be injected (usually set to channel 8 or 16).

Tuning & Behavior

  • Default: 0.
  • Setup: If you set this to 16, ensure your OSD or GCS is configured to look at Channel 16 for RSSI information.

BRD_RADIO_STKMD

Default 2
Range 1 2

Internal Radio Stick Mode (BRD_RADIO_STKMD)

Description

BRD_RADIO_STKMD defines which sticks on your transmitter control which flight axes.

  • Mode 1: Throttle and Roll on the right stick. Pitch and Yaw on the left stick.
  • Mode 2 (Default): Throttle and Yaw on the left stick. Pitch and Roll on the right stick. (Standard for most of the world).

Tuning & Behavior

  • Default: 2.
  • Usage: Only change this if you are a pilot trained in Mode 1 flight. This parameter is sent to the handheld transmitter to reconfigure its internal mixing.

BRD_RADIO_TELEM

Default 0
Range 0 1

Internal Radio Telemetry Enable (BRD_RADIO_TELEM)

Description

BRD_RADIO_TELEM enables the downlink of flight data from the drone's integrated radio receiver back to the pilot's handset.

This is primarily used for the Cypress (DSM) radio driver on specific flight controllers (like the SkyViper) to send battery status and other simple telemetry data to a Spektrum-compatible transmitter.

  • 0: Disabled.
  • 1: Enabled.

Tuning & Behavior

  • Default: 0.
  • Note: This parameter is specific to the internal SPI radio and does not affect external telemetry radios connected to UART ports.

BRD_RADIO_TESTCH

Default 0
Range 0 100

Internal Radio Factory Test Channel (BRD_RADIO_TESTCH)

Description

BRD_RADIO_TESTCH is a production and assembly tool for manufacturers.

It allows a drone's integrated radio to communicate on a fixed, pre-determined frequency channel without going through the standard "Bind" procedure. This allows factory workers to quickly verify that the radio hardware is functioning correctly before shipping.

  • 0: Disabled (Default). Normal operation with standard binding.
  • 1-100: Locks the radio to that specific test channel.

Tuning & Behavior

  • Default: 0.
  • Warning: Do not change this. If this is set to a non-zero value, you will not be able to bind your normal transmitter to the drone.

BRD_RADIO_TPPSCH

Default 0
Range 0 16

Internal Radio Telemetry PPS Channel (BRD_RADIO_TPPSCH)

Description

BRD_RADIO_TPPSCH provides the "Uplink" counterpart to BRD_RADIO_PPSCH.

It reports how many telemetry packets the handheld transmitter is successfully receiving from the drone every second. This value is transmitted back to the drone and mapped to a virtual RC channel. Monitoring both PPS and TPPS allows you to identify if a signal problem is one-way (e.g., a noisy VTX drowning out telemetry) or two-way (range limit).

Tuning & Behavior

  • Default: 0.
  • Setup: Map this to an RC channel and monitor it on your OSD to verify that your telemetry link is stable during flight.

BRD_RADIO_TSIGCH

Default 0
Range 0 16

Internal Radio Telemetry RSSI Channel (BRD_RADIO_TSIGCH)

Description

BRD_RADIO_TSIGCH reports how "Loudly" the handheld transmitter is hearing the drone.

This is the telemetry signal strength (RSSI) measured at the ground station/transmitter end. Like BRD_RADIO_SIGCH (which measures strength at the drone), this parameter maps the ground-side measurement to a virtual RC channel.

Tuning & Behavior

  • Default: 0.
  • Significance: If your drone's SIGCH is high but TSIGCH is low, it means the drone is receiving commands perfectly, but the ground station is struggling to hear the drone's telemetry return signal (often caused by a noisy video transmitter on the drone).

BRD_RADIO_TXMAX

Default 8
Range 1 8

Internal Radio Max TX Power (BRD_RADIO_TXMAX)

Description

BRD_RADIO_TXMAX sets the maximum power limit for the Handheld Transmitter (remote control) when using a two-way integrated radio system (like SkyViper).

The autopilot sends this value back to the transmitter via telemetry, commanding it to limit its output power to the specified level. This is useful for adhering to regional power regulations or managing battery life on the controller.

Tuning & Behavior

  • Default: 8 (Maximum).
  • Range: 1 (Lowest) to 8 (Highest).
  • Usage: For maximum control range outdoors, leave at 8. If you are only flying in a small indoor arena and want to reduce interference with other electronics, you can lower this value.

BRD_RADIO_TXPOW

Default 8
Range 1 8

Internal Radio Transmit Power (BRD_RADIO_TXPOW)

Description

BRD_RADIO_TXPOW controls the strength of the signal sent from the drone's internal radio back to the transmitter (Telemetry).

This is used on flight controllers with built-in SPI receivers (like the SkyViper or some small AIO boards). Increasing the power improves range but consumes more battery and generates more heat on the radio chip.

  • 1: Minimum power (Short range, safe for bench testing).
  • 8: Maximum power (Long range).

Tuning & Behavior

  • Default: 8.
  • Recommendation: Leave at 8 for outdoor flight. Reduce to 1 or 2 if you are only flying indoors or working on the bench to reduce electrical noise.

BRD_RADIO_TYPE

Default 0
Range 0 3

Internal Radio Type (BRD_RADIO_TYPE)

Description

BRD_RADIO_TYPE enables the integrated radio receiver found on some flight controllers (like the SkyViper or specialized AIO racing boards). These receivers are connected directly to the CPU via an SPI bus, rather than a standard UART.

  • 0: None. Internal radio is disabled.
  • 1: CYRF6936. DSM/Spektrum compatible.
  • 2: CC2500. FrSky/Futaba compatible.
  • 3: BK2425.

Tuning & Behavior

  • Reboot Required: Yes.
  • Setup: Once enabled, you must bind your transmitter. Use the board-specific binding procedure (usually a button or a MAVLink command).

BRD_RTC_TYPES

Default 1

Allowed RTC types (BRD_RTC_TYPES)

Description

Specifies which sources (GPS, Internal, System) are allowed to set the vehicle's Real Time Clock.

BRD_RTC_TZ_MIN

min
Default 0

Timezone offset (BRD_RTC_TZ_MIN)

Description

Offsets the system time from UTC for local time reporting in logs.

BRD_SAFETYOPTION

Default 3

Options for safety button behavior (BRD_SAFETYOPTION)

Description

Configures the specific interaction rules for the hardware safety button, such as whether it can be used to re-engage safety while armed.

Tuning & Behavior

  • Default Value: 3 (Button active for Safety On/Off)
  • Bitmask:
    • 0: ActiveForSafetyDisable
    • 1: ActiveForSafetyEnable
    • 2: ActiveWhenArmed
    • 3: Force safety on when the aircraft disarms

BRD_SAFETY_DEFLT

Default 1
Range 0 1

Sets default state of the safety switch (BRD_SAFETY_DEFLT)

Description

Determines if the hardware safety switch starts in the "Safe" (blashing) or "Armed" (solid) state upon boot.

Tuning & Behavior

  • Default Value: 1 (Starts in Safe state)
  • Values: 0:Disabled (Unsafe at boot), 1:Enabled (Safe at boot)
  • Safety switch behavior can still be toggled manually after boot.

BRD_SAFETY_MASK

Default 0

Outputs which ignore the safety switch state (BRD_SAFETY_MASK)

Description

Allows specific servo/motor outputs to function even if the hardware safety switch is in the "Safe" position. Commonly used for non-propulsion servos like camera gimbals or retractable landing gear.

Tuning & Behavior

  • Default Value: 0
  • Bitmask corresponds to output channels 1 through 14.

BRD_SBUS_OUT

Hz
Default 0
Range 0 7

SBUS output rate (BRD_SBUS_OUT)

Description

Configures the refresh rate of the SBUS output port.

Tuning & Behavior

  • Default Value: 0 (Disabled)
  • Values: 1:50Hz, 2:75Hz, 3:100Hz, 4:150Hz, 5:200Hz, 6:250Hz, 7:300Hz

BRD_SD_FENCE

kB
Default 0
Range 0 64

SDCard Fence size (BRD_SD_FENCE)

Description

Allocates dedicated storage space on the SD card for complex geofence definitions (fence.stg).

BRD_SD_MISSION

kB
Default 0
Range 0 64

SDCard Mission size (BRD_SD_MISSION)

Description

Allocates dedicated storage space on the SD card for mission command storage (mission.stg), allowing for much larger missions than internal EEPROM.

BRD_SD_SLOWDOWN

Default 0
Range 0 32

microSD slowdown (BRD_SD_SLOWDOWN)

Description

Reduces the SPI bus speed for the microSD card. This can resolve "No SD Card" or logging errors on certain combinations of flight boards and card types.

BRD_SER1_RTSCTS

Default 2
Range 0 3

Serial 1 flow control (BRD_SER1_RTSCTS)

Description

Enables hardware flow control (RTS/CTS) for the first telemetry port. This prevents data loss during high-bandwidth telemetry streaming.

Tuning & Behavior

  • Default Value: 2 (Auto)
  • Values: 0:Disabled, 1:Enabled, 2:Auto, 3:RS-485

BRD_SER2_RTSCTS

Default 2
Range 0 3

Serial 2 flow control (BRD_SER2_RTSCTS)

Description

Enables hardware flow control for the second telemetry port.

BRD_SER3_RTSCTS

Default 2
Range 0 3

Serial 3 flow control (BRD_SER3_RTSCTS)

Description

Enables hardware flow control for the third serial port.

BRD_SER4_RTSCTS

Default 2
Range 0 3

Serial 4 flow control (BRD_SER4_RTSCTS)

Description

Enables hardware flow control for the fourth serial port.

BRD_SER5_RTSCTS

Default 2
Range 0 3

Serial 5 flow control (BRD_SER5_RTSCTS)

Description

Enables hardware flow control for the fifth serial port.

BRD_SER6_RTSCTS

Default 2
Range 0 3

Serial 6 flow control (BRD_SER6_RTSCTS)

Description

Enables hardware flow control for the sixth serial port.

BRD_SER7_RTSCTS

Default 2
Range 0 3

Serial 7 flow control (BRD_SER7_RTSCTS)

Description

Enables hardware flow control for the seventh serial port.

BRD_SER8_RTSCTS

Default 2
Range 0 3

Serial 8 flow control (BRD_SER8_RTSCTS)

Description

Enables hardware flow control for the eighth serial port.

BRD_SERIAL_NUM

Default 0
Range -8388608 8388607

User-defined serial number (BRD_SERIAL_NUM)

Description

Allows users to assign a unique ID number to their aircraft. This is useful for fleet management and identifying specific airframes in log files.

BRD_TYPE

Default 0

Board type (BRD_TYPE)

Description

Specifies the hardware platform type. While ArduPilot usually auto-detects the board, this parameter can be used to force a specific driver set.

Tuning & Behavior

  • Default Value: 0 (Auto-detect)
  • Values: 1:PX4V1, 2:Pixhawk, 3:Cube/Pixhawk2, 4:Pixracer, etc.
  • Requires reboot to take effect.

BRD_VBUS_MIN

V
Default 4.3
Range 4.0 5.5

Autopilot board voltage requirement (BRD_VBUS_MIN)

Description

Pre-arm safety threshold for the flight controller's internal supply voltage. Arming is blocked if the input voltage is too low, indicating a potentially unreliable power source.

BRD_VSERVO_MIN

V
Default 0
Range 3.3 12.0

Servo voltage requirement (BRD_VSERVO_MIN)

Description

Pre-arm safety threshold for the servo power rail. Arming is blocked if the voltage powering the servos is below this value.