AP_HAL_Linux: RCInput: use GPIO5 for PPMSUM in bhat

This commit is contained in:
Lucas De Marchi 2016-01-07 10:24:46 -02:00
parent 321803919c
commit a803cfd1e8

View File

@ -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