Arduino DUE serial input and servo limits?

I am conduction 9 measurements, 4x distance using lidar and 5x pulse widths from a rc remote. as well as outputting 4 pwm signals to servos. i am attempting to switch between current measured pwm and internally stored pwm data.

i am using the rc remote to control servos. the arduino uses interrupts to measure the incoming pulse widths, then out puts that pwm straight to the servos. this works fine

but when i trigger a state with the rc remote, for the servos to use pulse widths that are internally stored in an array, it doesnt work.

it does work if i am only conducting 3 distance measurements (in any configuration, so it is not serial port dependant) but when i add the fourth, it does not output.

why can the arduino do all 9 measurements and output the pwm data if it is directly passed through, and not output stored internal pulse widths, which are the same signals just retrieved from an sd card.
but it works if there are only 3/4 distance measurements active

code:

#include <Servo.h>
#include <TFMini.h>
#include <SPI.h>
#include <SD.h>

// lidar set up
TFMini tfmini1;
TFMini tfmini2;
TFMini tfmini3;
TFMini tfmini4;

// distance sensor variables
long Distance_left, Distance_right, Distance_front, Distance_height;
bool Sensor_flag = 0;

// reciever variables
volatile unsigned long current_time, PWM_time, PWM_Ch1, PWM_Ch2, PWM_Ch3, PWM_Ch4, PWM_Ch5;
volatile byte Previous_state_ch1, Previous_state_ch2, Previous_state_ch3, Previous_state_ch4, Previous_state_ch5;

// PWM output variables
Servo Throttle;
Servo Pitch;
Servo Yaw;
Servo Roll;

// SD card set up
File Data_logger;

// internal logging set-up
const int value_limit = 2500; // limits the data set to 2000 values (20 seconds at 100Hz)
int q = 0;  // coloumn
int z = 0;  // row
int i = 0;  // row counter for logging to sd
int Recorded_value_counter = 0;

// distance read
char distance_sd_read[3]; // max size of the input value
int distance_input[4][value_limit]; // stores 4xlimit values

// pwm read
char PWM_sd_read[3]; // max size of the input value
int PWM_input[4][value_limit]; // stores 4xlimit values


void setup() {
  // put your setup code here, to run once:

  pinMode(LED_BUILTIN, OUTPUT); // set up led indicator

  //set up serial for distance measurement
  Serial.begin(115200);
  Serial1.begin(TFMINI_BAUDRATE); // left
  Serial2.begin(TFMINI_BAUDRATE); // right
  Serial3.begin(TFMINI_BAUDRATE); // right
  tfmini1.begin(&Serial1); // left
  tfmini2.begin(&Serial2); // right
  tfmini3.begin(&Serial3); // front
  tfmini4.begin(&Serial); // height
  delay(100);

  //set up pwm
  attachInterrupt(digitalPinToInterrupt(30), Get_PWM, CHANGE);  // checks interrupt state at pin 30
  attachInterrupt(digitalPinToInterrupt(32), Get_PWM, CHANGE);  // checks interrupt state at pin 32
  attachInterrupt(digitalPinToInterrupt(34), Get_PWM, CHANGE);  // checks interrupt state at pin 34
  attachInterrupt(digitalPinToInterrupt(36), Get_PWM, CHANGE);  // checks interrupt state at pin 36
  attachInterrupt(digitalPinToInterrupt(38), Get_PWM, CHANGE);  // checks interrupt state at pin 38

  // attach servos output to pins
  Roll.attach(8);
  Pitch.attach(9);
  Yaw.attach(10);
  Throttle.attach(11);

  //  SD card set up, slave pin
  SD.begin(52); // set data pin

// read distance
    Data_logger = SD.open("Distance.txt"); storing the data from the sd card, into local arrays
    
    while (Data_logger.available() && z < value_limit)
    {

      if (q == 4)
      {
        q = 0;
        z++;
      }

      distance_sd_read[i] = Data_logger.read();

      if (distance_sd_read[i]  == ' ' )
       {
         distance_sd_read[i] = 0;
         distance_input[q][z] = atoi(distance_sd_read);
         //Serial.print(distance_input[q][z]);
         //Serial.print(" ");
         i = 0;
         q++;
       }
       else
       {
        i++;
       }
    }
     
   Data_logger.close(); 

   Recorded_value_counter = z;
   i = 0;
   q = 0;
   z = 0;


// read PWM
    
    Data_logger = SD.open("RX_PWM.txt");
    
    while (Data_logger.available() && z < value_limit)
    {
      if (q == 4)
      {
        q = 0;
        z++;
      }

      PWM_sd_read[i] = Data_logger.read();

      if (PWM_sd_read[i]  == ' ' )
       {
         PWM_sd_read[i] = 0;
         PWM_input[q][z] = atoi(PWM_sd_read);
        // Serial.print(PWM_input[q][z]);
         //Serial.print(" ");
         i = 0;
         q++;
       }
       else
       {
        i++;
       }     
    }
     
    Data_logger.close();

   i = 0;
   q = 0;
   z = 0;
}

void loop() {
  // put your main code here, to run repeatedly:

  Distance_left = tfmini1.getDistance();  //get distance from sensor
  Distance_right = tfmini2.getDistance();  //get distance from sensor
  Distance_front = tfmini3.getDistance();  //get distance from sensor
  Distance_height = tfmini4.getDistance();  //get distance from sensor

  if (Distance_left > 15000 || Distance_right > 15000 || Distance_front > 15000 || Distance_height > 15000)
  {
    Sensor_flag = 1;
  }
  else
  {
    Sensor_flag = 0;
  }

  if (PWM_Ch5 > 1300 && Sensor_flag == 0 && z <= Recorded_value_counter) //if switch is triggered, start sensorless flight. end at recorded counter limit
  {
      digitalWrite(LED_BUILTIN, HIGH);
      
     Roll.writeMicroseconds(PWM_input[0][z]); // pwm output
     Pitch.writeMicroseconds(PWM_input[1][z]);
     Throttle.writeMicroseconds(PWM_input[2][z]);
     Yaw.writeMicroseconds(PWM_input[3][z]);
     
     z++; // increase data increment    
  }
  else
  {
    Roll.writeMicroseconds(PWM_Ch1);    // output pwm signals to drone for flight, passthrough
    Pitch.writeMicroseconds(PWM_Ch2);
    Throttle.writeMicroseconds(PWM_Ch3);
    Yaw.writeMicroseconds(PWM_Ch4);
    digitalWrite(LED_BUILTIN, LOW);
  }

  delay(10); // sensors run on 10hz

}

void Get_PWM () // get pwm for reciever
{
  current_time = micros();
  //////////////////////////////////////////////////////// Ch1
  if ((PIOD->PIO_PDSR & (0x01 << 9))) // reads port D at pin 30 with address 512, addresses given in Hex
  {
    if (Previous_state_ch1 == 0)
    {
      //Serial.println(PWM_time);
      Previous_state_ch1 = 1;
      PWM_time = current_time;
    }
  }
  else if (Previous_state_ch1 == 1)
  {
    Previous_state_ch1 = 0;
    PWM_Ch1 = current_time - PWM_time;
    //Serial.println(PWM_Ch1);
    if (PWM_Ch1 < 1000)
    {
      PWM_Ch1 = 1000;
    }
    if (PWM_Ch1 > 2000)
    {
      PWM_Ch1 = 2000;
    }
  }

  //////////////////////////////////////////////////////// Ch2
  if ((PIOD->PIO_PDSR & (0x01 << 10))) // reads port D at pin 32 with address 1024
  {
    if (Previous_state_ch2 == 0)
    {
      Previous_state_ch2 = 1;
      PWM_time = current_time;
    }
  }
  else if (Previous_state_ch2 == 1)
  {
    Previous_state_ch2 = 0;
    PWM_Ch2 = current_time - PWM_time;
    if (PWM_Ch2 < 1000)
    {
      PWM_Ch2 = 1000;
    }
    if (PWM_Ch2 > 2000)
    {
      PWM_Ch2 = 2000;
    }
  }

  //////////////////////////////////////////////////////// Ch3
  if ((PIOC->PIO_PDSR & (0x01 << 2))) // reads port D at pin 34 with address 4
  {
    if (Previous_state_ch3 == 0)
    {
      Previous_state_ch3 = 1;
      PWM_time = current_time;
    }
  }
  else if (Previous_state_ch3 == 1)
  {
    Previous_state_ch3 = 0;
    PWM_Ch3 = current_time - PWM_time;
    if (PWM_Ch3 < 1000)
    {
      PWM_Ch3 = 1000;
    }
    if (PWM_Ch3 > 2000)
    {
      PWM_Ch3 = 2000;
    }
  }

  //////////////////////////////////////////////////////// Ch4
  if ((PIOC->PIO_PDSR & (0x01 << 4))) // reads port C at pin 36 with address 8
  {
    if (Previous_state_ch4 == 0)
    {
      Previous_state_ch4 = 1;
      PWM_time = current_time;
    }
  }
  else if (Previous_state_ch4 == 1)
  {
    Previous_state_ch4 = 0;
    PWM_Ch4 = current_time - PWM_time;
    if (PWM_Ch4 < 1000)
    {
      PWM_Ch4 = 1000;
    }
    if (PWM_Ch4 > 2000)
    {
      PWM_Ch4 = 2000;
    }
  }

  //////////////////////////////////////////////////////// Ch5
  if ((PIOC->PIO_PDSR & (0x01 << 6))) // reads port D at pin 38 with address 64
  {
    if (Previous_state_ch5 == 0)
    {
      Previous_state_ch5 = 1;
      PWM_time = current_time;
    }
  }
  else if (Previous_state_ch5 == 1)
  {
    Previous_state_ch5 = 0;
    PWM_Ch5 = current_time - PWM_time;
    if (PWM_Ch5 < 1000)
    {
      PWM_Ch5 = 1000;
    }
    if (PWM_Ch5 > 2000)
    {
      PWM_Ch5 = 2000;
    }
  }
}

Some thoughts:

Remove delay(10) at the end of loop().

I think there is a confusdion in void GET_PWM(), plus write a return; at the end of each of the 3 first sub parts to keep the function as fast as possible e.g:

volatile [b]boolean[/b] Previous_state_ch1, Previous_state_ch2, Previous_state_ch3, Previous_state_ch4, Previous_state_ch5;
//......
if ((PIOD->PIO_PDSR & (0x01 << 9))) // reads port D at pin 30 with address 512, addresses given in Hex
{
  if (Previous_state_ch1 == false)
  {
    //Serial.println(PWM_time);
    Previous_state_ch1 = true;
    PWM_time = current_time;
  }
  else //if (Previous_state_ch1 == true)
  {
    Previous_state_ch1 = false;
    PWM_Ch1 = current_time - PWM_time;
    //Serial.println(PWM_Ch1);
    if (PWM_Ch1 < 1000)
    {
      PWM_Ch1 = 1000;
    }
    else if (PWM_Ch1 > 2000)
    {
      PWM_Ch1 = 2000;
    }
  }
  return;
}

i implemented and tested your suggestions, sadly no success.

the arduino is able to store the values from Get_PWM into their own vars, then using the servo write function, output those stored vars.

when i enable the switch to output pwm signals (that were previously recorded) it does not output anything (i do not have a scope handy to exactly see what is being transmitted)

why is the arduino able to output pwm signals from Get_PWM -> PWM_chX, but not from PWM_input[index_x][index_y], when essentially they're identical.

however, it is able to output values from PWM_input[index_x][index_y], if i only have 3 or less tfminiX.getDistance() commands. regardless of combination of the 3. the moment a 4th is added, it refuses to output from previously stored data.

the z counter is increasing with each loop, so the code executes the commands, but it does not provide any output signal.