Hi @yuki,
The SET_POSITION_TARGET_GLOBAL_INT
MAVLink message (which is used in our example set_target_depth
function) sets the current target for the vehicle to aim for - there’s no requirement to meet/achieve the current target in order for a new target to be specified instead.
That said, using that message currently requires a position-enabled flight mode (like Depth Hold, if you only want to control vertical position, or Guided mode if you want to target horizontal positions/velocities as well), which means it requires a position estimate (from a barometer for depth; or from a DVL, underwater GPS, etc for horizontal control).
Given you’re trying to control horizontal velocity, if you have a positioning sensor then it should work to set velocity targets if you want to, while in guided mode. The current ArduSub implementation requires setting all three (x,y,z) velocity targets together, because if you ignore one it will ignore all of them.
Changing the acceleration commands into force commands is not relevant here, but also wouldn’t work. The force, yaw, and yaw rate options are not currently implemented.
All up,
- If you have a (horizontal) position estimate
- And your vehicle is in Guided flight mode
- You can use the
SET_POSITION_TARGET_GLOBAL_INT
message to set velocity targets - Which should use the following bitmask
type_mask=( # ignore everything except velocity targets mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE | mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE | mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE | # DON'T mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE | # DON'T mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE | # DON'T 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 )
- And should set targets for all of vx, vy, and vz.