Updated fastPWM to 490Hz

This commit is contained in:
Jason Short 2012-02-29 22:15:13 -08:00
parent 8fa559930f
commit 59e1d43f60
2 changed files with 21 additions and 21 deletions

View File

@ -250,29 +250,29 @@ void APM_RC_APM1::Force_Out6_Out7(void)
// Output rate options:
#define OUTPUT_SPEED_50HZ 0
#define OUTPUT_SPEED_200HZ 1
#define OUTPUT_SPEED_400HZ 2
#define OUTPUT_SPEED_490HZ 2
void APM_RC_APM1::SetFastOutputChannels(uint32_t chmask)
{
if ((chmask & ( _BV(CH_1) | _BV(CH_2) | _BV(CH_9))) != 0)
_set_speed_ch1_ch2_ch9(OUTPUT_SPEED_400HZ);
_set_speed_ch1_ch2_ch9(OUTPUT_SPEED_490HZ);
if ((chmask & ( _BV(CH_3) | _BV(CH_4) | _BV(CH_10))) != 0)
_set_speed_ch3_ch4_ch10(OUTPUT_SPEED_400HZ);
_set_speed_ch3_ch4_ch10(OUTPUT_SPEED_490HZ);
if ((chmask & ( _BV(CH_5) | _BV(CH_6))) != 0)
_set_speed_ch5_ch6(OUTPUT_SPEED_400HZ);
_set_speed_ch5_ch6(OUTPUT_SPEED_490HZ);
if ((chmask & ( _BV(CH_7) | _BV(CH_8) | _BV(CH_11))) != 0)
_set_speed_ch7_ch8_ch11(OUTPUT_SPEED_400HZ);
_set_speed_ch7_ch8_ch11(OUTPUT_SPEED_490HZ);
}
void APM_RC_APM1::_set_speed_ch1_ch2_ch9(uint8_t speed)
{
switch(speed) {
case OUTPUT_SPEED_400HZ:
ICR1= 5000;
case OUTPUT_SPEED_490HZ:
ICR1= 4096;
break;
case OUTPUT_SPEED_200HZ:
ICR1= 10000;
@ -287,8 +287,8 @@ void APM_RC_APM1::_set_speed_ch1_ch2_ch9(uint8_t speed)
void APM_RC_APM1::_set_speed_ch3_ch4_ch10(uint8_t speed)
{
switch(speed) {
case OUTPUT_SPEED_400HZ:
ICR5= 5000;
case OUTPUT_SPEED_490HZ:
ICR5= 4096;
break;
case OUTPUT_SPEED_200HZ:
ICR5= 10000;
@ -303,8 +303,8 @@ void APM_RC_APM1::_set_speed_ch3_ch4_ch10(uint8_t speed)
void APM_RC_APM1::_set_speed_ch7_ch8_ch11(uint8_t speed)
{
switch(speed) {
case OUTPUT_SPEED_400HZ:
ICR3 = 5000;
case OUTPUT_SPEED_490HZ:
ICR3 = 4096;
break;
case OUTPUT_SPEED_200HZ:
ICR3 = 10000;

View File

@ -230,25 +230,25 @@ void APM_RC_APM2::Force_Out6_Out7(void) { }
// Output rate options:
#define OUTPUT_SPEED_50HZ 0
#define OUTPUT_SPEED_200HZ 1
#define OUTPUT_SPEED_400HZ 2
#define OUTPUT_SPEED_490HZ 2
void APM_RC_APM2::SetFastOutputChannels(uint32_t chmask)
{
if ((chmask & ( _BV(CH_1) | _BV(CH_2))) != 0)
_set_speed_ch1_ch2(OUTPUT_SPEED_400HZ);
_set_speed_ch1_ch2(OUTPUT_SPEED_490HZ);
if ((chmask & ( _BV(CH_3) | _BV(CH_4) | _BV(CH_5))) != 0)
_set_speed_ch3_ch4_ch5(OUTPUT_SPEED_400HZ);
_set_speed_ch3_ch4_ch5(OUTPUT_SPEED_490HZ);
if ((chmask & ( _BV(CH_6) | _BV(CH_7) | _BV(CH_8))) != 0)
_set_speed_ch6_ch7_ch8(OUTPUT_SPEED_400HZ);
_set_speed_ch6_ch7_ch8(OUTPUT_SPEED_490HZ);
}
void APM_RC_APM2::_set_speed_ch1_ch2(uint8_t speed)
{
switch(speed) {
case OUTPUT_SPEED_400HZ:
ICR1 = 5000;
case OUTPUT_SPEED_490HZ:
ICR1 = 4096;
break;
case OUTPUT_SPEED_200HZ:
ICR1 = 10000;
@ -263,8 +263,8 @@ void APM_RC_APM2::_set_speed_ch1_ch2(uint8_t speed)
void APM_RC_APM2::_set_speed_ch3_ch4_ch5(uint8_t speed)
{
switch(speed) {
case OUTPUT_SPEED_400HZ:
ICR4 = 5000;
case OUTPUT_SPEED_490HZ:
ICR4 = 4096;
break;
case OUTPUT_SPEED_200HZ:
ICR4 = 10000;
@ -280,8 +280,8 @@ void APM_RC_APM2::_set_speed_ch3_ch4_ch5(uint8_t speed)
void APM_RC_APM2::_set_speed_ch6_ch7_ch8(uint8_t speed)
{
switch(speed) {
case OUTPUT_SPEED_400HZ:
ICR3 = 5000;
case OUTPUT_SPEED_490HZ:
ICR3 = 4096;
break;
case OUTPUT_SPEED_200HZ:
ICR3 = 10000;