MAVLINKHUD

Overview

The MNT parameter group configures the Camera Mount (Gimbal) subsystem. ArduPilot supports up to 2 mounts (MNT1 and MNT2).

The mount system allows the autopilot to stabilize the camera against the vehicle's movement and point the camera at specific targets (ROI).

Key Concepts

1. Mount Types (MNT_TYPE)

Defines how the autopilot talks to the gimbal hardware.

  • 1 (Servo): PWM servos for Tilt, Roll, and Yaw. Stabilization is done by the flight controller.
  • 3 (AlexMos): Serial protocol for AlexMos/SimpleBGC gimbals.
  • 4 (STorM32): Serial protocol for STorM32 gimbals.
  • 6 (DJI): For DJI Zenmuse gimbals (via converter).
  • 8 (DroneCAN): CAN-based gimbals (e.g., Gremsy CAN).

2. Stabilization

If using a simple Servo gimbal (Type=1), ArduPilot can use its IMU data to keep the camera level.

  • MNT_LEAD_PTCH / RLL: Predictive lag compensation.

3. Angles and Limits (MNT_PITCH_MIN / MAX)

Defines the mechanical range of motion of the gimbal.

  • Pitch -90: Camera pointing straight down.
  • Pitch 0: Camera pointing straight forward.

Parameter Breakdown

  • MNT1_TYPE: Active driver.
  • MNT1_DEFLT_MODE: Behavior at boot (Retracted, Neutral, MAVLink, RC Target).
  • MNT1_RC_RATE: How fast the camera moves when you move the RC sticks (deg/s).

Integration Guide

  1. Hardware: Mount the gimbal. If serial, connect to a Telem port.
  2. Enable: Set MNT1_TYPE.
  3. Port: (If serial) Set SERIALx_PROTOCOL = 7 (AlexMos) or 8 (STorM32).
  4. Verify: Tilt the drone; the camera should remain level relative to the horizon.

Developer Notes

  • Library: libraries/AP_Mount.
  • Interaction: Tightly integrated with the CAM group for automated photo triggering during survey missions.

MNT_INST: Camera Mount instance

Description

Mount instance camera is associated with. 0 means camera and mount have identical instance numbers (e.g., Camera 1 -> Mount 1).

Values

  • Range: 0 to 2
  • Default: 0

Description

This parameter links a configured Camera (CAM or CAM2) to a specific Gimbal/Mount (MNT or MNT2).

  • 0: Default mapping (Camera 1 uses Mount 1, Camera 2 uses Mount 2).
  • 1: This Camera uses Mount 1.
  • 2: This Camera uses Mount 2.

Source Code

ardupilot/libraries/AP_Camera/AP_Camera_Params.cpp

MNT1_DEFLT_MODE

Default 3
Range 0 6

Mount Default Mode (MNT1_DEFLT_MODE)

Description

MNT1_DEFLT_MODE sets the fallback behavior for the gimbal. It determines where the camera points when the drone first powers on, or when an autonomous mission ends and returns control to the pilot.

  • 0: Retracted. Gimbal moves to its stowed position.
  • 1: Neutral. Gimbal points straight forward.
  • 2: MAVLink. Waits for a command from the GCS.
  • 3: RC Targeting. (Default). The gimbal follows the position of the knobs/sliders on your transmitter.
  • 4: GPS Point. Points at a specific location on the map.

Tuning & Behavior

  • Default: 3 (RC Targeting).
  • Recommendation: Set to 3 if you want manual control of the camera tilt during flight. Set to 6 (Home Location) if you want the camera to automatically track the takeoff point.

MNT1_DEVID

Default 0

Mount Device ID (MNT1_DEVID)

Description

MNT1_DEVID is a Read-Only diagnostic parameter that stores the unique hardware ID of the detected gimbal. It encodes the driver type, the communication bus (e.g. DroneCAN, I2C), and the bus address.

  • Role: Verifies that the autopilot has successfully connected to the external gimbal hardware.
  • Usage: If this is 0, the autopilot has failed to detect the gimbal specified in MNT1_TYPE.

Tuning & Behavior

  • Default: 0.
  • Action: No user adjustment is possible. This is used by the system to ensure it is talking to the correct device instance.

MNT1_LEAD_PTCH

s
Default 0
Range 0 0.2

Mount Pitch Lead Time (MNT1_LEAD_PTCH)

Description

MNT1_LEAD_PTCH compensates for the "Lag" in your gimbal servos.

When the drone pitches forward quickly, there is a small delay before the servo actually moves to counteract it. This can result in the horizon tilting momentarily in your video. This parameter tells the autopilot to "Predict" where the vehicle is going based on its current rotation speed and command the servo slightly ahead of time.

Tuning & Behavior

  • Default: 0.
  • Recommendation: Increase in small steps (e.g. 0.01s or 0.02s).
  • Optimal Setting: The horizon should stay perfectly level even during fast pitch maneuvers.
  • Warning: If you set this too high, the gimbal will "Overshoot" or vibrate during fast movements.

MNT1_LEAD_RLL

s
Default 0
Range 0 0.2

Mount Roll Lead Time (MNT1_LEAD_RLL)

Description

MNT1_LEAD_RLL compensates for mechanical and signal lag on your gimbal's roll axis.

It is similar to MNT1_LEAD_PTCH but for banking movements. If your video horizon "leans" during a turn and then slowly levels out, increasing this value will make the gimbal react faster to keep the camera flat.

Tuning & Behavior

  • Default: 0.
  • Recommendation: Start with 0.01s.
  • Optimal Setting: The horizon should stay perfectly horizontal even during aggressive "S-turns" or bank-and-yank maneuvers.

MNT1_OPTIONS

Default 0
Range 0 1

Mount Options (MNT1_OPTIONS)

Description

MNT1_OPTIONS is a bitmask to enable specific Gimbal behaviors.

  • Bit 0 (1): Lock state from previous mode. If you manually lock the gimbal's heading (using an RC switch) and then change the flight mode, the gimbal will stay locked in its current position rather than snapping back to its default orientation.

Tuning & Behavior

  • Default: 0.
  • Usage: Enable Bit 0 if you are performing cinematic shots where you want the camera to stay pointed at a subject even if the drone's autopilot behavior changes.

MNT1_PITCH_MAX

deg
Default 20
Range -90 90

Mount Pitch Maximum (MNT1_PITCH_MAX)

Description

MNT1_PITCH_MAX defines the upper mechanical limit of your gimbal.

Setting this correctly prevents the gimbal from trying to tilt past its physical stop, which can cause motor overheating, "gimbal flip," or mechanical damage.

  • Default: 20 degrees (pointing slightly above the horizon).
  • Recommendation: Match this to your gimbal's physical capability.

Tuning & Behavior

  • Default: 20.
  • Constraint: This value must be greater than MNT1_PITCH_MIN.
  • Usage: For mapping missions (straight down), you might set this to 0 to keep the camera strictly at or below the horizon.

MNT1_PITCH_MIN

deg
Default -90
Range -90 90

Mount Pitch Minimum (MNT1_PITCH_MIN)

Description

MNT1_PITCH_MIN defines the lower mechanical limit of your gimbal.

  • -90: Straight Down. (Standard for mapping and FPV photography).
  • 0: Horizon. (Prevents the gimbal from looking down at the ground).

Tuning & Behavior

  • Default: -90.
  • Action: Ensure your gimbal can physically reach the value set here without straining the motors.

MNT1_RC_RATE

deg/s
Default 0
Range 0 90

Mount RC Rate (MNT1_RC_RATE)

Description

MNT1_RC_RATE determines how fast your camera gimbal tilts or pans when you move the knobs on your transmitter.

  • Non-Zero Value (1-90): Enables Rate Control. Moving the knob away from the center makes the gimbal start moving in that direction. The farther you move the knob, the faster it rotates (up to this limit). Returning the knob to the center stops the movement.
  • Zero (0): Enables Angle Control. The gimbal's angle directly matches the position of the knob (e.g., knob at 10 o'clock = camera at -45 degrees).

Tuning & Behavior

  • Default: 0 (Angle Control).
  • Recommendation: Use Rate Control (e.g., 20 or 30 $deg/s$) for cinematic filming, as it allows for much smoother starts and stops. Use Angle Control (0) if you need the camera to instantly point where your switch/knob is located.

MNT1_ROLL_MAX

deg
Default 30
Range -180 180

Mount Roll Maximum (MNT1_ROLL_MAX)

Description

MNT1_ROLL_MAX sets the upper boundary for the gimbal's roll axis.

This is used to prevent the gimbal from hitting its physical stops when the drone is banking hard. It is particularly important for 2-axis gimbals or 3-axis gimbals with limited roll travel.

  • Units: Degrees.
  • Default: 30.

Tuning & Behavior

  • Default: 30.
  • Constraint: This value should match the physical limit of your gimbal. If the gimbal starts "stuttering" or making a high-pitched noise during a hard turn, your roll limits are likely too wide.

MNT1_ROLL_MIN

deg
Default -30
Range -180 180

Mount Roll Minimum (MNT1_ROLL_MIN)

Description

MNT1_ROLL_MIN sets the lower boundary for the gimbal's roll axis.

This is the negative counterpart to MNT1_ROLL_MAX. It ensures the gimbal doesn't try to bank too far in the opposite direction.

  • Units: Degrees.
  • Default: -30.

Tuning & Behavior

  • Default: -30.
  • Safety: Always verify that your gimbal can physically reach these angles by manually banking the drone while it is powered on.

MNT1_SYSID_DFLT

Default 0
Range 0 255

Mount Target System ID (MNT1_SYSID_DFLT)

Description

MNT1_SYSID_DFLT specifies the "Network Address" of the gimbal.

In a MAVLink network (where multiple components like the autopilot, gimbal, and camera communicate), this ID allows the autopilot to send tilt/pan commands specifically to the correct gimbal controller.

  • 0 (Default): The autopilot will attempt to automatically find the first gimbal on the network.
  • 1-255: Manually locks the autopilot to a specific MAVLink system ID.

Tuning & Behavior

  • Default: 0.
  • Usage: Only set this if you have multiple gimbals (e.g. forward and downward) and the autopilot is consistently trying to control the wrong one.
  • Reboot Required: Yes.

MNT1_TYPE

Default 0
Range 0 13

Mount Type (MNT1_TYPE)

Description

MNT1_TYPE enables gimbal control for your primary camera or payload. ArduPilot supports a wide variety of gimbals, from simple servos to high-end serial gimbals with integrated cameras.

  • 0: None. Gimbal control is disabled.
  • 1: Servo. For DIY gimbals controlled via PWM outputs on the flight controller.
  • 3: Alexmos Serial. For BaseCam/SimpleBGC controllers.
  • 4: SToRM32 MAVLink.
  • 6: Gremsy. Professional serial gimbals.
  • 8: Siyi. For Siyi ZR10/A8/ZR30 and similar integrated gimbals.
  • 11: Viewpro.

The Engineer's View

Defined in AP_Mount.
Enabling a mount type allocates the corresponding driver backend. The backend is responsible for receiving target angles from the autopilot (or RC passthrough) and commanding the hardware.

Tuning & Behavior

  • Default Value: 0 (Disabled).
  • Reboot Required: Yes. Mount drivers are allocated at boot.
  • Integration: Once enabled, you must also configure the default mode (MNT1_DEFLT_MODE) and limits (MNT1_PITCH_MIN, etc.).

MNT1_YAW_MAX

deg
Default 180
Range -180 180

Mount Yaw Maximum (MNT1_YAW_MAX)

Description

MNT1_YAW_MAX defines how far the gimbal is allowed to rotate (pan) to the right.

  • For 360-degree Gimbals: Set to 180 (allowing full rotation).
  • For Limited-travel Gimbals: Set to the physical stop (e.g. 45 or 90 degrees).

Tuning & Behavior

  • Default: 180.
  • Cable Safety: Ensure that your camera cables can handle the rotation set here without being pulled out or tangled.

MNT1_YAW_MIN

deg
Default -180
Range -180 180

Mount Yaw Minimum (MNT1_YAW_MIN)

Description

MNT1_YAW_MIN defines how far the gimbal is allowed to rotate (pan) to the left.

This is the negative counterpart to MNT1_YAW_MAX.

  • Units: Degrees.
  • Default: -180 (Full left rotation).

Tuning & Behavior

  • Default: -180.
  • Alignment: Ensure that 0 degrees corresponds to the camera pointing directly forward along the vehicle's centerline.

MNT2_DEFLT_MODE

Default MAV_MOUNT_MODE_RC_TARGETING
Range null

Mount default operating mode

Note: This parameter functions identically to MNT1_DEFLT_MODE.

MNT2_DEVID

Default 0
Range null

Mount Device ID

Note: This parameter functions identically to MNT1_DEVID.

MNT2_LEAD_PTCH

s
Default 0.0f
Range 0.0 0.2

Mount Pitch stabilization lead time

Note: This parameter functions identically to MNT1_LEAD_PTCH.

MNT2_LEAD_RLL

s
Default 0.0f
Range 0.0 0.2

Mount Roll stabilization lead time

Note: This parameter functions identically to MNT1_LEAD_RLL.

MNT2_OPTIONS

Default 0
Range null

Mount options

Note: This parameter functions identically to MNT1_OPTIONS.

MNT2_PITCH_MAX

deg
Default 20
Range -90 90

Mount Pitch angle maximum

Note: This parameter functions identically to MNT1_PITCH_MAX.

MNT2_PITCH_MIN

deg
Default -90
Range -90 90

Mount Pitch angle minimum

Note: This parameter functions identically to MNT1_PITCH_MIN.

MNT2_RC_RATE

deg/s
Default 0
Range 0 90

Mount RC Rate

Note: This parameter functions identically to MNT1_RC_RATE.

MNT2_ROLL_MAX

deg
Default 30
Range -180 180

Mount Roll angle maximum

Note: This parameter functions identically to MNT1_ROLL_MAX.

MNT2_ROLL_MIN

deg
Default -30
Range -180 180

Mount Roll angle minimum

Note: This parameter functions identically to MNT1_ROLL_MIN.

MNT2_SYSID_DFLT

Default 0
Range null

Mount Target sysID

Note: This parameter functions identically to MNT1_SYSID_DFLT.

MNT2_TYPE

Default 0
Range null

Mount Type

Note: This parameter functions identically to MNT1_TYPE.

MNT2_YAW_MAX

deg
Default 180
Range -180 180

Mount Yaw angle maximum

Note: This parameter functions identically to MNT1_YAW_MAX.

MNT2_YAW_MIN

deg
Default -180
Range -180 180

Mount Yaw angle minimum

Note: This parameter functions identically to MNT1_YAW_MIN.

MNT_NEUTRAL

deg
Default 0
Range -180 180

Mount Neutral Position (MNT_NEUTRAL)

Description

MNT_NEUTRAL defines the "Center" position of the gimbal.

This is used when the gimbal mode is set to Neutral. Typically, this is set to (0, 0, 0) so that the camera points straight ahead along the drone's longitudinal axis.

Tuning & Behavior

  • Default: 0.
  • Usage: If your gimbal is mounted slightly crooked, you can use these parameters to "Trim" the neutral position so that the camera is perfectly centered when the autopilot is in Neutral mode.

MNT_RETRACT

deg
Default 0
Range -180 180

Mount Retracted Position (MNT_RETRACT)

Description

MNT_RETRACT defines the "Parked" position of the gimbal.

This is used when the gimbal mode is set to Retracted. For many professional drones, this position points the camera inward or upward into a protective cavity to prevent the lens from being scratched or the motors from being strained during landing or transport.

Tuning & Behavior

  • Default: 0 (Centered).
  • Usage: Set the Roll, Pitch, and Yaw values to match your gimbal's specific stowing requirement.
  • Safety: Ensure the retracted position does not cause the gimbal to hit the airframe or stretch internal cables.