MAVLINKHUD

Overview

The PLND parameter group configures the Precision Landing system. This library uses visual sensors (IR Beacons, AprilTags, or companion computer vision) to land the vehicle on a specific target with centimeter-level accuracy, regardless of GPS drift.

Key Concepts

1. Landing Target Sensors (PLND_TYPE)

Defines the hardware used to see the target.

  • 1 (IR Lock): Uses a specialized IR camera (IRLock) to track a pulsed infrared beacon.
  • 2 (Companion): Receives target position updates from a companion computer (e.g., Raspberry Pi running OpenMV or AprilTag detection).
  • 3 (SITL): Simulated landing target.

2. Estimator and Filter (PLND_EST_TYPE)

Determines how the target's relative position is fused.

  • 0 (Raw): Direct sensor-to-motor correction (only recommended for simple IR lock).
  • 1 (Kalman Filter): Fuses vehicle velocity and sensor data to predict target position even if the target is briefly obscured.

3. Safety Thresholds

  • PLND_XY_DIST_MAX: If the target is further away than this, the drone will ignore it and land normally (prevents chasing a false positive).
  • PLND_ALT_MAX: Maximum altitude to start looking for the target.

Parameter Breakdown

  • PLND_ENABLED: Master switch.
  • PLND_YAW_ALIGN: Rotates the vehicle to match the orientation of the target (if using oriented tags).

Integration Guide

  1. Hardware: Mount the sensor (e.g., IRLock) facing straight down.
  2. Enable: Set PLND_ENABLED = 1 and PLND_TYPE.
  3. Mode: Set LAND_TYPE = 1 (Precision) if you want it to trigger every time you switch to Land mode.

Developer Notes

  • Library: libraries/AC_PrecLand.
  • Accuracy: Typically achieves < 10cm accuracy. Essential for automated charging pads or shipboard landings.

PLND_ACC_P_NSE

Default 2.5
Range 0.5 5.0

Kalman Filter Accelerometer Noise (PLND_ACC_P_NSE)

Description

PLND_ACC_P_NSE defines the "Trust Balance" for the precision landing system.

When the drone is landing on a target, it uses two pieces of information:

  1. The Sensor: Where the camera/IR sensor sees the target right now.
  2. The IMU: Where the drone thinks it has moved based on its internal accelerometers.
  • Higher Value: The drone assumes the IMU is noisy. It will react faster to new data from the landing sensor. Good for high-vibration drones.
  • Lower Value: The drone trusts its IMU more. It will ignore small jitters in the landing sensor and move more smoothly.

The Engineer's View

This parameter sets the process noise covariance ($Q$) for the internal precision landing Kalman filter. It specifically weights the accelerometer inputs against the measurement updates from the vision system.

Tuning & Behavior

  • Default Value: 2.5.
  • Oscillations: If the drone "Twitches" or over-corrects as it approaches the landing pad, decrease this value to 1.5.
  • Lag: If the drone is slow to react to target movements, increase to 3.5.

PLND_ALT_MAX

m
Default 8.0
Range 0 50

PrecLand maximum alt for retry (PLND_ALT_MAX)

Description

This parameter defines the "Active Search Zone" upper boundary for Precision Landing.

When the vehicle is descending in a precision landing mode, it expects to see the landing target (e.g., an IR beacon or AprilTag). If the vehicle is above PLND_ALT_MAX, it will continue to descend vertically even if it doesn't see the target. Once it drops below this altitude, the "Retry Logic" becomes active. If the target is lost while the vehicle is below this height, it will trigger a retry (climb back up to look for it) or a failsafe, depending on PLND_STRICT.

The Mathematics

This parameter acts as a height-based logic gate ($H\_{gate}$):

$$ \text{RetryLogicActive} = \text{IF } (Alt\_{RangeFinder} < PLND\_ALT\_MAX) $$

It requires a valid downward-facing rangefinder to function. If the rangefinder is not present or unhealthy, this altitude check is bypassed or fails safe depending on PLND_OPTIONS.

The Engineer's View

In AC_PrecLand::check_if_sensor_in_range() (libraries/AC_PrecLand/AC_PrecLand.cpp):

  1. The code checks if _sensor_max_alt is non-zero.
  2. It verifies that the rangefinder altitude is valid.
  3. If rangefinder_alt_m > _sensor_max_alt, it returns false, meaning the "Retry/Lost" logic should not yet be triggered (the vehicle is too high to reasonably expect a solid lock).
  4. Once below this height, the TargetState can transition to TARGET_RECENTLY_LOST or TARGET_OUT_OF_RANGE.

Tuning & Behavior

  • Default Value: 8 meters.
  • Agile Aircraft: Can be set higher (e.g., 15m) if the camera/sensor has a very wide field of view.
  • Limited Sensors: Should be set to the maximum reliable range of your landing sensor (e.g., IR-Lock is usually effective up to ~10-15m).
  • 0: Disables the maximum altitude check; retry logic is always active if the target is lost.

PLND_ALT_MIN

m
Default 0.75
Range 0 5

PrecLand minimum alt for retry (PLND_ALT_MIN)

Description

This parameter defines the "Commit Zone" lower boundary for Precision Landing.

When a vehicle is very close to the ground (e.g., during the final flare or touchdown), it is often dangerous to attempt a "Retry" (climbing back up) if the landing sensor loses the target (which often happens due to dust, ground effect, or camera focal limits).

If the vehicle is below PLND_ALT_MIN, it will ignore the fact that it lost the target and simply continue to land vertically. This ensures a safe touchdown rather than an unexpected and potentially unstable climb-out at very low altitude.

The Mathematics

This parameter acts as a low-altitude safety gate:

$$ \text{InCommitZone} = \text{IF } (Alt\_{RangeFinder} < PLND\_ALT\_MIN) $$

If InCommitZone is true, the TargetState remains TARGET_FOUND (or behaves as such for the landing logic) even if the sensor reporting fails.

The Engineer's View

In AC_PrecLand::check_if_sensor_in_range() (libraries/AC_PrecLand/AC_PrecLand.cpp):

  1. The code verifies that the rangefinder altitude is valid.
  2. If rangefinder_alt_m < _sensor_min_alt, it returns false, preventing the transition to a "Lost" state that would trigger a retry.
  3. This is a robust way to handle the "Blind Spot" that many optical and IR sensors have when they get within a few dozen centimeters of the target.

Tuning & Behavior

  • Default Value: 0.75 meters.
  • Tall Gear: If your aircraft has very tall landing gear or a underslung camera, you may need to increase this slightly (e.g., 1.0m).
  • Small Drones: Can often leave this at the default or slightly lower.
  • 0: Disables the minimum altitude check; the vehicle may attempt to retry even a few centimeters from the ground. Not recommended.

PLND_BUS

Default -1
Range -1 3

Sensor Bus (PLND_BUS)

Description

PLND_BUS specifies where you plugged in your I2C-based landing sensor (like an IR-Lock).

  • -1 (Default): The autopilot probes all external buses for a compatible sensor.
  • 0: Forces the internal bus.
  • 1: Forces the external bus (standard GPS/Compass port).

Tuning & Behavior

  • Default Value: -1.
  • Recommendation: Leave at -1 unless you have multiple identical sensors on different buses or a specialized hardware conflict.

PLND_CAM_POS_X

m
Default 0
Range -5 5

Camera X Position Offset (PLND_CAM_POS_X)

Description

PLND_CAM_POS_X tells the autopilot exactly where the camera is mounted on the drone.

For precision landing to work perfectly, the flight controller needs to know the "Lever Arm" effect. If the camera is 10cm forward of the center of gravity, and the drone tilts forward, the camera moves. Without this offset, the drone might "hunt" or circle the target because it thinks it has moved more (or less) than it actually has.

The Engineer's View

This parameter defines the longitudinal offset in the body frame.

  • Positive X: Camera is in front of the center.
  • Negative X: Camera is behind the center.

The values are used to transform the camera's raw sight-line vector into a global position relative to the vehicle's navigation origin.

Tuning & Behavior

  • Default Value: 0 m.
  • Recommendation: Measure the distance from the lens center to the center of your flight controller's IMU. Enter the value in meters (e.g. 0.1 for 10cm).

PLND_CAM_POS_Y

m
Default 0
Range -5 5

Camera Y Position Offset (PLND_CAM_POS_Y)

Description

PLND_CAM_POS_Y defines the lateral offset of the landing sensor.

  • Positive Y: Camera is to the right of center.
  • Negative Y: Camera is to the left of center.

See PLND_CAM_POS_X for detailed explanation.

PLND_ENABLED

Default 0
Range 0 1

Precision Landing Enable (PLND_ENABLED)

Description

PLND_ENABLED activates the "Visual Landing" system.

Standard GPS landing is accurate to about 1-2 meters. Precision Landing (PrecLand) uses a sensor (like an IRLock camera or an onboard computer) to see a target on the ground and guide the drone onto it with centimeter-level accuracy.

  • 0: Disabled.
  • 1: Enabled.

Tuning & Behavior

  • Reboot Required: Yes.
  • Trigger: Precision landing is typically used in the LAND flight mode. Once enabled, the drone will look for the target as it descends.

PLND_EST_TYPE

Default 1
Range 0 1

Precision Land Estimator Type (PLND_EST_TYPE)

Description

PLND_EST_TYPE defines how the drone interprets the data from its landing sensor.

  • 0: RawSensor. The drone flies directly toward where the sensor "sees" the target right now. (Simple, but can be twitchy).
  • 1: KalmanFilter (Default). The drone uses a mathematical model to predict where the target is, filtering out sensor noise and accounting for the drone's own movement. (Smooth and much more reliable).

The Engineer's View

Used in AC_PrecLand::run_estimator().
The Kalman Filter (1) mode uses the _ekf_x and _ekf_y internal state machines to track the target's relative velocity and position. This allows the drone to continue "knowing" where the target is for a few seconds even if the sensor momentarily loses sight of it (e.g., due to glare).

Tuning & Behavior

  • Default Value: 1
  • Recommendation: Always use 1 (KalmanFilter). It provides much better performance and handles sensor dropouts more gracefully.

PLND_LAG

s
Default 0.02
Range 0.02 0.250

Precision Landing Sensor Lag (PLND_LAG)

Description

PLND_LAG compensates for the processing time of your landing camera or sensor.

Computer vision takes time. By the time a Raspberry Pi or OpenMV cam tells the flight controller "The target is at X,Y," the drone has already moved several centimeters. This parameter allows the EKF to "Rewind" its internal state to match the moment the photo was actually taken, resulting in much smoother and more accurate centering.

  • Default Value: 0.02 seconds (20ms).
  • Too High: The drone will "overshoot" its corrections.
  • Too Low: The drone will feel sluggish and take longer to center.

Tuning & Behavior

  • Default Value: 0.02s.
  • Recommendation:
    • IR-Lock: 0.02s - 0.04s.
    • Companion Computer (OpenCV): 0.05s - 0.10s.

PLND_LAND_OFS_X

cm
Default 0
Range -20 20

Land offset forward (PLND_LAND_OFS_X)

Description

This parameter allows you to intentionally "offset" the final touchdown position of the vehicle along its forward/back (X) axis. While precision landing usually aims to put the camera directly over the center of the target, you might want the vehicle to land slightly forward or back from that center point.

This is particularly useful if your landing gear requires a specific alignment on a platform or if you want to avoid landing directly on top of a physical beacon.

The Mathematics

The offset is applied as a static translation in the vehicle's body-frame before being rotated into the global navigation frame.

$$ \text{Pos}{target\_final} = \text{Pos}{target\_detected} + \text{Rotation}\_{BodyToNED}(\text{LAND\_OFS\_X}, \text{LAND\_OFS\_Y}, 0) $$

A positive value shifts the landing point forward (the vehicle will land with the camera ahead of the target). A negative value shifts it backward.

The Engineer's View

In AC_PrecLand::run_output_prediction() (libraries/AC_PrecLand/AC_PrecLand.cpp), the _land_ofs_cm_x and _land_ofs_cm_y values are converted to meters and added to the relative target position estimate.
This translation is performed after the camera's physical position offset (CAM_POS) has been accounted for, ensuring that LAND_OFS is purely a bias on the final desired landing spot.

Tuning & Behavior

  • Default Value: 0 cm.
  • Range: -20 to 20 cm.
  • Tuning: If your drone consistently lands 5cm too far back from the center of the pad, set this to 5 to shift the landing point forward.
  • Note: This is an intentional bias. If the vehicle is missing the target due to wind or poor tuning, do not use this parameter to "fix" it; instead, tune the position controller or L1 parameters.

PLND_LAND_OFS_Y

cm
Default 0
Range -20 20

Land offset right (PLND_LAND_OFS_Y)

Description

This parameter allows you to intentionally "offset" the final touchdown position of the vehicle along its left/right (Y) axis. While precision landing usually aims to put the camera directly over the center of the target, you might want the vehicle to land slightly to the right or left of that center point.

This is useful for aligning the drone's landing gear with specific markings on a landing pad or for offset-mounted hardware.

The Mathematics

The offset is applied as a static translation in the vehicle's body-frame before being rotated into the global navigation frame.

$$ \text{Pos}{target\_final} = \text{Pos}{target\_detected} + \text{Rotation}\_{BodyToNED}(0, \text{LAND\_OFS\_Y}, 0) $$

A positive value shifts the landing point to the right. A negative value shifts it to the left.

The Engineer's View

In AC_PrecLand::run_output_prediction() (libraries/AC_PrecLand/AC_PrecLand.cpp), the _land_ofs_cm_y value is converted to meters and added to the relative target position estimate.
This translation is performed after the camera's physical position offset (CAM_POS) has been accounted for, ensuring that LAND_OFS is purely a bias on the final desired landing spot.

Tuning & Behavior

  • Default Value: 0 cm.
  • Range: -20 to 20 cm.
  • Tuning: If your drone consistently lands 5cm to the left of the beacon, set this to 5 (positive) to shift the landing point to the right.
  • Note: This is an intentional bias. If the vehicle is missing the target due to wind or poor tuning, do not use this parameter to "fix" it; instead, tune the position controller or L1 parameters.

PLND_OPTIONS

Bitmask
Default 0
Range null

Precision Landing Extra Options (PLND_OPTIONS)

Description

This parameter is a bitmask that enables specific advanced features for the Precision Landing sub-system. It allows the pilot to customize how the vehicle handles dynamic landing scenarios, such as landing on a moving deck or responding to pilot interventions.

The Mathematics

The bits are processed as individual boolean flags:

  • Bit 0 (Value 1): Moving Landing Target.
    Enables velocity estimation for the target. If the landing sensor detects the target is moving relative to the ground, the autopilot will attempt to match its speed for a more accurate touchdown.
  • Bit 1 (Value 2): Allow Precision Landing after manual reposition.
    Normally, if a pilot nudges the sticks during an autonomous landing, precision landing might be disabled. Setting this bit allows the autopilot to resume tracking the target even after the pilot has manually moved the vehicle.
  • Bit 2 (Value 4): Maintain high speed in final descent.
    Prevents the vehicle from slowing down to a very cautious descent rate as it nears the target, which is often required for landing on moving ships where "sticking the landing" quickly is safer than hovering close to a moving deck.

The Engineer's View

In AC_PrecLand.cpp, this maps to the _options member.

  • Moving Target Logic: Checked in AC_PrecLand::get_target_velocity(). If bit 0 is not set, the target velocity is always assumed to be zero, which simplifies the Kalman filter state transitions.
  • Manual Reposition: This bit is typically checked in the vehicle-specific mode_land.cpp.
  • High Speed Descent: Affects the velocity constraints in the final stages of the land mission.

Tuning & Behavior

  • Bit 0 (1): Highly Recommended if landing on a boat or a moving ground vehicle. Requires an EKF-based estimator (PLND_EST_TYPE=1).
  • Bit 1 (2): Useful for search-and-rescue or research missions where a pilot might want to move the drone slightly but still use the automated target centering.
  • Bit 2 (4): Use with caution. Only recommended for expert users landing on highly dynamic platforms.

PLND_ORIENT

Rotation
Default 25
Range null

Camera Orientation (PLND_ORIENT)

Description

This parameter defines the physical mounting orientation of the camera or IR sensor used for precision landing. It tells the autopilot which direction the sensor is "looking" relative to the front of the aircraft.

Correct orientation is vital for the navigation math to work. If the sensor is pointing down but the software thinks it's pointing forward, the drone will attempt to fly in the wrong direction to center the target.

The Mathematics

The autopilot uses this rotation matrix ($R\_{orient}$) to transform the raw vector reported by the sensor ($V\_{raw}$) into the body-frame coordinate system ($V\_{body}$).

$$ V\_{body} = R\_{orient} \times V\_{raw} $$

This ensures that regardless of how the sensor is mounted, the "Error X" and "Error Y" inputs to the landing controller are always relative to the vehicle's Forward and Right axes.

The Engineer's View

In AC_PrecLand::retrieve_los_meas() (libraries/AC_PrecLand/AC_PrecLand.cpp):

  1. The code retrieves the unit vector from the sensor backend.
  2. If the orientation is not the default PITCH_270 (Down), it performs a multi-step rotation:
    • First, it rotates by PITCH_90 to bring the vector from a default "downward" assumption to "forward."
    • Then, it applies the user-configured _orient rotation.
  3. This internal normalization allows the backend drivers to report vectors in a consistent frame while the user has the flexibility to mount hardware in various configurations.

Tuning & Behavior

  • Default Value: 25 (Rotation_Pitch_270 - Looking Down).
  • Rover Default: 0 (Rotation_None - Looking Forward).
  • Common Values:
    • 25: Downward (Standard for Copter/QuadPlane).
    • 0: Forward (Looking ahead, common for Rover or Plane-approach).
    • 4: Backward (Looking behind).
  • Reboot Required: Yes.

PLND_RET_BEHAVE

Option
Default 0
Range 0 1

PrecLand retry behaviour (PLND_RET_BEHAVE)

Description

This parameter defines the "Targeting Strategy" used during a Precision Landing retry. If the vehicle loses sight of the landing target and PLND_STRICT is set to retry, the drone will climb and reposition itself to re-acquire the signal. This parameter tells the drone where to go during that climb.

  • 0: Go to Target Location. The drone moves to the last estimated GPS coordinate of the landing target itself.
  • 1: Go to Last Vehicle Location. The drone moves back to the GPS coordinate where the vehicle was at the moment it last had a solid lock on the target.

The Mathematics

Regardless of the strategy chosen, the retry logic adds a hardcoded vertical climb offset ($H\_{retry}$) to ensure the sensor has a wider field of view for re-acquisition.

$$ Z\_{target} = Z\_{last\_valid} - 1.5\text{m} $$
(Note: In NED coordinates, negative Z is up).

The horizontal (XY) coordinates are determined by the PLND_RET_BEHAVE selection:

  • Mode 0: $XY\_{retry} = XY\_{target\_last\_seen}$
  • Mode 1: $XY\_{retry} = XY\_{vehicle\_at\_last\_seen}$

The Engineer's View

In AC_PrecLand_StateMachine::retry_landing() (libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp):

  1. The code reads the behavior preference.
  2. If set to GO_TO_TARGET_LOC (0), it calls _precland->get_last_detected_landing_pos().
  3. If set to GO_TO_LAST_LOC (1), it calls _precland->get_last_vehicle_pos_when_target_detected().
  4. The state machine then enters the RETRYING status, commanding the position controller to converge on this 3D point. Once the drone is within 0.75m of the goal, it attempts to descend again.

Tuning & Behavior

  • 0 (Default): Usually best for stationary targets. If the drone was slightly off-center, it will move directly over the last known pad location.
  • 1: Better for moving targets (like a boat) or if the landing sensor has a narrow field of view. Moving the drone back to where it knows it could see the target is often more reliable than moving to where it thinks the target was.

PLND_RET_MAX

Default 4
Range 0 10

Precision Land Maximum Retries (PLND_RET_MAX)

Description

PLND_RET_MAX limits how many "Bail-Outs" the drone is allowed to perform.

If the drone loses the target while landing (due to glare, blockage, etc.), and PLND_STRICT is set to 1 (Retry), the drone will climb back up to its staging altitude and try again. This parameter ensures the drone doesn't do this forever and waste its battery.

  • Default Value: 4 retries.
  • 0: Disable retries. The drone will follow the PLND_STRICT fallback on the first loss.

Tuning & Behavior

  • Default Value: 4.
  • Recommendation: Leave at 4. If the drone hasn't found the target after 4 tries, it's statistically unlikely to find it on the 5th, and it's better to land or RTL.

PLND_STRICT

Default 1
Range 0 2

Precision Landing Strictness (PLND_STRICT)

Description

PLND_STRICT decides the "Plan B" if the drone loses sight of its landing target.

Sometimes the target is obscured by grass, glare, or a temporary sensor glitch.

  • 0: Land Vertically (Not strict). If the target is lost, the drone just lands wherever it is.
  • 1: Retry Landing (Normal). If the target is lost, the drone will stop descending, potentially climb back up, and try to re-acquire the target.
  • 2: Just Hover (Very Strict). The drone will never land unless it can see the target. If the target is lost, it will hover indefinitely (or until failsafe triggers).

Tuning & Behavior

  • Default Value: 1.
  • Recommendation: Use 1 for most autonomous missions. Use 2 for high-value payloads where landing on bare earth (instead of the pad) is unacceptable.

PLND_TIMEOUT

s
Default 4
Range 0 20

PrecLand retry timeout (PLND_TIMEOUT)

Description

This parameter sets the "Grace Period" for target loss during a precision landing. It defines how many seconds the vehicle is allowed to continue its descent after it stops seeing the landing target.

If the target reappears within this window, the landing continues normally. If the timeout expires and the target is still missing, the vehicle will take action based on PLND_STRICT (usually climbing back up for a retry or switching to a standard land).

The Mathematics

The system maintains a timer ($t\_{lost}$) that resets whenever a valid target measurement is received.

$$ \text{IF } (t\_{now} - t\_{last\_seen} > PLND\_TIMEOUT) \rightarrow \text{Trigger Retry Action} $$

This duration allows the vehicle to "fly through" brief sensor outages caused by sun glare, dust, or momentary signal blockage.

The Engineer's View

In AC_PrecLand.cpp, this maps to _retry_timeout_sec.
The TargetState transitions from TARGET_FOUND to TARGET_RECENTLY_LOST as soon as the sensor data stops. The landing state machine (often implemented in the vehicle's mode_land.cpp) checks this timeout.

  • Note that AC_PrecLand also has a hardcoded LANDING_TARGET_TIMEOUT_MS (2000ms) which controls the "Healthy" status of the sensor itself, but PLND_TIMEOUT is the user-tunable delay for the physical landing behavior.

Tuning & Behavior

  • Default Value: 4 seconds.
  • Agile Aircraft: Can use a shorter timeout (e.g., 2s) to initiate retries faster.
  • High Dust/Shadow Environments: Increase to 5-8 seconds to allow the vehicle to drop through the obscuration and hope the target reappears at a lower altitude.
  • 0: Disables the grace period; a retry is triggered as soon as the sensor misses a frame.

PLND_TYPE

Default 0
Range 0 4

Precision Landing Type (PLND_TYPE)

Description

PLND_TYPE tells the autopilot what kind of eye it's using to find the landing target.

  • 0: None.
  • 1: MAVLink. The drone receives target coordinates from an external computer or camera (e.g. OpenMV) via a telemetry port.
  • 2: IRLock. Specifically for the MarkOne IRLock sensor (IR Beacon).
  • 4: SITL. Simulation mode for testing.

Tuning & Behavior

  • Reboot Required: Yes.

PLND_XY_DIST_MAX

m
Default 2.5
Range 0 10.0

Precision Land Maximum Start Distance (PLND_XY_DIST_MAX)

Description

PLND_XY_DIST_MAX is a "Descent Lock."

When the drone arrives at the landing site and sees the target, it must first align itself horizontally. If the drone is too far to the side (e.g. 5 meters away), starting the descent would cause it to land at an angle or miss the pad.

This parameter tells the drone: "Do not start moving down until you are within X meters of the center of the target."

  • Default Value: 2.5 meters.
  • Safety: Setting this to 0 disables the check, and the drone will descend immediately while still trying to fix its horizontal position.

The Engineer's View

Used in the Precision Landing state machine. While the horizontal error is greater than this value, the vertical velocity demand is held at 0 (or a very low "Wait" value). Once the error drops below the threshold, the Land stage is permitted to proceed with its standard vertical descent profile.

Tuning & Behavior

  • Default Value: 2.5m.
  • Precision: If you have a very small landing pad (e.g. 1 meter wide), decrease this to 1.0m to ensure a perfectly centered approach.
  • Windy Sites: If the wind is strong and the drone is struggling to get perfectly centered, increase this to 4.0m to prevent the drone from "hanging" indefinitely at height.

PLND_YAW_ALIGN

cdeg
Default 0
Range 0 36000

Precision Landing Yaw Alignment (PLND_YAW_ALIGN)

Description

PLND_YAW_ALIGN is used if your landing camera isn't pointing perfectly straight forward.

If you mounted your sensor rotated (e.g., 90 degrees sideways to fit the frame), the "Forward" direction in the camera view would actually be the drone's "Left" direction. This parameter allows you to correct that rotation in software.

  • Units: Centi-degrees (100 = 1 degree).

Tuning & Behavior

  • Default Value: 0.
  • Tuning: If you command the drone to move "Forward" toward the target, but it moves "Sideways" instead, your alignment is wrong.