Is there a way to control a servo with the script function with the ground station

Hello
I have servos controlled by a lua script
it takes the position of 2 x 3 positions rc switch and sends an impulse following the rc position to activate an electromagnet
mode works and controls 4 hatches with the rc
servo 4 → function 94
servo 5 → function 95
servo 6 → function 96
servo 7 → function 97
But I would also like to control these servos with the ground station
when I try I have for example the error :
ServoRelayEvent: Channel 6 is already in use
Is there a way or a trick to control a servo assigned to a script with the ground station?
Or maybe I’m going in the wrong direction?
And that I’m not doing it the right way?
i am new with ardupilot
if anyone can help me or guide me

The idea is
RC :
3 positions switch 1
3 positions switch 2
Pixhawk servos 4 to 7 withs functions 43 to 97
an a lua script
rc switch 1-> position 1 activate servo 4 50ms / position 2 off / position 3 activate servo 5 50ms
rc switch 2-> position 1 activate servo 6 50ms / position 2 off / position 3 activate servo 7 50ms

local scripting_rc_1 = rc:find_channel_for_option(300) --RC Channel Gauche (10)
local scripting_rc_2 = rc:find_channel_for_option(301) --RC Channel Droit (11)
local sw1_prev_pos = 9
local sw2_prev_pos = 9
local lock_relays = 0
local T_AVD = 94 --Servo output function T_AVD
local T_AVD_channel = SRV_Channels:find_channel(T_AVD) --T_AVD Servo Channel
local T_ARD = 95 --Servo output function T_ARD
local T_ARD_channel = SRV_Channels:find_channel(T_ARD) --T_ARD Servo Channel
local T_AVG = 96 --Servo output function T_AVG
local T_AVG_channel = SRV_Channels:find_channel(T_AVG) --T_AVG Servo Channel
local T_ARG = 97 --Servo output function T_ARG
local T_ARG_channel = SRV_Channels:find_channel(T_ARG) --T_ARG Servo Channel
--local chan_debug = 1

function update()
  lock_relays = 0
  SRV_Channels:set_output_pwm(T_AVG, 1100) --Init T_AVG Servo
  SRV_Channels:set_output_pwm(T_ARG, 1100) --Init T_ARG Servo
  SRV_Channels:set_output_pwm(T_AVD, 1100) --Init T_AVG Servo
  SRV_Channels:set_output_pwm(T_ARD, 1100) --Init T_ARG Servo

  -- Ouverture des trappes gauches en fonction des switchs
  if (scripting_rc_1) then
    local sw1_pos = scripting_rc_1:get_aux_switch_pos()
    if (sw1_pos ~= sw1_prev_pos) then
      if (sw1_pos == 0 and sw1_prev_pos ~= 9 and lock_relays == 0) then
        lock_relays = 1
        sw1_prev_pos = sw1_pos
        gcs:send_text(0, "Ouverture trappe avant gauche")
        SRV_Channels:set_output_pwm_chan_timeout(T_AVG_channel, 1900, 50)
      elseif (sw1_pos == 1) then
        sw1_prev_pos = sw1_pos
        SRV_Channels:set_output_pwm(T_AVG, 1100)
        SRV_Channels:set_output_pwm(T_ARG, 1100)
        gcs:send_text(0, "Reinitialisation des trappes gauche")
        lock_relays = 0	  
      elseif (sw1_pos == 2 and sw1_prev_pos ~= 9 and lock_relays == 0) then
        lock_relays = 1
        sw1_prev_pos = sw1_pos
        gcs:send_text(0, "Ouverture trappe arriere gauche")
        SRV_Channels:set_output_pwm_chan_timeout(T_ARG_channel, 1900, 50)
      end
    end
  end

  -- Ouverture des trappes droites en fonction des switchs
  if (scripting_rc_2) then
    local sw2_pos = scripting_rc_2:get_aux_switch_pos()
    if (sw2_pos ~= sw2_prev_pos) then
      if (sw2_pos == 0 and sw2_prev_pos ~= 9 and lock_relays == 0) then
        lock_relays = 1
        sw2_prev_pos = sw2_pos
        gcs:send_text(0, "Ouverture trappe avant droite")
        SRV_Channels:set_output_pwm_chan_timeout(T_AVD_channel, 1900, 50)
      elseif (sw2_pos == 1) then
        sw2_prev_pos = sw2_pos
        SRV_Channels:set_output_pwm(T_AVD, 1100)
        SRV_Channels:set_output_pwm(T_ARD, 1100)
        gcs:send_text(0, "Reinitialisation des trappes droite")
        lock_relays = 0	  
      elseif (sw2_pos == 2 and sw2_prev_pos ~= 9 and lock_relays == 0) then
        lock_relays = 1
        sw2_prev_pos = sw2_pos
        gcs:send_text(0, "Ouverture trappe arriere droite")
        SRV_Channels:set_output_pwm_chan_timeout(T_ARD_channel, 1900, 50)
      end
    end
  end

  return update, 50 -- reschedules the loop
end

return update()

This part works as I want, I just wish I could activate the servos with a ground station (Carp Pilot / it’s for a bait boat ) and also with RC

thank you in advance
Best regards, Stephane

You can send the RC_CHANNELS_OVERRIDE MAVLink message from GCS.
This overrides the required RC input channel.

Thank you ,
I need to see if Carp Pilot allows it. for now I just saw the function to control servos pwm