mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Fixed typo in notes about timer speed
This commit is contained in:
parent
2ad1294514
commit
c343cee727
@ -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
Block a user