Browse Source

AP_HAL_Linux: RCInput: use GPIO5 for PPMSUM in bhat

mission-4.1.18
Lucas De Marchi 9 years ago
parent
commit
a803cfd1e8
  1. 4
      libraries/AP_HAL_Linux/RCInput_RPI.cpp

4
libraries/AP_HAL_Linux/RCInput_RPI.cpp

@ -31,7 +31,11 @@ @@ -31,7 +31,11 @@
#define RCIN_RPI_SAMPLE_FREQ 500
#define RCIN_RPI_DMA_CHANNEL 0
#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
#endif
#define RCIN_RPI_MAX_SIZE_LINE 50
//Memory Addresses

Loading…
Cancel
Save