boards/ enforce astyle

This commit is contained in:
Daniel Agar 2018-12-01 13:15:39 -05:00
parent 1efad64f0c
commit 744bacd424
18 changed files with 132 additions and 307 deletions

View File

@ -8,7 +8,7 @@ then
PATTERN="$1"
fi
exec find src platforms \
exec find boards src platforms \
-path platforms/nuttx/NuttX -prune -o \
-path src/lib/DriverFramework -prune -o \
-path src/lib/ecl -prune -o \

View File

@ -85,10 +85,8 @@ __BEGIN_DECLS
* ------ --------- ---------
*/
#define GPIO_EMAC0_INT (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | \
GPIO_INT_FALLING | GPIO_PORT_PIOA | GPIO_PIN14)
#define GPIO_EMAC0_RESET (GPIO_OUTPUT | GPIO_CFG_PULLUP | GPIO_OUTPUT_SET | \
GPIO_PORT_PIOC | GPIO_PIN10)
#define GPIO_EMAC0_INT (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | GPIO_INT_FALLING | GPIO_PORT_PIOA | GPIO_PIN14)
#define GPIO_EMAC0_RESET (GPIO_OUTPUT | GPIO_CFG_PULLUP | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN10)
#define IRQ_EMAC0_INT SAM_IRQ_PA14
@ -97,8 +95,7 @@ __BEGIN_DECLS
* A single LED is available driven by PC8.
*/
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | \
GPIO_PORT_PIOC | GPIO_PIN8)
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN8)
#define GPIO_LED_RED GPIO_LED1
#define BOARD_OVERLOAD_LED LED_RED
@ -114,8 +111,7 @@ __BEGIN_DECLS
* button.
*/
#define GPIO_SW0 (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | \
GPIO_INT_BOTHEDGES | GPIO_PORT_PIOA | GPIO_PIN11)
#define GPIO_SW0 (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | GPIO_INT_BOTHEDGES | GPIO_PORT_PIOA | GPIO_PIN11)
#define IRQ_SW0 SAM_IRQ_PA11
/* HSMCI SD Card Detect
@ -138,8 +134,7 @@ __BEGIN_DECLS
* ------ ----------------- ---------------------
*/
#define GPIO_MCI0_CD (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_INT_BOTHEDGES | GPIO_PORT_PIOC | GPIO_PIN16)
#define GPIO_MCI0_CD (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_BOTHEDGES | GPIO_PORT_PIOC | GPIO_PIN16)
#define IRQ_MCI0_CD SAM_IRQ_PC16
/* USB Host
@ -150,53 +145,37 @@ __BEGIN_DECLS
* pin (PC16) low.
*/
#define GPIO_VBUSON (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | \
GPIO_PORT_PIOC | GPIO_PIN16)
#define GPIO_VBUSON (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN16)
/* External interrupts */
//todo:DBS fix all these
#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_MPU_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_MPU_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
/* Data ready pins off */
#define GPIO_GYRO_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_MAG_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_ACCEL_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_MPU_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_GYRO_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_MAG_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_ACCEL_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_MPU_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
/* SPI1 off */
#define GPIO_SPI1_SCK_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN22)
#define GPIO_SPI1_MISO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN20)
#define GPIO_SPI1_MOSI_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN21)
#define GPIO_SPI1_SCK_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN22)
#define GPIO_SPI1_MISO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN20)
#define GPIO_SPI1_MOSI_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN21)
/* SPI1 chip selects off */
#define GPIO_SPI_CS_GYRO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN13)
#define GPIO_SPI_CS_ACCEL_MAG_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN17 )
#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN11)
#define GPIO_SPI_CS_MPU_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN27)
#define GPIO_SPI_CS_GYRO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN13)
#define GPIO_SPI_CS_ACCEL_MAG_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN17)
#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN11)
#define GPIO_SPI_CS_MPU_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN27)
/* SPI chip selects */
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN13)
#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN17 )
#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN17)
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOD | GPIO_PIN11)
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOD | GPIO_PIN27)
@ -242,14 +221,10 @@ __BEGIN_DECLS
*
* GPIO0-3 are the PWM servo outputs.
*/
#define GPIO_GPIO0_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN19)
#define GPIO_GPIO1_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN26)
#define GPIO_GPIO2_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOA | GPIO_PIN2)
#define GPIO_GPIO3_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | \
GPIO_CFG_PULLDOWN | GPIO_PORT_PIOA | GPIO_PIN24)
#define GPIO_GPIO0_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN19)
#define GPIO_GPIO1_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN26)
#define GPIO_GPIO2_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOA | GPIO_PIN2)
#define GPIO_GPIO3_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOA | GPIO_PIN24)
#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN19)
#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN26)
#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOA | GPIO_PIN2)

View File

@ -142,11 +142,11 @@
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL | GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN15)
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
} while(0)
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
} while(0)
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)

View File

@ -72,17 +72,13 @@
* PB[6] PB06 42 nCAN_SILENT
*/
#define GPIO_CAN_SILENT (GPIO_OUTPUT | GPIO_PUSHPULL | \
GPIO_PORTB | GPIO_PIN6 | GPIO_OUTPUT_CLEAR)
#define GPIO_CAN_SILENT (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_PORTB | GPIO_PIN6 | GPIO_OUTPUT_CLEAR)
#define GPIO_RC_PWM (GPIO_INPUT | GPIO_PULLUP | GPIO_PORTA | GPIO_PIN0)
#define GPIO_OC_ADJ (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTA | GPIO_PIN4 | GPIO_OUTPUT_CLEAR)
#define GPIO_EN_GATE (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTA | GPIO_PIN5 | GPIO_OUTPUT_CLEAR)
#define GPIO_DC_CAL (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTA | GPIO_PIN6 | GPIO_OUTPUT_CLEAR)
#define GPIO_OC_ADJ (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN4 | GPIO_OUTPUT_CLEAR)
#define GPIO_EN_GATE (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN5 | GPIO_OUTPUT_CLEAR)
#define GPIO_DC_CAL (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN6 | GPIO_OUTPUT_CLEAR)
/* CAN ************************************************************************ *
@ -122,16 +118,13 @@
* PC[09] PC9/TIM3_CH4/TIM8_CH4 40 LED_BLUE
*/
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTA | GPIO_PIN2 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN2 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED_RED GPIO_LED1
#define GPIO_LED2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTA | GPIO_PIN3 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN3 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED_GREEN GPIO_LED2
#define GPIO_LED3 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTA | GPIO_PIN1 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED3 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN1 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED_BLUE GPIO_LED3
__BEGIN_DECLS

View File

@ -366,53 +366,20 @@
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN1)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN0)
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET |GPIO_PORTF | GPIO_PIN1)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET |GPIO_PORTF | GPIO_PIN0)
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTH | \
GPIO_PIN7)
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTH | \
GPIO_PIN8)
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT |GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN7)
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT |GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8)
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN14)
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN15)
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14)
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15)
/* SDMMC1
*

View File

@ -172,7 +172,7 @@
* UARTs.
*
*/
/* E_TX2 / E_RX2 */
/* E_TX2 / E_RX2 */
#define GPIO_USART2_RX GPIO_USART2_RX_1
#define GPIO_USART2_TX GPIO_USART2_TX_1

View File

@ -132,9 +132,7 @@
#define BOARD_SIM_CLKDIV2_USBFRAC 2
#define BOARD_SIM_CLKDIV2_USBDIV 7
#define BOARD_SIM_CLKDIV2_FREQ (BOARD_SOPT2_FREQ / \
BOARD_SIM_CLKDIV2_USBDIV * \
BOARD_SIM_CLKDIV2_USBFRAC)
#define BOARD_SIM_CLKDIV2_FREQ (BOARD_SOPT2_FREQ / BOARD_SIM_CLKDIV2_USBDIV * BOARD_SIM_CLKDIV2_USBFRAC)
#define BOARD_USB_CLKSRC SIM_SOPT2_USBSRC
#define BOARD_USB_FREQ BOARD_SIM_CLKDIV2_FREQ
@ -147,9 +145,7 @@
#define BOARD_SIM_CLKDIV3_PLLFLLFRAC 1
#define BOARD_SIM_CLKDIV3_PLLFLLDIV 2
#define BOARD_SIM_CLKDIV3_FREQ (BOARD_SOPT2_FREQ / \
BOARD_SIM_CLKDIV3_PLLFLLDIV * \
BOARD_SIM_CLKDIV3_PLLFLLFRAC)
#define BOARD_SIM_CLKDIV3_FREQ (BOARD_SOPT2_FREQ / BOARD_SIM_CLKDIV3_PLLFLLDIV * BOARD_SIM_CLKDIV3_PLLFLLFRAC)
#define BOARD_LPUART0_CLKSRC SIM_SOPT2_LPUARTSRC_MCGCLK
#define BOARD_LPUART0_FREQ BOARD_SIM_CLKDIV3_FREQ
@ -502,14 +498,14 @@
# define PROBE_6 (GPIO_LOWDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTE | PIN12)
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { kinetis_pinconfig(PROBE_1); } \
if ((mask)& PROBE_N(2)) { kinetis_pinconfig(PROBE_2); } \
if ((mask)& PROBE_N(3)) { kinetis_pinconfig(PROBE_3); } \
if ((mask)& PROBE_N(4)) { kinetis_pinconfig(PROBE_4); } \
if ((mask)& PROBE_N(5)) { kinetis_pinconfig(PROBE_5); } \
if ((mask)& PROBE_N(6)) { kinetis_pinconfig(PROBE_6); } \
} while(0)
do { \
if ((mask)& PROBE_N(1)) { kinetis_pinconfig(PROBE_1); } \
if ((mask)& PROBE_N(2)) { kinetis_pinconfig(PROBE_2); } \
if ((mask)& PROBE_N(3)) { kinetis_pinconfig(PROBE_3); } \
if ((mask)& PROBE_N(4)) { kinetis_pinconfig(PROBE_4); } \
if ((mask)& PROBE_N(5)) { kinetis_pinconfig(PROBE_5); } \
if ((mask)& PROBE_N(6)) { kinetis_pinconfig(PROBE_6); } \
} while(0)
# define PROBE(n,s) do {kinetis_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)

View File

@ -84,8 +84,7 @@ struct fmuk66_automount_config_s {
* Private Function Prototypes
************************************************************************************/
static int fmuk66_attach(FAR const struct automount_lower_s *lower,
automount_handler_t isr, FAR void *arg);
static int fmuk66_attach(FAR const struct automount_lower_s *lower, automount_handler_t isr, FAR void *arg);
static void fmuk66_enable(FAR const struct automount_lower_s *lower, bool enable);
static bool fmuk66_inserted(FAR const struct automount_lower_s *lower);
@ -129,8 +128,7 @@ static const struct fmuk66_automount_config_s g_sdhc_config = {
*
************************************************************************************/
static int fmuk66_attach(FAR const struct automount_lower_s *lower,
automount_handler_t isr, FAR void *arg)
static int fmuk66_attach(FAR const struct automount_lower_s *lower, automount_handler_t isr, FAR void *arg)
{
FAR const struct fmuk66_automount_config_s *config;
FAR struct fmuk66_automount_state_s *state;

View File

@ -184,11 +184,11 @@
# define PROBE_3 (GPIO_OUTPUT|GPIO_CNF_OUTPP | GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN3)
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
} while(0)
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
} while(0)
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)

View File

@ -75,11 +75,9 @@
* PA[01] PA1/USART2_RTS/ADC1/TIM2_CH2 15 D3(LED2)
*/
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
GPIO_PORTA | GPIO_PIN5 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN5 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED_GREEN GPIO_LED1
#define GPIO_LED2 (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
GPIO_PORTA | GPIO_PIN1 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED2 (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_PORTA | GPIO_PIN1 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED_YELLOW GPIO_LED2
/* BUTTON ***************************************************************************
@ -92,8 +90,7 @@
*
*/
#define BUTTON_BOOT0n (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_PORTC | GPIO_PIN9 | \
GPIO_EXTI)
#define BUTTON_BOOT0n (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_PORTC | GPIO_PIN9 | GPIO_EXTI)
#define IRQBUTTON BUTTON_BOOT0_BIT
/* USBs *****************************************************************************
@ -108,8 +105,7 @@
*/
#define GPIO_USB_VBUS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_PORTC | GPIO_PIN11)
#define GPIO_USB_PULLUPn (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
GPIO_PORTC | GPIO_PIN12 | GPIO_OUTPUT_SET)
#define GPIO_USB_PULLUPn (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN12 | GPIO_OUTPUT_SET)
/* SPI ***************************************************************************
*
@ -121,12 +117,10 @@
* PD[02] PD2/TIM3_ETR 54 D25(MMC_CS)
*/
#define GPIO_SPI1_SSn (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
GPIO_PORTC | GPIO_PIN9 | GPIO_OUTPUT_SET)
#define GPIO_SPI1_SSn (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN9 | GPIO_OUTPUT_SET)
#define USER_CSn GPIO_SPI1_SSn
#define GPIO_SPI2_SSn (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
GPIO_PORTD | GPIO_PIN2 | GPIO_OUTPUT_SET)
#define GPIO_SPI2_SSn (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_PORTD | GPIO_PIN2 | GPIO_OUTPUT_SET)
#define MMCSD_CSn GPIO_SPI2_SSn
/* CAN ***************************************************************************
@ -140,8 +134,7 @@
* PC[13] PC13/ANTI_TAMP 2 D21(CAN_CTRL)
*/
#define GPIO_CAN_CTRL (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
GPIO_PORTC | GPIO_PIN13 | GPIO_OUTPUT_CLEAR)
#define GPIO_CAN_CTRL (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_PORTC | GPIO_PIN13 | GPIO_OUTPUT_CLEAR)
__BEGIN_DECLS

View File

@ -77,12 +77,9 @@
*/
#define GPIO_RC_PWM (GPIO_INPUT | GPIO_PULLUP | GPIO_PORTA | GPIO_PIN3)
#define GPIO_OC_ADJ (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTA | GPIO_PIN4 | GPIO_OUTPUT_CLEAR)
#define GPIO_EN_GATE (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTA | GPIO_PIN5 | GPIO_OUTPUT_CLEAR)
#define GPIO_DC_CAL (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTA | GPIO_PIN6 | GPIO_OUTPUT_CLEAR)
#define GPIO_OC_ADJ (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN4 | GPIO_OUTPUT_CLEAR)
#define GPIO_EN_GATE (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN5 | GPIO_OUTPUT_CLEAR)
#define GPIO_DC_CAL (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTA | GPIO_PIN6 | GPIO_OUTPUT_CLEAR)
/* GPIO ***********************************************************************
@ -97,12 +94,9 @@
*
*/
#define GPIO_GAIN (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTB | GPIO_PIN2 | GPIO_OUTPUT_CLEAR)
#define GPIO_TEST2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTB | GPIO_PIN3 | GPIO_OUTPUT_CLEAR)
#define GPIO_TEST3 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTB | GPIO_PIN4 | GPIO_OUTPUT_CLEAR)
#define GPIO_GAIN (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN2 | GPIO_OUTPUT_CLEAR)
#define GPIO_TEST2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN3 | GPIO_OUTPUT_CLEAR)
#define GPIO_TEST3 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTB | GPIO_PIN4 | GPIO_OUTPUT_CLEAR)
/* CAN ************************************************************************ *
*
@ -168,16 +162,13 @@
* PC[09] PC9/TIM3_CH4/TIM8_CH4 40 LED_BLUE
*/
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTC | GPIO_PIN7 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTC | GPIO_PIN7 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED_RED GPIO_LED1
#define GPIO_LED2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTC | GPIO_PIN8 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED2 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTC | GPIO_PIN8 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED_GREEN GPIO_LED2
#define GPIO_LED3 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTC | GPIO_PIN9 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED3 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTC | GPIO_PIN9 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED_BLUE GPIO_LED3
@ -198,8 +189,7 @@
#define GPIO_HWID0 (GPIO_INPUT | GPIO_PULLUP | GPIO_PORTC | GPIO_PIN10)
#define GPIO_HWID1 (GPIO_INPUT | GPIO_PULLUP | GPIO_PORTC | GPIO_PIN11)
#define GPIO_TEST4 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTC | GPIO_PIN12 | GPIO_OUTPUT_CLEAR)
#define GPIO_TEST4 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTC | GPIO_PIN12 | GPIO_OUTPUT_CLEAR)
#define GPIO_PWRGD (GPIO_INPUT | GPIO_PULLUP | GPIO_PORTC | GPIO_PIN13)
#define GPIO_OCTW (GPIO_INPUT | GPIO_PULLUP | GPIO_PORTC | GPIO_PIN14)
@ -213,8 +203,7 @@
*
* PD[02] PD2/TIM3_ETR/UART5_RX/SDIO_CMD 54 TEST1
*/
#define GPIO_TEST1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTD | GPIO_PIN2 | GPIO_OUTPUT_CLEAR)
#define GPIO_TEST1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | GPIO_PORTD | GPIO_PIN2 | GPIO_OUTPUT_CLEAR)
__BEGIN_DECLS

View File

@ -259,17 +259,13 @@
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
#define GPIO_I2C1_SCL_GPIO \
(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO \
(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1
#define GPIO_I2C2_SCL_GPIO \
(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
#define GPIO_I2C2_SDA_GPIO \
(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
/* SPI
*

View File

@ -259,17 +259,13 @@
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
#define GPIO_I2C1_SCL_GPIO \
(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO \
(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1
#define GPIO_I2C2_SCL_GPIO \
(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
#define GPIO_I2C2_SDA_GPIO \
(GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11)
/* SPI
*

View File

@ -286,14 +286,14 @@
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
} while(0)
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
} while(0)
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)

View File

@ -415,70 +415,26 @@
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8] */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTB | \
GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTB | \
GPIO_PIN9)
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN1)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN0)
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0)
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTH | \
GPIO_PIN7)
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTH | \
GPIO_PIN8)
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN7)
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8)
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN14)
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN15)
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14)
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15)
/* SDMMC1
*
@ -515,16 +471,16 @@
# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 */
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \
if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \
} while(0)
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \
if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \
} while(0)
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)

View File

@ -215,7 +215,7 @@
/* UART6:
*
* The STM32F4 Discovery has no on-board serial devices, PC6 (TX) and PC7 (RX)
* The STM32F4 Discovery has no on-board serial devices, PC6 (TX) and PC7 (RX)
* for connection to an external serial device.
*/
@ -224,7 +224,7 @@
/* USART6 require a RX DMA configuration */
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_1
/* SPI - There is a MEMS device on SPI1 using these pins: */
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1

View File

@ -438,19 +438,8 @@
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8[CN12-3] */
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9[CN12-5] */
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTB | \
GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTB | \
GPIO_PIN9)
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
/* PF1 can not be used on Morpho connector without SB mods. */
#if defined(CONFIG_STM32F7_I2C2)
@ -459,36 +448,14 @@
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1[CN11-51] */
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0[CN11-53] */
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN1)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN0)
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET |GPIO_PORTF | GPIO_PIN1)
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET |GPIO_PORTF | GPIO_PIN0)
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14[CN12-50] */
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15[CN12-60] */
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN14)
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | \
GPIO_OPENDRAIN | \
GPIO_SPEED_50MHz| \
GPIO_OUTPUT_SET | \
GPIO_PORTF | \
GPIO_PIN14)
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14)
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14)
/* SDMMC1
*
@ -550,14 +517,14 @@
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14[CN12-46] */
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
} while(0)
do { \
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
} while(0)
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)

View File

@ -76,8 +76,7 @@
* PB[6] PB06 29 nCAN_SILENT
*/
#define GPIO_CAN_SILENT (GPIO_OUTPUT | GPIO_PUSHPULL | \
GPIO_PORTB | GPIO_PIN6 | GPIO_OUTPUT_CLEAR)
#define GPIO_CAN_SILENT (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_PORTB | GPIO_PIN6 | GPIO_OUTPUT_CLEAR)
__BEGIN_DECLS