Fixed wing guidance with no GPS

I have Skywalker X8 (elevons + throttle) drone with antenna sensor, which tracks the source of the signal. The drone should be guided in the area with no GPS signal. As I understand, SET_POSITION_TARGET_LOCAL_NED and SET_POSITION_TARGET_GLOBAL_INT can’t be used as they both require GPS lock. From what I read on the forum, the only available options could be SET_ATTITUDE_TARGET or RC_CHANNELS_OVERRIDE. I don’t want to use RC_CHANNELS_OVERRID as it’s not essentially a guided mode and requires bulletproof control inside the guidance code to be sure operator can overtake vehicle control. Hence, I focus on SET_ATTITUDE_TARGET now.

However, the SET_ATTITUDE_TARGET command in ArduPlane doesn’t handle roll, yaw, pitch rate parameters. Even though MAVLink documentation claims you can set them, there is no code which processes respective message parameters. You can only ask for roll, pitch, yaw position (attitude) change. I don’t know is it intentional ArduPlane vehicle type doesn’t handle rates, but in my use case it would be way easier to guide aircraft with rate control over attitude control.

Another idiosyncrasy relates to the yaw-to-roll control in the plane with elevons frame type (like Skywalker X8). I’d expect if I set SET_ATTITUDE_TARGET message with yaw parameter, the ArduPilot (ArduPlane) has to take care about coordinated turn and roll (bank) to the necessary angle to achieve the desired attitude. However, that doesn’t happen – the plain doesn’t turn anywhere. I run ArduPilot SITL with Gazebo plugin like this:

$ sim_vehicle.py -v ArduPlane --add-param-file=$HOME/Projects/SITL_Models/Gazebo/config/skywalker_x8.param --model JSON --map --console

Here is an example of the Python code I use to send commands every 2 seconds:

while True:

# RATE - ArduPlane doesn't work with rates
roll_rate_deg  = 0
pitch_rate_deg = 0
yaw_rate_deg   = 0

# POSITION
roll_deg  = 0.0
pitch_deg = 0.0
yaw_deg   = 90.0 # turn right 90°

thrust = 0.5

# https://mavlink.io/en/messages/common.html#ATTITUDE_TARGET_TYPEMASK
# https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/GCS_MAVLink_Plane.cpp#L1319
type_mask = 0b00000000

print(f"Type mask: {bin(type_mask)}")

# Sets a desired vehicle attitude. Used by an external controller to
# command the vehicle (manual controller or other system).
#
# time_boot_ms              : Timestamp (time since system boot). [ms] (type:uint32_t)
# target_system             : System ID (type:uint8_t)
# target_component          : Component ID (type:uint8_t)
# type_mask                 : Bitmap to indicate which dimensions should be ignored by the vehicle. (type:uint8_t, values:ATTITUDE_TARGET_TYPEMASK)
# q                         : Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) (type:float)
# body_roll_rate            : Body roll rate [rad/s] (type:float)
# body_pitch_rate           : Body pitch rate [rad/s] (type:float)
# body_yaw_rate             : Body yaw rate [rad/s] (type:float)
# thrust                    : Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) (type:float)
connection.mav.set_attitude_target_send(
    0, # int(time.time() * 1000) % 4294967296, # ms
    connection.target_system,             # 1
    connection.target_component,          # 1
    type_mask,
    QuaternionBase([math.radians(roll_deg), math.radians(pitch_deg), math.radians(yaw_deg)]),
    0, # math.radians(roll_rate_deg),
    0, # math.radians(pitch_rate_deg),
    0, # math.radians(yaw_rate_deg),
    thrust
)

print(f"SET_ATTITUDE_TARGET (82): roll {roll_deg}°, pitch {pitch_deg}°, yaw {yaw_deg}°, roll_rate {roll_rate_deg}°/s, pitch_rate {pitch_rate_deg}°/s, yaw_rate {yaw_rate_deg}°/s, thrust {thrust}")

time.sleep(2)

I have a suspicion the roll and yaw message parameters compete with each other, but I don’t understand which one has preference. From simulations it feels like the roll parameter has precedence over yaw. However, it’s hard to prove as SET_ATTITUDE_TARGET message doesn’t allow to ignore attitude components independently.

Overall, am I looking in the right direction?