mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_Linux: RCInput: use GPIO5 for PPMSUM in bhat
This commit is contained in:
parent
321803919c
commit
a803cfd1e8
@ -31,7 +31,11 @@
|
|||||||
#define RCIN_RPI_SAMPLE_FREQ 500
|
#define RCIN_RPI_SAMPLE_FREQ 500
|
||||||
#define RCIN_RPI_DMA_CHANNEL 0
|
#define RCIN_RPI_DMA_CHANNEL 0
|
||||||
#define RCIN_RPI_MAX_COUNTER 1300
|
#define RCIN_RPI_MAX_COUNTER 1300
|
||||||
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
|
||||||
|
#define PPM_INPUT_RPI RPI_GPIO_5
|
||||||
|
#else
|
||||||
#define PPM_INPUT_RPI RPI_GPIO_4
|
#define PPM_INPUT_RPI RPI_GPIO_4
|
||||||
|
#endif
|
||||||
#define RCIN_RPI_MAX_SIZE_LINE 50
|
#define RCIN_RPI_MAX_SIZE_LINE 50
|
||||||
|
|
||||||
//Memory Addresses
|
//Memory Addresses
|
||||||
|
Loading…
Reference in New Issue
Block a user