aboutsummaryrefslogtreecommitdiff
path: root/nuttx-configs/px4fmu-v1/include/board.h
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx-configs/px4fmu-v1/include/board.h')
-rw-r--r--nuttx-configs/px4fmu-v1/include/board.h72
1 files changed, 0 insertions, 72 deletions
diff --git a/nuttx-configs/px4fmu-v1/include/board.h b/nuttx-configs/px4fmu-v1/include/board.h
index 839631b3a..27ace4b7d 100644
--- a/nuttx-configs/px4fmu-v1/include/board.h
+++ b/nuttx-configs/px4fmu-v1/include/board.h
@@ -156,11 +156,6 @@
#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY)
#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY)
-/* High-resolution timer
- */
-#define HRT_TIMER 1 /* use timer1 for the HRT */
-#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
-
/* LED definitions ******************************************************************/
/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
* way. The following definitions are used to access individual LEDs.
@@ -216,33 +211,6 @@
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
/*
- * PWM
- *
- * Four PWM outputs can be configured on pins otherwise shared with
- * USART2; two can take the flow control pins if they are not being used.
- *
- * Pins:
- *
- * CTS - PA0 - TIM2CH1
- * RTS - PA1 - TIM2CH2
- * TX - PA2 - TIM2CH3
- * RX - PA3 - TIM2CH4
- *
- */
-#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_1
-#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1
-#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1
-#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1
-
-/*
- * PPM
- *
- * PPM input is handled by the HRT timer.
- */
-#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
-#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
-
-/*
* CAN
*
* CAN2 is routed to the expansion connector.
@@ -274,25 +242,6 @@
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN9)
/*
- * I2C busses
- */
-#define PX4_I2C_BUS_ESC 1
-#define PX4_I2C_BUS_ONBOARD 2
-#define PX4_I2C_BUS_EXPANSION 3
-
-/*
- * Devices on the onboard bus.
- *
- * Note that these are unshifted addresses.
- */
-#define PX4_I2C_OBDEV_HMC5883 0x1e
-#define PX4_I2C_OBDEV_MS5611 0x76
-#define PX4_I2C_OBDEV_EEPROM NOTDEFINED
-
-#define PX4_I2C_OBDEV_PX4IO_BL 0x18
-#define PX4_I2C_OBDEV_PX4IO 0x1a
-
-/*
* SPI
*
* There are sensors on SPI1, and SPI3 is connected to the microSD slot.
@@ -316,27 +265,6 @@
#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2
-/*
- * Use these in place of the spi_dev_e enumeration to
- * select a specific SPI device on SPI1
- */
-#define PX4_SPIDEV_GYRO 1
-#define PX4_SPIDEV_ACCEL 2
-#define PX4_SPIDEV_MPU 3
-
-/*
- * Optional devices on IO's external port
- */
-#define PX4_SPIDEV_ACCEL_MAG 2
-
-/*
- * Tone alarm output
- */
-#define TONE_ALARM_TIMER 3 /* timer 3 */
-#define TONE_ALARM_CHANNEL 3 /* channel 3 */
-#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
-#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
-
/************************************************************************************
* Public Data
************************************************************************************/