mirror of https://github.com/ArduPilot/ardupilot
removed some initial settings
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2565 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
350b2c5ea2
commit
16d1e5d0b8
|
@ -70,14 +70,14 @@ APM_RC_Class::APM_RC_Class()
|
|||
void APM_RC_Class::Init(void)
|
||||
{
|
||||
// Init PWM Timer 1
|
||||
pinMode(11,OUTPUT); // (PB5/OC1A)
|
||||
pinMode(11,OUTPUT); //OUT9 (PB5/OC1A)
|
||||
pinMode(12,OUTPUT); //OUT2 (PB6/OC1B)
|
||||
pinMode(13,OUTPUT); //OUT3 (PB7/OC1C)
|
||||
|
||||
//Remember the registers not declared here remains zero by default...
|
||||
TCCR1A =((1<<WGM11)|(1<<COM1A1)|(1<<COM1B1)|(1<<COM1C1)); //Please read page 131 of DataSheet, we are changing the registers settings of WGM11,COM1B1,COM1A1 to 1 thats all...
|
||||
TCCR1B = (1<<WGM13)|(1<<WGM12)|(1<<CS11); //Prescaler set to 8, that give us a resolution of 0.5us, read page 134 of data sheet
|
||||
OCR1A = 3000; //PB5, none
|
||||
//OCR1A = 3000; //PB5, OUT9
|
||||
//OCR1B = 3000; //PB6, OUT2
|
||||
//OCR1C = 3000; //PB7 OUT3
|
||||
ICR1 = 40000; //50hz freq...Datasheet says (system_freq/prescaler)/target frequency. So (16000000hz/8)/50hz=40000,
|
||||
|
@ -85,22 +85,22 @@ void APM_RC_Class::Init(void)
|
|||
// Init PWM Timer 3
|
||||
pinMode(2,OUTPUT); //OUT7 (PE4/OC3B)
|
||||
pinMode(3,OUTPUT); //OUT6 (PE5/OC3C)
|
||||
pinMode(4,OUTPUT); // (PE3/OC3A)
|
||||
pinMode(5,OUTPUT); //OUT10(PE3/OC3A)
|
||||
TCCR3A =((1<<WGM31)|(1<<COM3A1)|(1<<COM3B1)|(1<<COM3C1));
|
||||
TCCR3B = (1<<WGM33)|(1<<WGM32)|(1<<CS31);
|
||||
OCR3A = 3000; //PE3, NONE
|
||||
OCR3B = 3000; //PE4, OUT7
|
||||
OCR3C = 3000; //PE5, OUT6
|
||||
//OCR3A = 3000; //PE3, OUT10
|
||||
//OCR3B = 3000; //PE4, OUT7
|
||||
//OCR3C = 3000; //PE5, OUT6
|
||||
ICR3 = 40000; //50hz freq
|
||||
|
||||
// Init PWM Timer 5
|
||||
pinMode(44,OUTPUT); //OUT1 (PL5/OC5C)
|
||||
pinMode(45,OUTPUT); //OUT0 (PL4/OC5B)
|
||||
pinMode(46,OUTPUT); // (PL3/OC5A)
|
||||
pinMode(46,OUTPUT); //OUT8 (PL3/OC5A)
|
||||
|
||||
TCCR5A =((1<<WGM51)|(1<<COM5A1)|(1<<COM5B1)|(1<<COM5C1));
|
||||
TCCR5B = (1<<WGM53)|(1<<WGM52)|(1<<CS51);
|
||||
OCR5A = 3000; //PL3,
|
||||
//OCR5A = 3000; //PL3, OUT8
|
||||
//OCR5B = 3000; //PL4, OUT0
|
||||
//OCR5C = 3000; //PL5, OUT1
|
||||
ICR5 = 40000; //50hz freq
|
||||
|
|
Loading…
Reference in New Issue