*/ /********************************************************************************************************/ /* PREPROCESSOR DIRECTIVES */ /********************************************************************************************************/ #include #include #include /********************************************************************************************************/ /* USER CONFIGURATION BLOCK START */ /********************************************************************************************************/ #ifndef F_CPU #define F_CPU 8000000UL /* CPU CLOCK FREQUENCY */ #endif #define RC_FAILSAFE_CHANNEL_1 1500UL #define RC_FAILSAFE_CHANNEL_2 1500UL #define RC_FAILSAFE_CHANNEL_3 1000UL #define RC_FAILSAFE_CHANNEL_4 1500UL #define RC_FAILSAFE_CHANNEL_5 1000UL #define RC_FAILSAFE_CHANNEL_6 1000UL #define RC_FAILSAFE_CHANNEL_7 1000UL #define RC_FAILSAFE_CHANNEL_8 1000UL #define RC_USE_FAILSAFE 0 #define RC_PPM_GEN_CHANNELS 8 #define RC_PPM_OUTPUT_TYPE 0 #define RC_CONSTANT_PPM_FRAME_TIME 0 #define RC_DEPTH_OF_PPM_FILTER 0 #define RC_REDUCE_LATENCY 0 #define RC_MIN_PULSE_WIDTH 800UL /* in microseconds */ #define RC_CENTER_PULSE_WIDTH 1500UL /* in microseconds */ #define RC_MAX_PULSE_WIDTH 2200UL /* in microseconds */ #define RC_PPM_CHANNEL_SYNC_PW 300UL /* the width of the PPM channel sync pulse in microseconds. */ #define RC_PPM_RESET_PW 0UL /* Min reset time in microseconds(ie. 7500UL), 0=AUTO */ #define RC_PPM_FRAME_LENGTH_MS 0UL /* Max PPM frame period in microseconds(ie. 23500UL), 0=AUTO */ #define RC_MAX_TIMEOUT 30000UL /* in microseconds, max ~65000 @ 8 mHZ, ~32000 @ 16 Mhz */ #define RC_MAX_BAD_PPM_FRAMES 4 /* Max consecutive bad servo pulse samples before failsafe */ #define RC_LEVEL_CHANGE_SAMPLES 3 /* # of samples to take in order to detect a level change */ #define RC_JITTER_FILTER_WINDOW 20UL /* In microseconds. */ #define RC_LED_FREQUENCY 5UL /* In Hertz, not accurate, min=1, max=you will get a warning */ /********************************************************************************************************/ /* USER CONFIGURATION BLOCK END */ /********************************************************************************************************/ /********************************************************************************************************/ /* Normaly you shouldn't need to change anything below this line but who knows? */ /********************************************************************************************************/ #if defined(__AVR_ATmega168__) #define RC_SERVO_PORT_REG PORTD /* The port for the servo pulse input. */ #define RC_SERVO_PORT_DDR_REG DDRD #define RC_SERVO_PORT_PIN_REG PIND #define RC_LED_PORT_REG PORTB /* The port for the PPM waveform and the led. */ #define RC_LED_PORT_DDR_REG DDRB #define RC_LED_PORT_PIN_REG PINB #define RC_LED_PIN 0 /* The led indicator pin. */ #define RC_PPM_PORT_REG PORTB #define RC_PPM_PORT_DDR_REG DDRB #define RC_PPM_PORT_PIN_REG PINB #define RC_PPM_PIN 2 /* The PPM waveform output pin */ #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 #if (RC_DEPTH_OF_PPM_FILTER * RC_MAX_PULSE_PW_VALUE) > 0xFFF0 #undef RC_DEPTH_OF_PPM_FILTER #define RC_DEPTH_OF_PPM_FILTER ( 0xFFFF / ((((F_CPU/1000) * RC_MAX_PULSE_WIDTH)/1000)/TIMER0_PRESCALER) ) #warning RC_DEPTH_OF_PPM_FILTER set to maximum #endif #else #error AVR type not suitable #endif #if RC_DEPTH_OF_PPM_FILTER > 0 && RC_REDUCE_LATENCY == 1 #undef RC_DEPTH_OF_PPM_FILTER #define RC_DEPTH_OF_PPM_FILTER 0 #warning PPM FILTER cannot be used with RC_REDUCE_LATENCY set to 1 #endif #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_CENTER_PULSE_WIDTH)) #define RC_PPM_FRAME_LENGTH_MS (RC_PPM_RESET_PW + (RC_PPM_GEN_CHANNELS * RC_CENTER_PULSE_WIDTH)) #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_CENTER_PULSE_WIDTH)+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_CENTER_PULSE_WIDTH)) #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 #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 /* Macro command definitions. */ #define PPM_ON() { RC_TIMER1_PRESCALER_REG &= (~(TIMER1_PRESCALER_BITS)); \ TCNT1 = 0; isr_channel_number = RC_PPM_GEN_CHANNELS; \ RC_TIMER1_COMP1_REG = RC_RESET_PW_TIMER_VALUE; \ RC_TIMER1_COMP2_REG = RC_TIMER1_COMP1_REG - RC_PPM_SYNC_PW_VALUE; \ RC_TIMER1_TIFR |= ( (1<= (RC_MIN_PULSE_PW_VALUE - RC_PPM_SYNC_PW_VALUE) ); \ RC_TIMER1_PRESCALER_REG &= (~(TIMER1_PRESCALER_BITS)); \ RC_TIMER1_TIFR |= ( (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 short get_channel_pw(unsigned char pin); unsigned char get_pw_of_connected_channels(void); void load_failsafe_values(void); #if RC_DEPTH_OF_PPM_FILTER > 0 && RC_REDUCE_LATENCY == 0 void clear_pw_buffer(void); #endif /********************************************************************************************************/ /* GLOBAL VARIABLES */ /********************************************************************************************************/ volatile unsigned short isr_channel_pw[(RC_PPM_GEN_CHANNELS +1)]; // +1 is for the reset pulse. volatile unsigned char pin_interrupt_detected = 0; volatile unsigned char isr_channel_number = 0; volatile unsigned short isr_timer0_16 = 0; unsigned char channel_mask = 0; union word2byte{ volatile unsigned short timer0_16; volatile unsigned char timer0[2]; } timer0; volatile unsigned short isr_timer0 = 0; #if RC_CONSTANT_PPM_FRAME_TIME == 1 volatile unsigned short reset_pw = 0; #endif #if RC_DEPTH_OF_PPM_FILTER > 0 unsigned char pw_memory_y = 0; unsigned char pw_memory_x = 0; unsigned short pw_memory[RC_DEPTH_OF_PPM_FILTER][RC_SERVO_INPUT_CHANNELS]; #endif /********************************************************************************************************/ /* LOCAL FUNCTION DEFINITIONS */ /********************************************************************************************************/ /*11111111111111111111111111111111111111111111111111111111111111111111111111111111111111111111111111*/ void initialize_mcu(void) { asm("cli"); STOP_TIMER0(); RESET_TIMER0(); TCNT1=0; /* Enable pwm mode 15 (fast pwm with top=OCR1A) and stop the timer. */ /* The timer compare module must be configured before the DDR register. */ #if RC_PPM_OUTPUT_TYPE == 0 //FUTABA negative shift RC_TIMER1_MODE_REG = (1< 0 clear_pw_buffer(); #endif isr_channel_number = RC_PPM_GEN_CHANNELS; asm("sei"); return; } /*11111111111111111111111111111111111111111111111111111111111111111111111111111111111111111111111111*/ /*22222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222*/ void wait_for_rx(void) { unsigned short pw=0; unsigned char x = 0; unsigned char y = 0; unsigned char servo_connected = 0; RC_SERVO_PORT_DDR_REG = 0; /* Activate the pull up resistors for the servo input port. */ RC_SERVO_PORT_REG = 0xFF; RESET_START_TIMER0(); /* give some time for the pull up resistors to work. */ while(timer0.timer0[1] < RC_MAX_TIMEOUT_VALUE ); do{ for(x=0; x < RC_SERVO_INPUT_CHANNELS; x++) { wdt_reset(); RESET_TIMER0(); servo_connected = 0; y=0; while(timer0.timer0[1] <= RC_MAX_TIMEOUT_VALUE ) { if(RC_SERVO_PORT_PIN_REG & (1<= RC_PULSE_TIMEOUT_VALUE ){ servo_connected = 1; break; } } if(servo_connected >= 1){ break; } } }while(servo_connected < 1); /* Turn off the pull up resistors for the servo input port. */ RC_SERVO_PORT_REG = 0; //Now test the found channel for a proper servo pulse. y = 0; while(1) { pw=get_channel_pw(x); if( (pw > RC_MIN_PULSE_WIDTH) && (pw < RC_MAX_PULSE_WIDTH) ) { y++; }else{ y=0; } if(y >= 3) { break; } } return; } /*22222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222*/ /*33333333333333333333333333333333333333333333333333333333333333333333333333333333333333333333333333*/ unsigned char detect_connected_channels(void) { unsigned short pw = 0; unsigned char channel=0; unsigned char servo_connected = 0; unsigned char x = 0; unsigned char y = 0; /* There must be no error in which channels are connected to the encoder because this will have devastating effects later on. */ RC_SERVO_PORT_DDR_REG = 0; /* Activate the pull up resistors for the servo input port. */ RC_SERVO_PORT_REG = 0xFF; RESET_START_TIMER0(); /* give some time for the pull up resistors to work. */ while(timer0.timer0[1] < RC_MAX_TIMEOUT_VALUE ); wdt_reset(); 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_VALUE ) { if(RC_SERVO_PORT_PIN_REG & (1<= RC_PULSE_TIMEOUT_VALUE ){ servo_connected++; break; } } if(servo_connected >= 3){ channel_mask |= (1< RC_MAX_PULSE_WIDTH) { channel_mask &= (~(1<= RC_PULSE_TIMEOUT_VALUE ){ return(0); } }while(x < RC_LEVEL_CHANGE_SAMPLES); RESET_TIMER0(); /* loop_until_bit_is_set with noise filter */ x=0; do{ x++; if( (RC_SERVO_PORT_PIN_REG & (1<= RC_MAX_TIMEOUT_VALUE ){ return(0); } }while(x < RC_LEVEL_CHANGE_SAMPLES); /* Reset the timer so we can start measuring the pulse's width. The timer is already started. */ RESET_TIMER0(); /* loop_until_bit_is_clear with noise filter*/ x=0; do{ x++; if(RC_SERVO_PORT_PIN_REG & (1<= RC_PULSE_TIMEOUT_VALUE ){ return(0); } }while(x < RC_LEVEL_CHANGE_SAMPLES); /*Stop the timer */ STOP_TIMER0(); timer0.timer0[0]= TCNT0; timer0_value = timer0.timer0_16; timer0_value = (timer0_value * 100)/RC_TIMER0_VALUE_CORRECTION; return((unsigned short)timer0_value); } /*55555555555555555555555555555555555555555555555555555555555555555555555555555555555555555555555555*/ /*66666666666666666666666666666666666666666666666666666666666666666666666666666666666666666666666666*/ /* Measure all active channels, a 16 bit timer would help here. */ unsigned char get_pw_of_connected_channels(void) { unsigned short pw_of_channel[RC_SERVO_INPUT_CHANNELS]; unsigned char channel_mask_buffer = 0; unsigned char pin_reg_buffer0 = 0; unsigned char pin_reg_buffer1 = 0; unsigned char channels_to_check=0; unsigned char number_of_valid_channels = 0; unsigned char channel_status = 0; unsigned char x=0; unsigned char y = 0; #if RC_REDUCE_LATENCY == 1 unsigned short timer0_buffer = 0; #endif #if RC_DEPTH_OF_PPM_FILTER > 0 unsigned short pw_buffer = 0; #endif wdt_reset(); channel_mask_buffer = channel_mask; RESET_START_TIMER0(); /* Main time stamp code */ /* The measuring loop will continue as long as all connected channels get measured or a timeout occurs. */ RC_PIN_INT_EN_REG &= (~(1<= RC_MAX_TIMEOUT_VALUE ) { RC_PIN_INT_EN_REG &= (~(1<= RC_MAX_TIMEOUT_VALUE ) { goto LOAD_ARRAY; } #endif }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); pin_interrupt_detected = 0; channels_to_check = pin_reg_buffer1 ^ pin_reg_buffer0; pin_reg_buffer1 = pin_reg_buffer0; while(x RC_MIN_PULSE_PW_VALUE) && (timer0_buffer < RC_MAX_PULSE_PW_VALUE) ) { isr_channel_pw[x] = timer0_buffer; number_of_valid_channels++; } } #elif RC_REDUCE_LATENCY == 0 /* if the channel has a time stamp then that is the end of the pulse. */ if( channel_status & y ) { pw_of_channel[x] = isr_timer0_16 - pw_of_channel[x]; channel_mask_buffer &= (~y); } #endif } // 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. #if RC_REDUCE_LATENCY == 0 /* Load the ISR ppm pulse width array and apply a low pass filter if specified. */ LOAD_ARRAY: RC_PIN_INT_EN_REG &= (~(1< 0 for(x=0; x < RC_SERVO_INPUT_CHANNELS; x++) { if(channels_to_check & (1< RC_MIN_PULSE_PW_VALUE) && (pw_of_channel[x] < RC_MAX_PULSE_PW_VALUE) ) { pw_buffer = pw_of_channel[x]; /* Averaging filter. */ pw_memory_y = 1; for(y=0; y RC_MIN_PULSE_PW_VALUE) && (pw_buffer < RC_MAX_PULSE_PW_VALUE) ) { isr_channel_pw[x] = pw_buffer; number_of_valid_channels++; } else{ pw_memory[pw_memory_x][x] = 0; } } else{ pw_memory[pw_memory_x][x] = 0; } } } pw_memory_x++; if(pw_memory_x >=RC_DEPTH_OF_PPM_FILTER ){ pw_memory_x = 0; } #else for(x=0; x < RC_SERVO_INPUT_CHANNELS; x++) { if(channels_to_check & (1< RC_MIN_PULSE_PW_VALUE) && (pw_of_channel[x] < RC_MAX_PULSE_PW_VALUE) ) { isr_channel_pw[x] = pw_of_channel[x]; number_of_valid_channels++; } } } #endif #endif //#if RC_REDUCE_LATENCY == 0 RC_PIN_INT_EN_REG &= (~(1<= 2 isr_channel_pw[1] = RC_FS_CH_2_TIMER_VALUE; #endif #if RC_PPM_GEN_CHANNELS >= 3 isr_channel_pw[2] = RC_FS_CH_3_TIMER_VALUE; #endif #if RC_PPM_GEN_CHANNELS >= 4 isr_channel_pw[3] = RC_FS_CH_4_TIMER_VALUE; #endif #if RC_PPM_GEN_CHANNELS >= 5 isr_channel_pw[4] = RC_FS_CH_5_TIMER_VALUE; #endif #if RC_PPM_GEN_CHANNELS >= 6 isr_channel_pw[5] = RC_FS_CH_6_TIMER_VALUE; #endif #if RC_PPM_GEN_CHANNELS >= 7 isr_channel_pw[6] = RC_FS_CH_7_TIMER_VALUE; #endif #if RC_PPM_GEN_CHANNELS >= 8 isr_channel_pw[7] = RC_FS_CH_8_TIMER_VALUE; #endif #if RC_PPM_GEN_CHANNELS >= 9 isr_channel_pw[8] = RC_FS_CH_8_TIMER_VALUE; #endif isr_channel_pw[RC_PPM_GEN_CHANNELS] = RC_RESET_PW_TIMER_VALUE; return; } /*77777777777777777777777777777777777777777777777777777777777777777777777777777777777777777777777777*/ /*88888888888888888888888888888888888888888888888888888888888888888888888888888888888888888888888888*/ #if RC_DEPTH_OF_PPM_FILTER > 0 && RC_REDUCE_LATENCY == 0 void clear_pw_buffer(void) { unsigned char x = 0; unsigned char y = 0; for(pw_memory_x=0; pw_memory_x= led_frequency ){ led_counter = 0; TOGGLE_LED(); } if( x >= channels_in_use ) { y = 0; if(servo_signals_lost) { PPM_ON(); servo_signals_lost = 0; LED_ON(); led_counter = 0; led_frequency = RC_LED_FREQUENCY_VALUE; } } else{ if(servo_signals_lost == 0) { y++; #if RC_DEPTH_OF_PPM_FILTER > 0 && RC_REDUCE_LATENCY == 0 if(y == RC_DEPTH_OF_PPM_FILTER) { clear_pw_buffer(); } #endif if(y >= RC_MAX_BAD_PPM_FRAMES) { # if RC_USE_FAILSAFE == 1 load_failsafe_values(); servo_signals_lost = 1; led_counter = 0; led_frequency = RC_LED_FREQUENCY_VALUE_1HZ; #elif RC_USE_FAILSAFE == 0 PPM_OFF(); servo_signals_lost = 1; led_counter = 0; led_frequency = RC_LED_FREQUENCY_VALUE_1HZ; #endif } } //end of if(servo_signals_lost == 0) statement. } //end of if( x > (channels_in_use/2) ){...}else{...} statement. } //end of while(1) loop. return(0); } /********************************************************************************************************/ /* 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 and changing the values within the OCIE1B interrupt timing is very accurate. The interrupt execution can be delayed because the OCR1X registers are double buffered and the actual registers are updated when the timer reaches the OCR1A (TOP) value automatically. */ ISR(TIMER1_COMPB_vect, ISR_NOBLOCK) { #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_VALUE; } 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; } RC_TIMER1_COMP2_REG = (RC_TIMER1_COMP1_REG - RC_PPM_SYNC_PW_VALUE); #elif 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]; RC_TIMER1_COMP2_REG = (RC_TIMER1_COMP1_REG - RC_PPM_SYNC_PW_VALUE); #endif return; } /********************************************************************************************************/ ISR(PCINT2_vect) { timer0.timer0[0]= TCNT0; if( RC_TIMER0_TIFR & (1<