RC_CHANNELS_OVERRIDE not working

BlueROV2(RaspberryPi4B + NAVIGATOR)(No GPS)

I want manual control, but RC_CHANNELS_OVERRIDE not working.
1.Added UDP Client(14551) at “Mavlink Endpoints”.
2.Run the code on RaspberryPi.

from pymavlink import mavutil
import time

master = mavutil.mavlink_connection(‘udpin:localhost:14551’, source_system=1)
master.wait_heartbeat()

master.arducopter_arm()
master.motors_armed_wait()

i = 0
while i < 10:
master.mav.rc_channels_override_send(master.target_system, master.target_component, 1600, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1100, 1100, 1100, 0, 0, 0, 0, 0, 0, 0)
time.sleep(0.5)
i += 1

master.arducopter_disarm()
master.motors_disarmed_wait()

3.I checked the “http://192.168.2.2:6040/mavlink/vehicles/1/components/0/messages/RC_CHANNELS_OVERRIDE”.
{
“message”: {
“chan10_raw”: 1100,
“chan11_raw”: 1100,
“chan12_raw”: 0,
“chan13_raw”: 0,
“chan14_raw”: 0,
“chan15_raw”: 0,
“chan16_raw”: 0,
“chan17_raw”: 0,
“chan18_raw”: 0,
“chan1_raw”: 1600,
“chan2_raw”: 1500,
“chan3_raw”: 1500,
“chan4_raw”: 1500,
“chan5_raw”: 1500,
“chan6_raw”: 1500,
“chan7_raw”: 1500,
“chan8_raw”: 1500,
“chan9_raw”: 1100,
“target_component”: 0,
“target_system”: 1,
“type”: “RC_CHANNELS_OVERRIDE”
},
“status”: {
“time”: {
“counter”: 22,
“first_update”: “2023-05-30T00:09:50.117144636+00:00”,
“frequency”: 0.02663438208401203,
“last_update”: “2023-05-30T00:23:36.574383336+00:00”
}
}
}

4.I checked the “http://192.168.2.2:6040/mavlink/vehicles/1/components/1/messages/RC_CHANNELS
{
“message”: {
“chan10_raw”: 1100,
“chan11_raw”: 1100,
“chan12_raw”: 0,
“chan13_raw”: 0,
“chan14_raw”: 0,
“chan15_raw”: 0,
“chan16_raw”: 0,
“chan17_raw”: 0,
“chan18_raw”: 0,
“chan1_raw”: 1500,
“chan2_raw”: 1500,
“chan3_raw”: 1500,
“chan4_raw”: 1500,
“chan5_raw”: 1500,
“chan6_raw”: 1500,
“chan7_raw”: 1500,
“chan8_raw”: 1500,
“chan9_raw”: 1100,
“chancount”: 0,
“rssi”: 0,
“time_boot_ms”: 1065660,
“type”: “RC_CHANNELS”
},
“status”: {
“time”: {
“counter”: 2128,
“first_update”: “2023-05-30T00:06:58.124794212+00:00”,
“frequency”: 2.0018813610076904,
“last_update”: “2023-05-30T00:24:41.619018972+00:00”
}
}
}

RC_CHANNES is updated even if QGroundControl is not running.
Why are the thrusters not moving?
Is it okay if the Component ID is different?

sorry.
I am not good at English.

solved.
1.Changed mavlink_connection.
2.Changed to wait for Arm/Disarm with HEARTBEAT message.
3.Only HEARTBEAT messages that can determine Arm/Disarm have been received.
There were multiple HEARTBEAT messages with different Types.
QGroundControl is starting, but no controller.
Is there a good way to determine Arm/Disarm?

from pymavlink import mavutil
import time, threading

heartbeat_requirement = mavutil.periodic_event(1)
def heartbeatLoop():
    while True:
        if heartbeat_requirement.trigger():
            master.mav.heartbeat_send(
                mavutil.mavlink.MAV_TYPE_GCS,
                mavutil.mavlink.MAV_AUTOPILOT_INVALID,
                0, 0, 0)

def WaitArmDisarm(arm_disarm):
    while True:
        msg = master.recv_match(type="HEARTBEAT", blocking=True)
        msg = msg.to_dict()
        if msg['autopilot'] == mavutil.mavlink.MAV_AUTOPILOT_ARDUPILOTMEGA:
            if arm_disarm == mavutil.mavlink.MAV_STATE_ACTIVE:
                if msg['system_status'] == mavutil.mavlink.MAV_STATE_ACTIVE:
                    if msg['base_mode'] & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED == mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED:
                        print('Arm!!')
                        break;
            elif arm_disarm == mavutil.mavlink.MAV_STATE_STANDBY:
                if msg['system_status'] == mavutil.mavlink.MAV_STATE_STANDBY:
                    if msg['base_mode'] & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED == 0:
                        print('Disarm!!')
                        break;

master = mavutil.mavlink_connection('udpin:localhost:14551')

hbThread = threading.Thread(target= heartbeatLoop, daemon=True)
hbThread.start()

master.wait_heartbeat()

master.arducopter_arm()
#master.motors_armed_wait()
WaitArmDisarm(mavutil.mavlink.MAV_STATE_ACTIVE)

mode = 'MANUAL'
if mode not in master.mode_mapping():
    print('Unknown mode : {}'.format(mode))
    print('Try:', list(master.mode_mapping().keys()))
    sys.exit(1)
mode_id = master.mode_mapping()[mode]
master.mav.set_mode_send(master.target_system, mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED, mode_id)
while True:
    ack_msg = master.recv_match(type='COMMAND_ACK', blocking=True)
    ack_msg = ack_msg.to_dict()
    if ack_msg['command'] == mavutil.mavlink.MAVLINK_MSG_ID_SET_MODE:
        print('Changed to manual mode.')
        break

#pitch, roll, throttle, yaw, forward, lateral, camera_pan, camera_tilt, lights1, lights2, video_switch
master.mav.rc_channels_override_send(master.target_system, master.target_component, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1100, 1100, 1100, 0, 0, 0, 0, 0, 0, 0)

i = 0
while i < 10:
    master.mav.rc_channels_override_send(master.target_system, master.target_component, 1500, 1700, 1500, 1500, 1500, 1500, 1500, 1500, 1100, 1100, 1100, 0, 0, 0, 0, 0, 0, 0)
    time.sleep(0.5)
    i += 1

master.mav.rc_channels_override_send(master.target_system, master.target_component, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1100, 1100, 1100, 0, 0, 0, 0, 0, 0, 0)

master.arducopter_disarm()
#master.motors_disarmed_wait()
WaitArmDisarm(mavutil.mavlink.MAV_STATE_STANDBY)

I had to add two settings to MAVLink Endpoints
1.Added UDP Client(14551:Enable)
2.Added UDP Server(14551:Disable)
Doing so made motors_armed_wait() and motors_disarmed_wait() work.
It was possible to control from Surface Computer in parallel with QGroundControl.

from pymavlink import mavutil
import time, threading

heartbeat_requirement = mavutil.periodic_event(1)
def heartbeatLoop():
    while True:
        if heartbeat_requirement.trigger():
            master.mav.heartbeat_send(
                mavutil.mavlink.MAV_TYPE_GCS,
                mavutil.mavlink.MAV_AUTOPILOT_INVALID,
                0, 0, 0)

master = mavutil.mavlink_connection('udpin:0.0.0.0:14551')

hbThread = threading.Thread(target= heartbeatLoop, daemon=True)
hbThread.start()

master.wait_heartbeat()

master.arducopter_arm()
master.motors_armed_wait()

mode = 'MANUAL'
if mode not in master.mode_mapping():
    print('Unknown mode : {}'.format(mode))
    print('Try:', list(master.mode_mapping().keys()))
    sys.exit(1)
mode_id = master.mode_mapping()[mode]
master.mav.set_mode_send(master.target_system, mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED, mode_id)
while True:
    ack_msg = master.recv_match(type='COMMAND_ACK', blocking=True)
    ack_msg = ack_msg.to_dict()
    if ack_msg['command'] == mavutil.mavlink.MAVLINK_MSG_ID_SET_MODE:
        print('Changed to manual mode.')
        break

master.mav.rc_channels_override_send(master.target_system, master.target_component, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1100, 1100, 1100, 0, 0, 0, 0, 0, 0, 0)

i = 0
while i < 10:
    master.mav.rc_channels_override_send(master.target_system, master.target_component, 1500, 1500, 1500, 1500, 1510, 1500, 1500, 1500, 1100, 1100, 1100, 0, 0, 0, 0, 0, 0, 0)
    time.sleep(0.5)
    i += 1

master.mav.rc_channels_override_send(master.target_system, master.target_component, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1100, 1100, 1100, 0, 0, 0, 0, 0, 0, 0)

master.arducopter_disarm()
master.motors_disarmed_wait()