mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_HAL_ChibiOS: move AP_Periph config of NUM_SERVO_CHANNELS into chibios_hwdef.py
This commit is contained in:
parent
8a312d4f34
commit
d4930b4e55
@ -2876,6 +2876,16 @@ def add_apperiph_defaults(f):
|
|||||||
#define AP_ROBOTISSERVO_ENABLED 0
|
#define AP_ROBOTISSERVO_ENABLED 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// by default an AP_Periph defines as many servo output channels as
|
||||||
|
// there are PWM outputs:
|
||||||
|
#ifndef NUM_SERVO_CHANNELS
|
||||||
|
#ifdef HAL_PWM_COUNT
|
||||||
|
#define NUM_SERVO_CHANNELS HAL_PWM_COUNT
|
||||||
|
#else
|
||||||
|
#define NUM_SERVO_CHANNELS 0
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef AP_STATS_ENABLED
|
#ifndef AP_STATS_ENABLED
|
||||||
#define AP_STATS_ENABLED 0
|
#define AP_STATS_ENABLED 0
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user