PPM Creation Problem [Controlling Quadcopter using ESP8266]

Hi,
Since Saturday we are working on our first Arduino Based Quadcopter. The Controller is an Arduino Nano Running MultiWii 2.3. To receive our RC Data we are using the WiFi Module ESP8266 connected to another Arduino Nano. The Arduino is reading the 4 Values over the Serial (SoftwareSerial) port and converting them to Integers. The next step is to output these Integers as a PPM signal.
Cause we want to use the PPM-Sum feature of MultiWii the two Arduinos are connected by one wire.

The following Code works as expected. By Opening the MultiWii Config GUI we are receiving the Values for THROTTLE, ROLL, PITCH and YAW. If we change one channel another untouched channel moves weird between 1000 and 2000.

Modified Code from iforce2d (Cheap-ass quadcopter build Part 8 - "Receiver" (continued) - YouTube)

#include <SPI.h>
#include <SoftwareSerial.h>
SoftwareSerial mySerial(9, 8); // RX, TX

////////////////////// PPM CONFIGURATION//////////////////////////
#define channel_number 6  //set the number of channels
#define sigPin 2  //set PPM signal output pin on the arduino
#define PPM_FrLen 22500  //set the PPM frame length in microseconds (1ms = 1000µs)
#define PPM_PulseLen 300  //set the pulse length
//////////////////////////////////////////////////////////////////

int ppm[channel_number];

char values[]={'1','2','4','0',0x00};
int package[4];
int valPosition = 0;
int packagePosition=0;

void setPPMValuesFromData()
{

  /*YAW*/
  ppm[0] = package[3];
  /*PITCH*/
  ppm[1] = package[1];
  /*throttle*/
  ppm[2] = package[0];
  /*ROLL*/
  ppm[3] = package[2];
  /*AUX 1*/
  ppm[4] = 1500;
  /*AUX 2*/
  ppm[5] = 1500;
}

/**************************************************/

void setupPPM() {
  pinMode(sigPin, OUTPUT);
  digitalWrite(sigPin, 0);  //set the PPM signal pin to the default state (off)
  cli();
  TCCR1A = 0; // set entire TCCR1 register to 0
  TCCR1B = 0;
  OCR1A = 100;  // compare match register (not very important, sets the timeout for the first interrupt)
  TCCR1B |= (1 << WGM12);  // turn on CTC mode
  TCCR1B |= (1 << CS11);  // 8 prescaler: 0,5 microseconds at 16mhz
  TIMSK1 |= (1 << OCIE1A); // enable timer compare interrupt
  sei();
}

void setup()
{  
  mySerial.begin(9600);
  setupPPM();
  //default values
  package[0] = 1000;
  package[1] = 1200;
  package[2] = 1400;
  package[3] = 1600;
  
}

void loop()
{
  //reading serial data from esp8266 and convert values (from 1000 to 2000) to Integer
  //data format: 1200:2000:1400:1400:E
   if(mySerial.available()) {
   char inChar = mySerial.read(); 
    if((char)inChar== 'E') {
      setPPMValuesFromData();
      packagePosition=0;
    }
    else if((char)inChar==':') {
     long newValue = atol(values);
     package[packagePosition]= newValue;
     valPosition=0;  packagePosition=packagePosition+1;
    }
    else if(inChar >= '0' && inChar <= '9' && valPosition < 4) // is this an ascii digit between 0 and 9?
     {
      values[valPosition] = inChar;
      valPosition=valPosition+1;
    }
  }
  
}


/**************************************************/
//PPM Code (thanks to iforce2d)
//#error This line is here to intentionally cause a compile error. Please make sure you set clockMultiplier below as appropriate, then delete this line.
#define clockMultiplier 2; // set this to 2 if you are using a 16MHz arduino, leave as 1 for an 8MHz arduino

ISR(TIMER1_COMPA_vect){
  static boolean state = true;

  TCNT1 = 0;

  if ( state ) {
    //end pulse
     //digitalWrite(sigPin,0);
    PORTD = PORTD & ~B00000100; // turn pin 2 off. Could also use: digitalWrite(sigPin,0)
    OCR1A = PPM_PulseLen * clockMultiplier;
    state = false;
  }
  else {
    //start pulse
    static byte cur_chan_numb;
    static unsigned int calc_rest;

      //digitalWrite(sigPin,1);
    PORTD = PORTD | B00000100; // turn pin 2 on. Could also use: digitalWrite(sigPin,1)
    state = true;

    if(cur_chan_numb >= channel_number) {
      cur_chan_numb = 0;
      calc_rest += PPM_PulseLen;
      OCR1A = (PPM_FrLen - calc_rest) * clockMultiplier;
      calc_rest = 0;
    }
    else {
      OCR1A = (ppm[cur_chan_numb] - PPM_PulseLen) * clockMultiplier;
      calc_rest += ppm[cur_chan_numb];
      cur_chan_numb++;
    }     
  }
}

The values inside "setPPMValuesFromData" are correct. I checked them using "Serial.println". But as written above, the received PPM-SUM signal is kind of broken. Maybe a performance issue ?

Thanks in advance !