Depth Hold Mode Does Not Hold at 1 Meter How to Set Target Depth Autonomously?

Hi everyone,

I’m using a Pixhawk with ArduSub installed. My goal is to operate the vehicle in Depth Hold mode and keep it exactly at 1 meter depth. However, the vehicle consistently stabilizes at the bottom of a 2-meter pool, even though the target depth is set to 1.0 meter in the code.

Below is the full Python code I’m using. I’m sending a target depth via set_position_target_local_ned_send() and switching to ALT_HOLD mode (which I understand corresponds to Depth Hold in ArduSub).

I don’t use a joystick because the system needs to be fully autonomous. According to the ArduSub documentation, Depth Hold mode maintains the current depth unless a manual dive/surface command is given. What I’m unsure about is whether this mode supports external depth targeting or not.

Here’s the full code:

#!/usr/bin/env python3
# -- coding: utf-8 --

from pymavlink import mavutil
import time
time.sleep(15)

TARGET_DEPTH = 1.0  # meters
P0 = None           # surface pressure reference
last_send_time = 0

print("Connecting to Pixhawk...")
master = mavutil.mavlink_connection('/dev/ttyACM0', baud=57600)
master.wait_heartbeat()
print("Connected.")

def arm_vehicle():
    master.mav.command_long_send(
        master.target_system,
        master.target_component,
        mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
        0,
        1, 0, 0, 0, 0, 0, 0
    )
    print("ARM command sent.")

def set_alt_hold_mode():
    master.mav.set_mode_send(
        master.target_system,
        mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
        2  # ALT_HOLD
    )
    print("ALT_HOLD mode set.")

def calculate_depth(p_hPa, P0_hPa):
    rho = 997.0
    g = 9.80665
    delta_p = (p_hPa - P0_hPa) * 100  # Convert to Pa
    h = delta_p / (rho * g)
    return max(0.0, h)

def send_target_depth(target_depth):
    target_z = target_depth  # In NED: positive Z is downward
    master.mav.set_position_target_local_ned_send(
        int(time.time() * 1000),
        master.target_system,
        master.target_component,
        mavutil.mavlink.MAV_FRAME_LOCAL_NED,
        0b0000111111111000,  # Only position control
        0, 0, target_z,
        0, 0, 0,
        0, 0, 0,
        0, 0
    )
    print(f"Target depth sent: {target_depth:.2f} m")

arm_vehicle()
time.sleep(1)
set_alt_hold_mode()
time.sleep(1)

print("Reading pressure and calculating depth...")

while True:
    msg = master.recv_match(type='SCALED_PRESSURE2', blocking=False)
    if msg and msg.press_abs > 0:
        pressure = msg.press_abs

        if P0 is None:
            P0 = pressure
            print(f"Calibration complete: P0 = {P0:.2f} hPa")
            continue

        depth = calculate_depth(pressure, P0)
        print(f"Current depth: {depth:.2f} m")

    if time.time() - last_send_time > 1.0:
        send_target_depth(TARGET_DEPTH)
        last_send_time = time.time()

    time.sleep(0.05)

Even though TARGET_DEPTH is set to 1.0 meter, the vehicle always stabilizes at the pool floor (about 2 meters). So I’m wondering if the depth setpoint is being ignored because of how Depth Hold mode works.

This system must operate autonomously — so I cannot use a joystick to command the desired depth.

From the ArduSub documentation:

“In Depth Hold mode, the vehicle will maintain its current depth unless commanded to dive or surface. It will also maintain its current heading unless commanded otherwise.”

So, my question is:

Is it possible to set a specific target depth programmatically while in Depth Hold mode, or is this mode limited to holding the current depth only?
If this is not possible, what would be the recommended approach to hold a precise depth autonomously?


Also, I have a question about how Depth Hold mode works in QGroundControl:

If I switch to Depth Hold mode manually from the QGroundControl interface,
how does the vehicle determine which depth to hold?
Is it simply the current depth at the moment the mode is activated?

Is there any way to see or configure the target depth within QGroundControl itself?

I’ve read that in Depth Hold mode, the vehicle holds its depth unless a dive or surface command is given,
but I’d like to confirm if it always holds whatever depth it was at when entering the mode — and if so, how to verify or control that behavior more precisely?

Thanks

Hi again,
During today’s pool test, only 1 motor worked at first, then 2 motors started spinning, but the other 2 vertical thrusters didn’t work at all. The vehicle still doesn’t hold at 1 meter depth.

I’m using a Pixhawk with ArduSub installed. My vehicle has 8 thrusters (4 horizontal, 4 vertical) and the system must run autonomously — I’m not using a joystick. I’m in ALT_HOLD mode and sending the target depth using set_position_target_local_ned_send(), but it doesn’t seem to have any effect.

I’m not sure how to properly use Depth Hold mode. Could you please help me understand and fix this issue?
Thank you

Yes, as you said, I am working with pymavlink in depth hold mode by sending the target depth using the SET_POSITION_TARGET_GLOBAL_INT message and controlling yaw with the SET_ATTITUDE_TARGET message. I am also focusing on and trying to implement these parts.

Below is an example code I took from the MAVLink documentation on the ArduSub site:

import time
import math
from pymavlink import mavutil
from pymavlink.quaternion import QuaternionBase

def set_target_depth(depth):
    master.mav.set_position_target_global_int_send(
        int(1e3 * (time.time() - boot_time)),
        master.target_system, master.target_component,
        coordinate_frame=mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
        type_mask=(
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |
            # DON'T ignore Z
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE
        ),
        lat_int=0, lon_int=0, alt=depth,
        vx=0, vy=0, vz=0,
        afx=0, afy=0, afz=0, yaw=0, yaw_rate=0
    )

def set_target_attitude(roll, pitch, yaw):
    master.mav.set_attitude_target_send(
        int(1e3 * (time.time() - boot_time)),
        master.target_system, master.target_component,
        mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE,
        QuaternionBase([math.radians(angle) for angle in (roll, pitch, yaw)]),
        0, 0, 0, 0
    )

master = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
boot_time = time.time()
master.wait_heartbeat()

master.arducopter_arm()
master.motors_armed_wait()

DEPTH_HOLD = 'ALT_HOLD'
DEPTH_HOLD_MODE = master.mode_mapping()[DEPTH_HOLD]
while not master.wait_heartbeat().custom_mode == DEPTH_HOLD_MODE:
    master.set_mode(DEPTH_HOLD)

set_target_depth(-0.5)

roll_angle = pitch_angle = 0
for yaw_angle in range(0, 500, 10):
    set_target_attitude(roll_angle, pitch_angle, yaw_angle)
    time.sleep(1)

for yaw_angle in range(500, 0, -30):
    set_target_attitude(roll_angle, pitch_angle, yaw_angle)
    time.sleep(1)

master.arducopter_disarm()
master.motors_disarmed_wait()

My question is: Is it enough to just give the target depth as a negative value in meters here? Do I need any extra setting or conversion, or can I simply keep the target depth stable by sending this value?

Also, I don’t fully understand how to use the Depth Hold mode effectively and stably, especially for maintaining a constant depth like 1 meter. Where do I set the PID or gain parameters? Are these configured inside the Pixhawk or should I handle them in my code? If you have any experience or advice, I would really appreciate it.

Thanks again for your help!

Hi @beyza,

I have combined a couple of your posts, because they’re on the same topic (and shouldn’t be spread across multiple topics, to avoid a confusing trail).

That is correct.

I’m not sure whether this is intentional or an oversight, but setting just the depth target for depth hold mode in ArduSub requires the set_position_target_global_int message - the ..._local_ned message requires AUTO or GUIDED mode.

In addition, only ArduSub >= 4.5 will work with the example code you copied in your last comment - older versions grouped the X/Y/Z position typemasks, in which case all three need to be set to “don’t ignore”, or the command will be ignored.

The autopilot’s default controller gains are generally expected to be sufficient for most users. If you particularly want to change them you can access them via an autopilot parameter modifier (e.g. in BlueOS or QGroundControl), but there isn’t currently any documentation on how to go about efficiently changing the position controller gains.

Hello again,

I am using an 8-motor underwater vehicle with ArduSub v4.5.2 and Pixhawk. The vehicle has 4 vertical thrusters: servo5, servo6, servo7, and servo8.

When I switch to Depth Hold mode via QGroundControl and monitor the PWM outputs, I noticed two main issues:


  1. Issue: servo8 PWM value decreases over time

While Depth Hold is active and the vehicle is maintaining a stable depth, the PWM values for servo5, servo6, and servo7 remain stable. However, servo8’s PWM value starts similar to the others (e.g., around 1735 µs) but decreases gradually after a few seconds—even though there is no change in pressure (depth), eventually dropping to around 1500 µs.

Since the vehicle remains stationary in depth, this decrease only on servo8 seems illogical.


  1. Issue: Large differences between vertical thruster PWM values

Sometimes the PWM values for the thrusters are as follows:

servo5: 1900 µs
servo6: 1740 µs
servo7: 1740 µs
servo8: 1500 µs

I don’t believe there is any mechanical imbalance on the vehicle. I don’t understand why there is such a significant difference between servo5 and servo8.



I monitor the PWM values both from the QGroundControl interface and using pymavlink with the code below. The values match in both sources:

import time
import math
from pymavlink import mavutil
from pymavlink.quaternion import QuaternionBase

# Connection settings
print("Connecting to Pixhawk (/dev/ttyACM0)...")
master = mavutil.mavlink_connection('/dev/ttyACM0', baud=57600)
boot_time = time.time()

# Parameters
TARGET_DEPTH = -1.0  # 1 meter depth (negative direction)
DEPTH_TOLERANCE = 0.01  # 1cm tolerance
MIN_PWM = 1100
MAX_PWM = 2000
SENSOR_FILTER_GAIN = 0.4  # Pressure sensor filter coefficient

print("Waiting for heartbeat...")
master.wait_heartbeat()
print(f"Connection established: SYSID={master.target_system} COMPID={master.target_component}")

def setup_vehicle():
    """Sets up basic vehicle parameters"""
    # Set PID parameters (optimized for depth)
    pid_params = {
        'POS_Z_P': 0.6,
        'POS_Z_I': 0.2,
        'POS_Z_D': 0.1,
        'VEL_Z_P': 2.0,
        'VEL_Z_I': 1.0,
        'VEL_Z_D': 0.0
    }
    
    for param, value in pid_params.items():
        master.mav.param_set_send(
            master.target_system, master.target_component,
            param.encode(),
            value,
            mavutil.mavlink.MAV_PARAM_TYPE_REAL32
        )
        time.sleep(0.1)

def calibrate_sensor():
    """Calibrates the pressure sensor"""
    print("Waiting for calibration...")
    offset = None
    samples = []
    
    while len(samples) < 10:
        msg = master.recv_match(type='GLOBAL_POSITION_INT', blocking=True, timeout=2)
        if msg:
            samples.append(msg.relative_alt / 1000)
            print(f"Calibration sample {len(samples)}: {samples[-1]:.4f}m")
            time.sleep(0.1)
    
    offset = sum(samples) / len(samples)
    print(f"Calibration completed. Offset: {offset:.4f}m")
    return offset

def set_target_depth(depth):
    """Sets the target depth"""
    master.mav.set_position_target_global_int_send(
        int(1e3 * (time.time() - boot_time)),
        master.target_system, master.target_component,
        coordinate_frame=mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
        type_mask=0b111111111000,  # Position control only
        lat_int=0, lon_int=0, alt=depth,
        vx=0, vy=0, vz=0, afx=0, afy=0, afz=0, yaw=0, yaw_rate=0
    )

def get_motor_pwms():
    """Reads motor PWM values"""
    msg = master.recv_match(type='SERVO_OUTPUT_RAW', blocking=True, timeout=1)
    if msg:
        return [getattr(msg, f'servo{i+1}_raw') for i in range(8)]
    return None

def print_status(depth, pwms):
    """Prints system status"""
    print("\033c", end="")  # Clear screen
    print(f"=== UNDERWATER DEPTH CONTROL (1m) ===")
    print(f"Target Depth: {TARGET_DEPTH:.3f}m | Current: {depth:.3f}m")
    print("\nMotor PWM Values:")
    for i in range(4):
        print(f"  Motor {i+1}: {pwms[i]} µs", end="\t")
    print()
    for i in range(4,8):
        print(f"  Motor {i+1}: {pwms[i]} µs", end="\t")
    print("\n")

try:
    # Prepare the vehicle
    setup_vehicle()
    offset = calibrate_sensor()
    filtered_alt = offset
    
    # Arming
    print("Arming...")
    master.arducopter_arm()
    master.motors_armed_wait()
    print("Vehicle armed!")
    
    # Set mode to ALT_HOLD
    master.set_mode('ALT_HOLD')
    print("Switched to ALT_HOLD mode.")
    
    # Set target depth
    set_target_depth(TARGET_DEPTH)
    
    # Main control loop
    while True:
        # Read and filter sensor data
        msg = master.recv_match(type='GLOBAL_POSITION_INT', blocking=True, timeout=0.1)
        if msg:
            raw_alt = msg.relative_alt / 1000
            filtered_alt = (1-SENSOR_FILTER_GAIN)*filtered_alt + SENSOR_FILTER_GAIN*raw_alt
            current_depth = filtered_alt - offset
        
        # Read motor PWM values
        pwms = get_motor_pwms()
        
        # Print status
        if pwms:
            print_status(current_depth, pwms)
        
        # Control loop delay
        time.sleep(0.1)

except KeyboardInterrupt:
    print("\nShutting down...")
    
    # Disarm
    master.arducopter_disarm()
    master.motors_disarmed_wait()
    print("Vehicle disarmed.")

Hi @beyza -
Without .BIN autopilot logs, it’s tough to advise on what might be going on! It seems likely that those PWM values are what are required for the vehicle to remain stable - is that what it does when in the water? If you’re testing in air, note that the control loops will always go a bit crazy, as the vehicle does not move from the thrusters outuput…

A couple of questions:

  1. Does the vehicle start out wobbling, and stabilise to level once that motor’s output is decreased?
  2. Have you checked that the thruster actually works?
    • When the vehicle is off/disarmed, the propeller should be able to move freely when spun by hand
    • If you try actuating just that motor in the Motor Test section of BlueOS (in Vehicle Setup / PWM Outputs), does the motor spin as expected?
2 Likes