mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
ACM: set default RC fast speed to 400Hz
This commit is contained in:
parent
bfca928211
commit
91c3f993b4
@ -105,6 +105,11 @@
|
||||
# define INSTANT_PWM DISABLED
|
||||
#endif
|
||||
|
||||
// default RC speed in Hz if INSTANT_PWM is not used
|
||||
#ifndef RC_FAST_SPEED
|
||||
# define RC_FAST_SPEED 400
|
||||
#endif
|
||||
|
||||
// LED and IO Pins
|
||||
//
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
||||
|
Loading…
Reference in New Issue
Block a user