I cannot manually set the depth of the ROV

Hi, I want to set depth for ROV. I use the link set-target-depth-attitude in the code to set the depth, I found that no matter what number I set in the set_target_depth() function, the ROV was never able to reach my preset depth. ROV always maintains depth at a depth of about 15cm from the surface of the water. Why is this? Looking forward to your reply.

"""
Example of how to set target depth in depth hold mode with pymavlink
"""

import time
import math
# Import mavutil
from pymavlink import mavutil
# Imports for attitude
from pymavlink.quaternion import QuaternionBase

def set_target_depth(depth):
    """ Sets the target depth while in depth-hold mode.

    Uses https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT

    'depth' is technically an altitude, so set as negative meters below the surface
        -> set_target_depth(-1.5) # sets target to 1.5m below the water surface.

    """
    master.mav.set_position_target_global_int_send(
        int(1e3 * (time.time() - boot_time)), # ms since boot
        master.target_system, master.target_component,
        coordinate_frame=mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
        type_mask=( # ignore everything except z position
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |
            # DON'T mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE |
            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 |
            # DON'T mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE
        ), lat_int=0, lon_int=0, alt=depth, # (x, y WGS84 frame pos - not used), z [m]
        vx=0, vy=0, vz=0, # velocities in NED frame [m/s] (not used)
        afx=0, afy=0, afz=0, yaw=0, yaw_rate=0
        # accelerations in NED frame [N], yaw, yaw_rate
        #  (all not supported yet, ignored in GCS Mavlink)
    )

def set_target_attitude(roll, pitch, yaw):
    """ Sets the target attitude while in depth-hold mode.

    'roll', 'pitch', and 'yaw' are angles in degrees.

    """
    master.mav.set_attitude_target_send(
        int(1e3 * (time.time() - boot_time)), # ms since boot
        master.target_system, master.target_component,
        # allow throttle to be controlled by depth_hold mode
        mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE,
        # -> attitude quaternion (w, x, y, z | zero-rotation is 1, 0, 0, 0)
        QuaternionBase([math.radians(angle) for angle in (roll, pitch, yaw)]),
        0, 0, 0, 0 # roll rate, pitch rate, yaw rate, thrust
    )

# Create the connection
master = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
boot_time = time.time()
# Wait a heartbeat before sending commands
master.wait_heartbeat()

# arm ArduSub autopilot and wait until confirmed
master.arducopter_arm()
master.motors_armed_wait()

# set the desired operating mode
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 a depth target
set_target_depth(-0.5)
time.sleep(10)

# clean up (disarm) at the end
master.arducopter_disarm()
master.motors_disarmed_wait()

Try commenting out the X_IGNORE and Y_IGNORE lines as well, see this example: Don't ignore position · clydemcqueen/ardusub-gitbook@6b26cd3 · GitHub

ArduSub will ignore the x and y in ALT_HOLD mode – only the z will be used, see: ardupilot/GCS_Mavlink.cpp at master · ArduPilot/ardupilot · GitHub

I hope this helps.
/Clyde

1 Like

Hi @clyde, thanks for picking up on this - that’s a bug, so I’ve raised an issue for it here :slight_smile:

@robotmark in the meantime Clyde’s suggested workaround of not setting the ignore flags of X and Y position should avoid the issue, although maybe put a note in any code that does that that it will need to be modified once you’re using a newer version of ArduSub that has the fix included.

Thank you !

Thank you very much !

For posterity, the fix for this was merged into master at the time, and not backported to older releases, so requires ArduSub >= 4.5.

Hi,

I am trying to send my BlueROV2 running a navigator board a Z value. There is no GPS attached so I’ve specified to ignore x y values. I would like this to work in a local frame, and not require any sort of global positioning. I’ve tried to execute this command in both ALT_HOLD and MANUAL mode, but it doesn’t work. I’ve also tried to manually assign it an x.y position which didn’t seem to work (not shown in the code below but I can attach if it’s helpful). Is there a way to work around not having a GPS and still sending it depth in this way?

Thanks in advance. I’ve pasted the code which doesn’t work below.

import time
# Import mavutil
from pymavlink import mavutil
import sys
import os
sys.path.insert(0, os.path.abspath(os.path.join(os.path.dirname(__file__), '..')))
import utils.bluerov_utils as utils 

def set_target_depth(depth):
    """ Sets the target depth while in depth-hold mode.
     'depth' is technically an altitude, so set as negative meters below the surface
     -> set_target_depth(-1.5) # sets target to 1.5m below the water surface.
     """
    
    master.mav.set_position_target_local_ned_send(
        int(1e3 * (time.time() - boot_time)), # ms since boot
        master.target_system, master.target_component,
        coordinate_frame=mavutil.mavlink.MAV_FRAME_LOCAL_NED,
        type_mask=( # ignore everything except z position
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |
            # DON'T mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE |
            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 |
            # DON'T mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE |
            mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE
        ), x=0, y=0, z=depth,
        vx=0, vy=0, vz=0, # velocities in NED frame [m/s] (not used)
        afx=0, afy=0, afz=0, yaw=0, yaw_rate=0
        # accelerations in NED frame [N], yaw, yaw_rate
        # (all not supported yet, ignored in GCS Mavlink)
    )

# Create the connection
master, armed = utils.arm()


# set the desired operating mode
# this doesn't work in manual mode either, or stabilize
DEPTH_HOLD = 'ALT_HOLD'
mapping = master.mode_mapping()
DEPTH_HOLD_MODE = mapping[DEPTH_HOLD]
for m in mapping:
    print(f"{m}: {mapping[m]}")
while not master.wait_heartbeat().custom_mode == DEPTH_HOLD_MODE:
    master.set_mode(DEPTH_HOLD)
boot_time = time.time()
# set a depth target of 0.5 meters below the surface
set_target_depth(-.5)

# wait for a while at the target depth (adjust time as needed)
time.sleep(10)  # Wait for 30 seconds at the target depth

master = utils.disarm(master)

Hi @shefali, welcome to the forum :slight_smile:

I’ve moved your post here because it’s seemingly on the same topic.
As specified in the solution above, setting just the Z position bit for depth control should work in ArduSub >= 4.5 (which is the current stable). If you want to use it with an older version you’ll need to also comment out the X and Y position ignore bits because they’re treated as a group.

If that doesn’t resolve your issue then there may be other issues with your code. In particular I’d suggest making sure you’re

  1. Waiting specifically for an autopilot heartbeat
  2. Avoiding (or disabling) relevant failsafes
1 Like