mirror of https://github.com/ArduPilot/ardupilot
Fixed typo in notes about timer speed
This commit is contained in:
parent
730668b0c7
commit
c6c6a98b0b
|
@ -7,7 +7,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 = 5000; // 50 hz output CH 7, 8, 11
|
||||
ICR3 = 5000; // 400 hz output CH 7, 8, 11
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -7,7 +7,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 = 5000; // 50 hz output CH 7, 8, 11
|
||||
ICR3 = 5000; // 400 hz output CH 7, 8, 11
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -7,7 +7,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 = 5000; // 50 hz output CH 7, 8, 11
|
||||
ICR3 = 5000; // 400 hz output CH 7, 8, 11
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -4,13 +4,12 @@
|
|||
|
||||
#define YAW_DIRECTION 1
|
||||
|
||||
|
||||
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; // 50 hz output CH 7, 8, 11
|
||||
ICR3 = 5000; // 400 hz output CH 7, 8, 11
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue