mirror of https://github.com/ArduPilot/ardupilot
fixed an overflow issue in AP_RC
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2074 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
85d006c290
commit
6d4b77340b
|
@ -36,10 +36,10 @@ volatile int16_t timer4diff = 1500 * 2;
|
|||
#define CH_4 3
|
||||
|
||||
volatile int8_t _rc_ch_read;
|
||||
volatile uint8_t _timer_out;
|
||||
volatile uint8_t _timer_ovf_a;
|
||||
volatile uint8_t _timer_ovf_b;
|
||||
volatile uint8_t _timer_ovf;
|
||||
volatile uint16_t _timer_out;
|
||||
volatile uint16_t _timer_ovf_a;
|
||||
volatile uint16_t _timer_ovf_b;
|
||||
volatile uint16_t _timer_ovf;
|
||||
|
||||
|
||||
AP_RC::AP_RC()
|
||||
|
@ -117,27 +117,33 @@ AP_RC::output_ch_pwm(uint8_t ch, uint16_t pwm)
|
|||
{
|
||||
switch(ch){
|
||||
case CH_1:
|
||||
pwm <<= 1;
|
||||
pwm <<= 1; // multiplies by 2
|
||||
OCR1A = pwm;
|
||||
break;
|
||||
|
||||
case CH_2:
|
||||
pwm <<= 1;
|
||||
OCR1B = pwm;
|
||||
OCR1B = pwm; // multiplies by 2
|
||||
break;
|
||||
|
||||
case CH_3:
|
||||
_timer_out = pwm % 512;
|
||||
_timer_ovf_a = pwm / 512;
|
||||
_timer_out >>= 1;
|
||||
OCR2A = _timer_out;
|
||||
_timer_out >>= 1; // divides by 2
|
||||
//OCR2A = _timer_out;
|
||||
if(OCR2A != _timer_out)
|
||||
OCR2A = _timer_out;
|
||||
|
||||
break;
|
||||
|
||||
case CH_4:
|
||||
_timer_out = pwm % 512;
|
||||
_timer_ovf_b = pwm / 512;
|
||||
_timer_out >>= 1;
|
||||
OCR2B = _timer_out;
|
||||
_timer_ovf_b = pwm / 512;
|
||||
_timer_out >>= 1; // divides by 2
|
||||
//OCR2B = _timer_out;
|
||||
if(OCR2B != _timer_out)
|
||||
OCR2B = _timer_out;
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -211,10 +217,10 @@ ISR(PCINT0_vect)
|
|||
ISR(TIMER1_CAPT_vect) // Timer/Counter1 Capture Event
|
||||
{
|
||||
//This is a timer 1 interrupts, executed every 20us
|
||||
PORTB |= B00000001; //Putting the pin high!
|
||||
PORTC |= B00010000; //Putting the pin high!
|
||||
TCNT2 = 0; //restarting the counter of timer 2
|
||||
_timer_ovf = 0;
|
||||
PORTB |= B00000001; //Putting the pin high!
|
||||
PORTC |= B00010000; //Putting the pin high!
|
||||
TCNT2 = 0; //restarting the counter of timer 2
|
||||
_timer_ovf = 0;
|
||||
}
|
||||
|
||||
ISR(TIMER2_OVF_vect)
|
||||
|
|
Loading…
Reference in New Issue