Browse Source

Arducopter: each motors_ pde uses APM_RC.SetFastOutputChannels

mission-4.1.18
Pat Hickey 13 years ago committed by Pat Hickey
parent
commit
eee2da01ac
  1. 4
      ArduCopter/heli.pde
  2. 5
      ArduCopter/motors_hexa.pde
  3. 5
      ArduCopter/motors_octa.pde
  4. 5
      ArduCopter/motors_octa_quad.pde
  5. 4
      ArduCopter/motors_quad.pde
  6. 4
      ArduCopter/motors_tri.pde
  7. 5
      ArduCopter/motors_y6.pde

4
ArduCopter/heli.pde

@ -207,9 +207,7 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o @@ -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
ArduCopter/motors_hexa.pde

@ -5,9 +5,8 @@ @@ -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
ArduCopter/motors_octa.pde

@ -5,9 +5,8 @@ @@ -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
ArduCopter/motors_octa_quad.pde

@ -5,9 +5,8 @@ @@ -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
}

4
ArduCopter/motors_quad.pde

@ -5,9 +5,7 @@ @@ -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
ArduCopter/motors_tri.pde

@ -4,9 +4,7 @@ @@ -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
}

5
ArduCopter/motors_y6.pde

@ -7,9 +7,8 @@ @@ -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…
Cancel
Save