mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: add and use AP_SBUSOUTPUT_ENABLED
.... which will allow periphs to instantiate this if they really feel like it, and for it to be removed on smaller boards on the custom build server (and potentially on lower-specced boards.
This commit is contained in:
parent
5daa38ffba
commit
3869c4c0e9
|
@ -3079,6 +3079,10 @@ INCLUDE common.ld
|
|||
#define AP_ROBOTISSERVO_ENABLED 0
|
||||
#endif
|
||||
|
||||
#ifndef AP_SBUSOUTPUT_ENABLED
|
||||
#define AP_SBUSOUTPUT_ENABLED 0
|
||||
#endif
|
||||
|
||||
// by default an AP_Periph defines as many servo output channels as
|
||||
// there are PWM outputs:
|
||||
#ifndef NUM_SERVO_CHANNELS
|
||||
|
|
Loading…
Reference in New Issue