mirror of https://github.com/ArduPilot/ardupilot
APM_RC: APM2 fast output speed increased to 400hz.
This commit is contained in:
parent
8a0c6eba78
commit
733000583d
|
@ -203,22 +203,26 @@ 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
|
||||
|
||||
void APM_RC_APM2::SetFastOutputChannels(uint32_t chmask)
|
||||
{
|
||||
if ((chmask & ( MSK_CH_1 | MSK_CH_2 )) != 0)
|
||||
_set_speed_ch1_ch2(OUTPUT_SPEED_200HZ);
|
||||
_set_speed_ch1_ch2(OUTPUT_SPEED_400HZ);
|
||||
|
||||
if ((chmask & ( MSK_CH_3 | MSK_CH_4 | MSK_CH_5 )) != 0)
|
||||
_set_speed_ch3_ch4_ch5(OUTPUT_SPEED_200HZ);
|
||||
_set_speed_ch3_ch4_ch5(OUTPUT_SPEED_400HZ);
|
||||
|
||||
if ((chmask & ( MSK_CH_6 | MSK_CH_7 | MSK_CH_8 )) != 0)
|
||||
_set_speed_ch6_ch7_ch8(OUTPUT_SPEED_200HZ);
|
||||
_set_speed_ch6_ch7_ch8(OUTPUT_SPEED_400HZ);
|
||||
}
|
||||
|
||||
void APM_RC_APM2::_set_speed_ch1_ch2(uint8_t speed)
|
||||
{
|
||||
switch(speed) {
|
||||
case OUTPUT_SPEED_400HZ:
|
||||
ICR1 = 5000;
|
||||
break;
|
||||
case OUTPUT_SPEED_200HZ:
|
||||
ICR1 = 10000;
|
||||
break;
|
||||
|
@ -232,6 +236,9 @@ 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;
|
||||
break;
|
||||
case OUTPUT_SPEED_200HZ:
|
||||
ICR4 = 10000;
|
||||
break;
|
||||
|
@ -246,6 +253,9 @@ 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;
|
||||
break;
|
||||
case OUTPUT_SPEED_200HZ:
|
||||
ICR3 = 10000;
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue