Browse Source

AP_BoardConfig: default to 6 PWM on FMUv4

less likely to use relays
master
Andrew Tridgell 9 years ago
parent
commit
c3546dfbb0
  1. 5
      libraries/AP_BoardConfig/AP_BoardConfig.cpp

5
libraries/AP_BoardConfig/AP_BoardConfig.cpp

@ -33,7 +33,10 @@ @@ -33,7 +33,10 @@
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
#define BOARD_PWM_COUNT_DEFAULT 2
#define BOARD_SER1_RTSCTS_DEFAULT 0 // no flow control on UART5 on FMUv1
#else
#elif CONFIG_ARCH_BOARD_PX4FMU_V4
#define BOARD_PWM_COUNT_DEFAULT 6
#define BOARD_SER1_RTSCTS_DEFAULT 2
#else // V2
#define BOARD_PWM_COUNT_DEFAULT 4
#define BOARD_SER1_RTSCTS_DEFAULT 2
#endif

Loading…
Cancel
Save