Not receiving COMMAND_ACK or MISSION_ACK for some commands in PyMAVLink

I am a beginner so if i explain incorrectly please feel free to correct me or ask for more info on my problem. :slight_smile:
I am trying to control a drone using PyMavLink. The drone has a pixhawk board running arducopter software. V4.5.5 (Newest).
I also have the newest pymavlink version. V2.4.41
My code is this for now:

from pymavlink import mavutil
import time


def connect_to_pixhawk(port='/dev/ttyUSB0', baud=57600):
    # Connect to the Pixhawk
    connection = mavutil.mavlink_connection(port, baud=baud)
    connection.wait_heartbeat()
    print(f"Heartbeat from system (system {connection.target_system} component {connection.target_component})")
    return connection



def change_mode(connection, mode=0):
    try:
        connection.mav.command_long_send(
                connection.target_system,
                connection.target_component,
                176,
                0,
                1, mode, 0, 0, 0, 0, 0)
        ack = connection.recv_match(type='COMMAND_ACK', blocking=True, timeout=5)
        print(ack)
        return ack
    except Exception as e:
        print(e)

def arm(connection, value=1):
    try:
        connection.mav.command_long_send(
                connection.target_system,
                connection.target_component,
                400,
                0,
                value, 0, 0, 0, 0, 0, 0)
        ack = connection.recv_match(type='COMMAND_ACK', blocking=True, timeout=5)
        print(ack)
    except Exception as e:
        print(e)

def takeoff(connection, height):
    connection.mav.command_long_send(
            connection.target_system,
            connection.target_component,
            mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
            0, 0, 0, 0, 0, 0, 0,
            height)

    # Receive and print acknowledgement message for takeoff

    msg = connection.recv_match(type='COMMAND_ACK', blocking=True)

def check_modes(connection):
    print(connection.mode_mapping())


def move(connnection, x,y,z):

    connection.mav.set_position_target_local_ned_encode(0,
            connection.target_system,
            connection.target_component,
            mavutil.mavlink.MAV_FRAME_BODY_FRD, #Relative to drone itself, not north. (Only for forward not rotate)
            64, #Dont Touch
            x, #x
            y, #y
            z, #z
            0, #vx
            0, #vy
            0, #vz
            0, #yaw
            0, #yaw rate
            0,0,0)
    ack = connection.recv_match(type='COMMAND_ACK', blocking=True, timeout=5)
    print(ack)

if __name__ == "__main__":

    connection = connect_to_pixhawk()
    check_modes(connection)
    change_mode(connection, 0)
    time.sleep(1)
    arm(connection, 1)
    time.sleep(1)
    takeoff(connection, 3)
    time.sleep(1)
    move(connection, 2,0,0)
    time.sleep(1)
    move(connection, 0,0,0)
    time.sleep(1)
    arm(connection, 0)

    print("DONE")

I am getting this output:

Heartbeat from system (system 1 component 0)
{'STABILIZE': 0, 'ACRO': 1, 'ALT_HOLD': 2, 'AUTO': 3, 'GUIDED': 4, 'LOITER': 5, 'RTL': 6, 'CIRCLE': 7, 'POSITION': 8, 'LAND': 9, 'OF_LOITER': 10, 'DRIFT': 11, 'SPORT': 13, 'FLIP': 14, 'AUTOTUNE': 15, 'POSHOLD': 16, 'BRAKE': 17, 'THROW': 18, 'AVOID_ADSB': 19, 'GUIDED_NOGPS': 20, 'SMART_RTL': 21, 'FLOWHOLD': 22, 'FOLLOW': 23, 'ZIGZAG': 24, 'SYSTEMID': 25, 'AUTOROTATE': 26, 'AUTO_RTL': 27}
COMMAND_ACK {command : 176, result : 0, progress : 0, result_param2 : 0, target_system : 255, target_component : 0}
COMMAND_ACK {command : 400, result : 0, progress : 0, result_param2 : 0, target_system : 255, target_component : 0}
None
None
COMMAND_ACK {command : 400, result : 0, progress : 0, result_param2 : 0, target_system : 255, target_component : 0}
DONE

I am using a radio antenna to connect the computer running pymavlink and the pixhawk drone. This is because i tried a serial connection but it was unstable.
When I use pymavlink to control the drone, I can arm it, change modes, however I cannot liftoff, move or do anything else with it.
I am not sure if my code is incorrect itself, as some commands work but others return no ACK.

I have been facing this problem for months, and I really couldnt find any answer online, I hope this is a dumb mistake, any help is very appreciated.