Change from 3.7 to 4.3 GUIDED_NOGPS Problem

Currently we have a drone that is built around a Pixhawk PX4 using ArduCopter version 4.3.7. We are interfacing our Pixhawk with a Raspberry Pi4 companion computer that can communicate with the Pixhawk over USB using the Dronekit APIs implemented in Python3. For our application we are flying indoors in a GUIDED_NOGPS flight mode. We are using a Vicon motion capture system to provide translational and attitude feedback to the Raspberry Pi. We use this feedback and our desired state to generate an attitude and percent throttle command. We use the SendAttitudeTarget() Dronekit function to communicate this information to the Pixhawk. For our purposes, since we are inside, we are attempting to set the ‘yaw_rate’ instead of the ‘yaw’, however, given the right bitmap, we are unable to set the yaw_rate (it seems to still want to set the yaw). Does anyone have any insight on how to use the yaw_rate function using SendAttitudeTarget() (See implementation below)?

Another note is that we are using this same function on a UAV that runs ArduCopter version 3.6.12, and the yaw_rate functionality seems to work. So I am wondering if there is something on the ArduCopter side of things that changed from this version to version 4.3.7?

Here is the SendAttitudeTarget() function we are currently using (https://github.com/dronekit/dronekit-python/blob/master/examples/set_attitude_target/set_attitude_target.py)

def SendAttitudeTarget(self, roll_angle=0.0, pitch_angle=0.0, yaw_angle=None, yaw_rate=0.0, use_yaw_rate=False, throttle=0.5):

    #! This value may be unused by vehicle depending on use_yaw_rate

    if yaw_angle is None:

        yaw_angle = self.vehicle_state.attitude['eul_ang']['yaw']



    #! Set up MAV link message

    #  Note: throttle > 0.5 --> Ascend

    #        throttle = 0.5 --> Hold current altitude

    #        throttle < 0.5 --> Descend

    msg = self.vehicle.message_factory.set_attitude_target_encode(

        0, # time_boot_ms

        1, # target system

        1, # target component

        0b00000000 if use_yaw_rate else 0b00000100,

        self.RadiansToQuaternions(roll_angle, pitch_angle, yaw_angle),

        0, # Body roll rate in rad/s

        0, # Body pitch rate in rad/s

        yaw_rate, # Body yaw rate in rad/s

        throttle  # throttle command

    )



    #! Send the message over mavlink

    self.vehicle.send_mavlink(msg)

Thanks in advance!