mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Arducopter: each motors_ pde uses APM_RC.SetFastOutputChannels
This commit is contained in:
parent
0549a50e9e
commit
5c13aa33be
@ -207,9 +207,7 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
ICR5 = 8000; // 250 hz output CH 1, 2, 9
|
||||
ICR1 = 8000; // 250 hz output CH 3, 4, 10
|
||||
ICR3 = 40000; // 50 hz output CH 7, 8, 11
|
||||
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4 );
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -5,9 +5,8 @@
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
ICR5 = 5000; // 400 hz output CH 1, 2, 9
|
||||
ICR1 = 5000; // 400 hz output CH 3, 4, 10
|
||||
ICR3 = 5000; // 400 hz output CH 7, 8, 11
|
||||
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4
|
||||
| MSK_CH_7 | MSK_CH_8 );
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -5,9 +5,8 @@
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
ICR5 = 5000; // 400 hz output CH 1, 2, 9
|
||||
ICR1 = 5000; // 400 hz output CH 3, 4, 10
|
||||
ICR3 = 5000; // 400 hz output CH 7, 8, 11
|
||||
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4
|
||||
| MSK_CH_7 | MSK_CH_8 | MSK_CH_10 | MSK_CH_11 );
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -5,9 +5,8 @@
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
ICR5 = 5000; // 400 hz output CH 1, 2, 9
|
||||
ICR1 = 5000; // 400 hz output CH 3, 4, 10
|
||||
ICR3 = 5000; // 400 hz output CH 7, 8, 11
|
||||
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4
|
||||
| MSK_CH_7 | MSK_CH_8 | MSK_CH_10 | MSK_CH_11 );
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -5,9 +5,7 @@
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
ICR5 = 5000; // 400 hz output CH 1, 2, 9
|
||||
ICR1 = 5000; // 400 hz output CH 3, 4, 10
|
||||
ICR3 = 40000; // 50 hz output CH 7, 8, 11
|
||||
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4 );
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -4,9 +4,7 @@
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
ICR5 = 5000; // 400 hz output CH 1, 2, 9
|
||||
ICR1 = 5000; // 400 hz output CH 3, 4, 10
|
||||
ICR3 = 40000; // 50 hz output CH 7, 8, 11
|
||||
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_4 );
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -7,9 +7,8 @@
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
ICR5 = 5000; // 400 hz output CH 1, 2, 9
|
||||
ICR1 = 5000; // 400 hz output CH 3, 4, 10
|
||||
ICR3 = 5000; // 400 hz output CH 7, 8, 11
|
||||
APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4
|
||||
| MSK_CH_7 | MSK_CH_8 );
|
||||
#endif
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user