/********************************************************************************************************* Title : C file for the rc ppm encoder (servo2ppm_v4_2.c) Author: Chris Efstathiou E-mail: hendrix at vivodinet dot gr Homepage: ........................ Date: 3/Aug/2009 Compiler: AVR-GCC with AVR-AS MCU type: ATmega168 Comments: This software is FREE. Use it at your own risk. *********************************************************************************************************/ /********************************************************************************************************/ /* PREPROCESSOR DIRECTIVES */ /********************************************************************************************************/ #include #include #include #include #include #include "servo2ppm_settings.h" /********************************************************************************************************/ /* Normaly you shouldn't need to change anything below this line but who knows? */ /********************************************************************************************************/ #define RC_SERVO_PORT D /* The port for the servo pulse input. */ #define RC_LED_PORT B /* The port for the PPM waveform and the led. */ #define RC_LED_PIN 0 /* The led indicator pin. */ #define RC_PPM_PORT B #define RC_PPM_PIN 2 /* The PPM waveform output pin */ #define RC_MUX_PORT B /* The port for the MUX controller. */ #define RC_MUX_PIN 1 /* The pin to control the MUX. */ #define RC_SETUP_PORT B #define RC_SETUP_PIN 4 #define RC_TIMER0_TIMSK TIMSK0 /* Timer0 registers */ #define RC_TIMER0_TIFR TIFR0 #define RC_TIMER0_PRESCALER_REG TCCR0B #define RC_TIMER1_TIMSK TIMSK1 /* Timer1 registers */ #define RC_TIMER1_TIFR TIFR1 #define RC_TIMER1_PRESCALER_REG TCCR1B #define RC_TIMER1_MODE_REG TCCR1A #define RC_TIMER1_COMP1_REG OCR1A #define RC_TIMER1_COMP2_REG OCR1B #define RC_PIN_INT_EN_REG PCICR #define RC_PIN_INT_EN_BIT PCIE2 #define RC_PIN_INT_FLAG_REG PCIFR #define RC_PIN_INT_FLAG_BIT PCIF2 #define RC_PIN_INT_MASK_REG PCMSK2 #define RC_SERVO_INPUT_CHANNELS 8 /* You can copy the above avr type data and edit them as needed if you plan to use a different avr type cpu having at least 2k bytes of flash memory. */ #define _CONCAT2_(a, b) a ## b #define CONCAT2(a, b) _CONCAT2_(a, b) #define RC_SERVO_PORT_OUT_REG CONCAT2(PORT, RC_SERVO_PORT) #define RC_SERVO_PORT_DDR_REG CONCAT2(DDR, RC_SERVO_PORT) #define RC_SERVO_PORT_PIN_REG CONCAT2(PIN, RC_SERVO_PORT) #define RC_LED_PORT_OUT_REG CONCAT2(PORT, RC_LED_PORT) #define RC_LED_PORT_DDR_REG CONCAT2(DDR, RC_LED_PORT) #define RC_LED_PORT_PIN_REG CONCAT2(PIN, RC_LED_PORT) #define RC_MUX_PORT_OUT_REG CONCAT2(PORT, RC_MUX_PORT) #define RC_MUX_PORT_DDR_REG CONCAT2(DDR, RC_MUX_PORT) #define RC_MUX_PORT_PIN_REG CONCAT2(PIN, RC_MUX_PORT) #define RC_PPM_PORT_OUT_REG CONCAT2(PORT, RC_PPM_PORT) #define RC_PPM_PORT_DDR_REG CONCAT2(DDR, RC_PPM_PORT) #define RC_PPM_PORT_PIN_REG CONCAT2(PIN, RC_PPM_PORT) #define RC_SETUP_PORT_OUT_REG CONCAT2(PORT, RC_SETUP_PORT) #define RC_SETUP_DDR_REG CONCAT2(DDR, RC_SETUP_PORT) #define RC_SETUP_PIN_REG CONCAT2(PIN, RC_SETUP_PORT) #if RC_PPM_GEN_CHANNELS > 8 #error PPM generator max number of channels is 8 #endif #if RC_PPM_GEN_CHANNELS == 0 #error PPM generator channels cannot be zero! #endif #if RC_PPM_GEN_CHANNELS < RC_SERVO_INPUT_CHANNELS #undef RC_SERVO_INPUT_CHANNELS #define RC_SERVO_INPUT_CHANNELS RC_PPM_GEN_CHANNELS #warning servo channels = PPM generator channels #endif #if RC_PPM_RESET_PW == 0 && RC_PPM_FRAME_LENGTH_MS == 0 #undef RC_PPM_FRAME_LENGTH_MS #undef RC_PPM_RESET_PW #define RC_PPM_RESET_PW (23500UL - (8 * RC_SERVO_CENTER_PW)) #define RC_PPM_FRAME_LENGTH_MS (RC_PPM_RESET_PW + (RC_PPM_GEN_CHANNELS * RC_SERVO_CENTER_PW)) #elif RC_PPM_FRAME_LENGTH_MS == 0 && RC_PPM_RESET_PW > 0 #undef RC_PPM_FRAME_LENGTH_MS #define RC_PPM_FRAME_LENGTH_MS ((RC_PPM_GEN_CHANNELS * RC_SERVO_CENTER_PW)+RC_PPM_RESET_PW) #elif RC_PPM_FRAME_LENGTH_MS > 0 && RC_PPM_RESET_PW == 0 #undef RC_PPM_RESET_PW #define RC_PPM_RESET_PW (RC_PPM_FRAME_LENGTH_MS -(RC_PPM_GEN_CHANNELS * RC_SERVO_CENTER_PW)) #endif #if RC_PPM_FRAME_LENGTH_MS > 25000UL #warning PPM frame period exceeds 25ms #endif #if RC_PPM_RESET_PW <= (5000UL + RC_PPM_CHANNEL_SYNC_PW) #warning PPM reset period lower than 5ms #endif /* Search for a suitable timer prescaler. Both timers must use the same prescaling factor. */ #if ((F_CPU * (RC_MAX_TIMEOUT/1000))/1000) < 0xFFF0 #define TIMER0_PRESCALER 1 #define TIMER0_PRESCALER_BITS ((0< 255) #error RC_MAX_TIMEOUT is set too high! #endif #define RC_LED_FREQUENCY_VAL (((1000000/RC_LED_FREQUENCY)/23500)/2) //each frame is 23,5 ms #if RC_LED_FREQUENCY_VAL <= 0 #undef RC_LED_FREQUENCY_VAL #define RC_LED_FREQUENCY_VAL 1 #warning LED FREQUENCY set to maximum #endif //It is used when there is no servo signals received so the elapsed time is always RC_MAX_TIMEOUT ms. #define RC_LED_FREQUENCY_VAL_1HZ (((1000000/1)/RC_MAX_TIMEOUT)/2) /* Macro command definitions. */ #define LED_ON() { RC_LED_PORT_OUT_REG |= (1< 1 #error RC_USE_FAILSAFE can be 0 or 1 #endif #if RC_PPM_OUTPUT_TYPE > 1 #error RC_PPM_OUTPUT_TYPE can be 0 or 1 #endif #if RC_CONSTANT_PPM_FRAME_TIME > 1 #error RC_CONSTANT_PPM_FRAME_TIME can be 0 or 1 #endif #if RC_REDUCE_LATENCY > 1 #error RC_REDUCE_LATENCY can be 0 or 1 #endif /********************************************************************************************************/ /* TYPE DEFINITIONS */ /********************************************************************************************************/ /********************************************************************************************************/ /* LOCAL FUNCTION PROTOTYPES */ /********************************************************************************************************/ void initialize_mcu(void); void wait_for_rx(void); unsigned char detect_connected_channels(void); unsigned int get_channel_pw(unsigned char pin); void check_for_setup_mode(void); void write_default_values_to_eeprom(void); void load_failsafe_values(void); void load_values_from_eeprom(void); static inline void ppm_off(void); static inline void ppm_on(void); /********************************************************************************************************/ /* GLOBAL VARIABLES */ /********************************************************************************************************/ volatile unsigned int isr_channel_pw[(RC_PPM_GEN_CHANNELS +1)]; // +1 is for the reset pulse. /* unsigned int fs_channel_pw[8]= { RC_FS_CH_1_TIMER_VAL, RC_FS_CH_2_TIMER_VAL, RC_FS_CH_3_TIMER_VAL, RC_FS_CH_4_TIMER_VAL, RC_FS_CH_5_TIMER_VAL, RC_FS_CH_6_TIMER_VAL, RC_FS_CH_7_TIMER_VAL, RC_FS_CH_8_TIMER_VAL, }; */ const char version_info[]="Servo2ppm V4.20"; volatile unsigned char pin_interrupt_detected = 0; volatile unsigned char isr_channel_number = 0; volatile unsigned int isr_timer0_16 = 0; unsigned char channels_in_use = 0; unsigned char channel_mask = 0; union word2byte{ volatile unsigned int timer0_16; volatile unsigned char timer0[2]; } timer0; volatile unsigned int isr_timer0 = 0; #if RC_CONSTANT_PPM_FRAME_TIME == 1 volatile unsigned int reset_pw = 0; #endif //unsigned char failsafe_mode = 0; unsigned int ppm_off_threshold = RC_PPM_OFF_THRESHOLD_VAL; unsigned char rc_lost_channel = (RC_LOST_CHANNEL-1); //Dummy variable array in order not to use the beggining of the eeprom for usefull data. //The beggining of the eeprom and especially byte 0 is prone to data corruption. // "EEMEM" is equal to "__attribute__((section(".eeprom")))" unsigned int dummy_int[10] __attribute__((section(".eeprom")))= { 1, 1 ,1, 1, 1, 1, 1, 1, 1, 1 }; unsigned int EEMEM ppm_off_threshold_e[11] = { RC_PPM_OFF_THRESHOLD_VAL, RC_PPM_OFF_THRESHOLD_VAL, RC_PPM_OFF_THRESHOLD_VAL, RC_PPM_OFF_THRESHOLD_VAL, RC_PPM_OFF_THRESHOLD_VAL, RC_PPM_OFF_THRESHOLD_VAL, RC_PPM_OFF_THRESHOLD_VAL, RC_PPM_OFF_THRESHOLD_VAL, RC_PPM_OFF_THRESHOLD_VAL, RC_PPM_OFF_THRESHOLD_VAL, RC_PPM_OFF_THRESHOLD_VAL }; unsigned char EEMEM rc_lost_channel_e[11] = { RC_LOST_CHANNEL-1, RC_LOST_CHANNEL-1, RC_LOST_CHANNEL-1, RC_LOST_CHANNEL-1, RC_LOST_CHANNEL-1, RC_LOST_CHANNEL-1, RC_LOST_CHANNEL-1, RC_LOST_CHANNEL-1, RC_LOST_CHANNEL-1, RC_LOST_CHANNEL-1, RC_LOST_CHANNEL-1 }; //unsigned int EEMEM ch_failsafe_pw_e[RC_PPM_GEN_CHANNELS]; /********************************************************************************************************/ /* LOCAL FUNCTION DEFINITIONS */ /********************************************************************************************************/ /*11111111111111111111111111111111111111111111111111111111111111111111111111111111111111111111111111*/ void initialize_mcu(void) { unsigned char x = 0; unsigned int eep_address = 0; asm("cli"); STOP_TIMER0(); RESET_TIMER0(); /* Enable pwm mode 15 (fast pwm with top=OCR1A) and stop the timer. */ /* The timer compare module must be configured before the DDR register. */ // THE PPM GENERATOR IS CONFIGURED HERE ! #if RC_PPM_OUTPUT_TYPE == 0 // NEGATIVE PULSES RC_TIMER1_MODE_REG = (1< 0 void wait_for_rx(void) { unsigned int pw=0; unsigned char x = 0; unsigned char servo_connected = 0; RESET_START_TIMER0(); servo_connected = 0; do{ wdt_reset(); RESET_TIMER0(); x=0; while(timer0.timer0[1] <= RC_MAX_TIMEOUT_VAL ) { if( (RC_SERVO_PORT_PIN_REG & (1<<(RC_RX_READY_CHANNEL-1))) ) { x=timer0.timer0[1]; } if( (timer0.timer0[1] - x) >= RC_PULSE_TIMEOUT_VAL ){ servo_connected = 1; break; } } }while(servo_connected < 1); //Now test the found channel for a proper servo pulse. x = 0; while(1) { pw=get_channel_pw( (RC_RX_READY_CHANNEL-1) ); if( (pw > RC_SERVO_MIN_PW_VAL) && (pw < RC_SERVO_MAX_PW_VAL) ) { x++; }else{ x=0; } if(x >= 3) { break; } } return; } #else void wait_for_rx(void) { unsigned int pw=0; unsigned char x = 0; unsigned char servo_connected = 0; unsigned char channel = 0; RESET_START_TIMER0(); do{ for(channel=0; channel < RC_SERVO_INPUT_CHANNELS; channel++) { wdt_reset(); RESET_TIMER0(); servo_connected = 0; x=0; while(timer0.timer0[1] <= RC_MAX_TIMEOUT_VAL ) { if(RC_SERVO_PORT_PIN_REG & (1<= RC_PULSE_TIMEOUT_VAL ){ servo_connected = 1; break; } } if(servo_connected >= 1){ break; } } }while(servo_connected < 1); //Now test the found channel for a proper servo pulse. x = 0; while(1) { pw=get_channel_pw(channel); if( (pw > RC_SERVO_MIN_PW_VAL) && (pw < RC_SERVO_MAX_PW_VAL) ) { x++; }else{ x=0; } if(x >= 3) { break; } } return; } #endif /*22222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222*/ /*33333333333333333333333333333333333333333333333333333333333333333333333333333333333333333333333333*/ unsigned char detect_connected_channels(void) { unsigned char channel=0; unsigned char servo_connected = 0; unsigned char connected_channels = 0; unsigned char x = 0; unsigned char y = 0; #if defined(RC_RX_READY_CHANNEL) && RC_RX_READY_CHANNEL > 0 unsigned int pw = 0; #endif /* There must be no error in which channels are connected to the encoder because this will have devastating effects later on. */ wdt_reset(); RESET_START_TIMER0(); for(channel=0; channel < RC_SERVO_INPUT_CHANNELS; channel++) { servo_connected = 0; for(y=0; y<5; y++) { wdt_reset(); RESET_TIMER0(); x=0; while(timer0.timer0[1] <= RC_MAX_TIMEOUT_VAL ) { if(RC_SERVO_PORT_PIN_REG & (1<= RC_PULSE_TIMEOUT_VAL ){ servo_connected++; break; } } if(servo_connected >= 3){ channel_mask |= (1< 0 connected_channels = 0; for(channel=0; channel < RC_SERVO_INPUT_CHANNELS; channel++) { if(channel_mask & (1< RC_SERVO_MAX_PW_VAL) { channel_mask &= (~(1<= match_lower_limit ) { if( eeprom_buf_x < RC_SERVO_INPUT_CHANNELS ) { rc_lost_channel = eeprom_buf_x; //Load the stored value to throttle_thershold. if(match < match_upper_limit) { for(x=0; x= match_lower_limit ) { if( (eeprom_buf_x >= RC_PPM_OFF_UPPER_WINDOW_VAL) && (eeprom_buf_x <= RC_SERVO_MAX_PW_VAL) ) { ppm_off_threshold = eeprom_buf_x; //Load the stored value to throttle_thershold. if(match < match_upper_limit) { for(x=0; x < match_upper_limit; x++){ eeprom_write_word(&ppm_off_threshold_e[x], eeprom_buf_x); } } }else if( (eeprom_buf_x <= RC_PPM_OFF_LOWER_WINDOW_VAL) && (eeprom_buf_x >= RC_SERVO_MIN_PW_VAL) ) { ppm_off_threshold = eeprom_buf_x; //Load the stored value to throttle_thershold. if(match < match_upper_limit) { for(x=0; x < match_upper_limit; x++){ eeprom_write_word(&ppm_off_threshold_e[x], eeprom_buf_x); } } }else{ match = 0; } break; } } if( match < match_lower_limit ){ write_default_values_to_eeprom(); return; } return; } /*55555555555555555555555555555555555555555555555555555555555555555555555555555555555555555555555555*/ /*66666666666666666666666666666666666666666666666666666666666666666666666666666666666666666666666666*/ unsigned int get_channel_pw(unsigned char pin) { unsigned int pw = 0; unsigned char pw_measurement_started = 0; wdt_reset(); /* The servo input pins are already configured as inputs with pullup resistors. */ // First we must disable the pin interrupt. RC_PIN_INT_EN_REG &= (~(1<= RC_MAX_TIMEOUT_VAL ) { return(0); } }while( pin_interrupt_detected == 0 ); pin_interrupt_detected = 0; if( RC_SERVO_PORT_PIN_REG & (1< RC_MAX_TIMEOUT_VAL ){setup_mode = 0; break; } } }while(x < 100); if(setup_mode) { /****************************************************************************************************/ /* FIRST WE MUST FIND WHICH CHANNEL WILL BE USED AS A TX SIGNAL LOST INDICATOR */ /****************************************************************************************************/ wdt_reset(); success = 0; if(channels_in_use > 1 ) { if( channel_mask & (1<<(RC_LOST_CHANNEL - 1)) ) { rc_lost_channel = (RC_LOST_CHANNEL - 1); for(x=0; x < (sizeof(rc_lost_channel_e)/sizeof(char)); x++) { eeprom_write_byte(&rc_lost_channel_e[x], rc_lost_channel); } success += 1; } }else if(channels_in_use == 1) { for(x=0; x < RC_SERVO_INPUT_CHANNELS; x++) { if(channel_mask & (1<= RC_SERVO_MIN_PW_VAL && pw <= RC_SERVO_MAX_PW_VAL) { pw_buffer += pw; y++; } } pw_buffer /= y; wdt_reset(); if( (pw_buffer >= RC_PPM_OFF_UPPER_WINDOW_VAL) && (pw_buffer <= RC_SERVO_MAX_PW_VAL) ) { for(x=0; x<(sizeof(ppm_off_threshold_e)/sizeof(int)); x++) { eeprom_write_word(&ppm_off_threshold_e[x], (pw_buffer+RC_PPM_OFF_OFFSET_VAL)); } success += 1; }else if( (pw_buffer <= RC_PPM_OFF_LOWER_WINDOW_VAL) && (pw_buffer >= RC_SERVO_MIN_PW_VAL) ) { for(x=0; x<(sizeof(ppm_off_threshold_e)/sizeof(int)); x++) { eeprom_write_word(&ppm_off_threshold_e[x], (pw_buffer-RC_PPM_OFF_OFFSET_VAL)); } success += 1; } } /****************************************************************************************************/ /* LASTLY WE MUST INDICATE TO THE USER IF THE SETUP PROCEDURE WAS SUCCESSFUL */ /****************************************************************************************************/ if(success == 2) { RC_SETUP_PORT_OUT_REG &= (~(1<= 2 isr_channel_pw[1] = RC_FS_CH_2_TIMER_VAL; #endif #if RC_PPM_GEN_CHANNELS >= 3 isr_channel_pw[2] = RC_FS_CH_3_TIMER_VAL; #endif #if RC_PPM_GEN_CHANNELS >= 4 isr_channel_pw[3] = RC_FS_CH_4_TIMER_VAL; #endif #if RC_PPM_GEN_CHANNELS >= 5 isr_channel_pw[4] = RC_FS_CH_5_TIMER_VAL; #endif #if RC_PPM_GEN_CHANNELS >= 6 isr_channel_pw[5] = RC_FS_CH_6_TIMER_VAL; #endif #if RC_PPM_GEN_CHANNELS >= 7 isr_channel_pw[6] = RC_FS_CH_7_TIMER_VAL; #endif #if RC_PPM_GEN_CHANNELS >= 8 isr_channel_pw[7] = RC_FS_CH_8_TIMER_VAL; #endif #if RC_PPM_GEN_CHANNELS >= 9 isr_channel_pw[8] = RC_FS_CH_8_TIMER_VAL; #endif isr_channel_pw[RC_PPM_GEN_CHANNELS] = RC_RESET_PW_TIMER_VAL; return; } /* void load_failsafe_values(void) { unsigned char x = 0; for(x=0; x< RC_PPM_GEN_CHANNELS; x++) { isr_channel_pw[x] = fs_channel_pw[x]; } // LOAD THE PPM FRAME RESET PULSE WIDTH. isr_channel_pw[RC_PPM_GEN_CHANNELS] = RC_RESET_PW_TIMER_VAL; return; } */ /*88888888888888888888888888888888888888888888888888888888888888888888888888888888888888888888888888*/ /*99999999999999999999999999999999999999999999999999999999999999999999999999999999999999999999999999*/ static inline void ppm_on(void) { RC_TIMER1_PRESCALER_REG &= (~(TIMER1_PRESCALER_BITS)); TCNT1 = 0; isr_channel_number = RC_PPM_GEN_CHANNELS; RC_TIMER1_COMP1_REG = RC_RESET_PW_TIMER_VAL; RC_TIMER1_COMP2_REG = RC_PPM_SYNC_PW_VAL; RC_TIMER1_TIFR |= ( (1<RC_MUX_MIN)&&(PULSE_WIDTHRC_MUX_MIN)&&(PULSE_WIDTH= RC_MAX_TIMEOUT_VAL ) { goto PPM_CONTROL; } }while( pin_interrupt_detected == 0 ); x=0; y=1; //Only pins that changed their state will be tested for a high or low level pin_reg_buffer0 = (RC_SERVO_PORT_PIN_REG & channel_mask_buffer); pin_interrupt_detected = 0; channels_to_check = pin_reg_buffer1 ^ pin_reg_buffer0; pin_reg_buffer1 = pin_reg_buffer0; while(x RC_SERVO_MIN_PW_VAL) && (timer0_buffer < RC_SERVO_MAX_PW_VAL) ) { #if defined(RC_LOST_CHANNEL) && RC_LOST_CHANNEL > 0 if(x == rc_lost_channel) { if(ppm_off_threshold > RC_SERVO_CENTER_PW_VAL) { if(timer0_buffer >= ppm_off_threshold) { channel_mask_buffer = 0xFF; goto PPM_CONTROL; } }else{ if(timer0_buffer <= ppm_off_threshold) { channel_mask_buffer = 0xFF; goto PPM_CONTROL; } } } #endif if(servo_signals_lost == 0) { asm("cli"); //Atomic operation needed here. isr_channel_pw[x] = timer0_buffer; asm("sei"); } } // End of " if( (timer0_buffer > RC_SERVO_MIN_PW_VAL) && ..." statement. } // End of "if( channel_status & y )" statement. } // End of "if( (pin_reg_buffer0 & y) )...else..." statement } // End of "if(channels_to_check & y)" statement. x++; y=(y<<1); } } // End of "while(channel_mask_buffer)" loop. PPM_CONTROL: led_counter++; if( led_counter >= led_frequency ){ led_counter = 0; TOGGLE_LED(); } //We need 'RC_MAX_BAD_PPM_FRAMES" consecutive readings in order to change the PPM generator's status. if( channel_mask_buffer == 0 ) //IF ALL CHANNELS HAVE BEEN MEASURED... { tx_signal_lost = 0; if(servo_signals_lost == 1) //IF PREVIOUSLY THE SERVO SIGNAL WAS LOST... { tx_signal_detected++; if(tx_signal_detected > RC_MAX_BAD_PPM_FRAMES) { ppm_on(); servo_signals_lost = 0; LED_ON(); led_counter = 0; led_frequency = RC_LED_FREQUENCY_VAL; } } } else{ //IF NOT ALL CHANNELS HAVE BEEN MEASURED... pin_reg_buffer1 = (RC_SERVO_PORT_PIN_REG & channel_mask); tx_signal_detected = 0; if(servo_signals_lost == 0) { tx_signal_lost++; if(tx_signal_lost > RC_MAX_BAD_PPM_FRAMES) { servo_signals_lost = 1; led_counter = 0; led_frequency = RC_LED_FREQUENCY_VAL_1HZ; #if defined(RC_USE_FAILSAFE) && RC_USE_FAILSAFE == 1 load_failsafe_values(); #else ppm_off(); #endif } } //end of if(servo_signals_lost == 0) statement. } //end of if( x > (channels_in_use/2) ){...}else{...} statement. mux_control(); } //end of while(1) loop. } /********************************************************************************************************/ /* INTERRUPT SERVICE ROUTINES */ /********************************************************************************************************/ //ISR(TIMER0_OVF_vect, ISR_NAKED) ISR(TIMER0_OVF_vect) { timer0.timer0[1]++; return; } /********************************************************************************************************/ /* By using the fast pwm mode 15 which uses the OCR1A value as TOP value and changing the values within the OCR1B interrupt, timing is very accurate because the OCR1A and OCR1B registers are double buffered. This means that although it looks like we modify both registers within the OCR1B interrupt we are actually modifying their buffers and not the actual registers. Both actual registers are updated when the timer reaches the OCR1A (TOP) value automatically. This way the OCR1B interrupt can be delayed as needed without any loss of timing accuracy. */ ISR(TIMER1_COMPB_vect) { asm("sei"); #if RC_CONSTANT_PPM_FRAME_TIME == 1 isr_channel_number++; if( isr_channel_number >= (RC_PPM_GEN_CHANNELS + 1) ) {isr_channel_number = 0; reset_pw = RC_PPM_FRAME_TIMER_VAL; } if(isr_channel_number < RC_PPM_GEN_CHANNELS) { RC_TIMER1_COMP1_REG = isr_channel_pw[isr_channel_number]; reset_pw -= RC_TIMER1_COMP1_REG; }else{ RC_TIMER1_COMP1_REG = reset_pw; } #endif #if RC_CONSTANT_PPM_FRAME_TIME == 0 isr_channel_number++; if( isr_channel_number >= (RC_PPM_GEN_CHANNELS + 1) ) {isr_channel_number = 0; } RC_TIMER1_COMP1_REG = isr_channel_pw[isr_channel_number]; #endif return; } /********************************************************************************************************/ ISR(PCINT2_vect) { timer0.timer0[0]= TCNT0; if( RC_TIMER0_TIFR & (1<