reworked gpio pin handling functions
This commit is contained in:
parent
5c9dc5ebfc
commit
83c834091c
|
@ -1,5 +1,7 @@
|
|||
#
|
||||
|
||||
menu.usb_cfg=USB configuration
|
||||
|
||||
##############################################################
|
||||
discovery_f407.name=STM32 Discovery F407
|
||||
|
||||
|
@ -57,6 +59,15 @@ generic_f407v.build.error_led_port=GPIOA
|
|||
generic_f407v.build.error_led_pin=7
|
||||
generic_f407v.build.board=STM32GenericF407VET6
|
||||
|
||||
generic_f407v.menu.usb_cfg.usb_nc=USB inactive
|
||||
generic_f407v.menu.usb_cfg.usb_nc.build.cpu_flags=-DUSB_NC
|
||||
|
||||
generic_f407v.menu.usb_cfg.usb_serial=USB serial (CDC)
|
||||
generic_f407v.menu.usb_cfg.usb_serial.build.cpu_flags=-DSERIAL_USB
|
||||
|
||||
generic_f407v.menu.usb_cfg.usb_msc=USB Mass Storage (MSC)
|
||||
generic_f407v.menu.usb_cfg.usb_msc.build.cpu_flags=-DUSB_MSC
|
||||
|
||||
##############################################################
|
||||
stm32f4stamp.name=STM32F4Stamp F405
|
||||
|
||||
|
|
|
@ -41,6 +41,7 @@
|
|||
#include "adc.h"
|
||||
#include "timer.h"
|
||||
#include "usb.h"
|
||||
#include "usb_serial.h"
|
||||
|
||||
|
||||
static void setupFlash(void);
|
||||
|
@ -67,7 +68,10 @@ void init(void) {
|
|||
setupADC();
|
||||
setupTimers();
|
||||
|
||||
#ifdef SERIAL_USB
|
||||
setupUSB();
|
||||
SerialUSB.begin();
|
||||
#endif
|
||||
}
|
||||
|
||||
/* You could farm this out to the files in boards/ if e.g. it takes
|
||||
|
|
|
@ -40,7 +40,6 @@
|
|||
#define _BOARDS_H_
|
||||
|
||||
#include "libmaple.h"
|
||||
#include "gpio.h"
|
||||
#include "timer.h"
|
||||
|
||||
#include "wirish_types.h"
|
||||
|
@ -55,9 +54,12 @@ enum {
|
|||
D32, D33, D34, D35, D36, D37, D38, D39, D40, D41, D42, D43, D44, D45, D46,
|
||||
D47, D48, D49, D50, D51, D52, D53, D54, D55, D56, D57, D58, D59, D60, D61,
|
||||
D62, D63, D64, D65, D66, D67, D68, D69, D70, D71, D72, D73, D74, D75, D76,
|
||||
#if 0 // not available on LQFP100 package
|
||||
D77, D78, D79, D80, D81, D82, D83, D84, D85, D86, D87, D88, D89, D90, D91,
|
||||
D92, D93, D94, D95, D96, D97, D98, D99, D100, D101, D102, D103, D104, D105,
|
||||
D106, D107, D108, D109, D110, D111, };
|
||||
D106, D107, D108, D109, D110, D111,
|
||||
#endif // not available on LQFP100 package
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Maps each Maple pin to a corresponding stm32_pin_info.
|
||||
|
@ -115,26 +117,13 @@ extern void boardInit(void);
|
|||
* @return true if the given pin is in boardUsedPins, and false otherwise.
|
||||
* @see boardUsedPins
|
||||
*/
|
||||
bool boardUsesPin(uint8 pin);
|
||||
extern bool boardUsesPin(uint8 pin);
|
||||
|
||||
/* Include the appropriate private header from boards/: */
|
||||
|
||||
/* FIXME HACK put boards/ before these paths once IDE uses make. */
|
||||
|
||||
#ifdef BOARD_maple
|
||||
#include "maple.h"
|
||||
#elif defined(BOARD_maple_native)
|
||||
#include "maple_native.h"
|
||||
#elif defined(BOARD_maple_mini)
|
||||
#include "maple_mini.h"
|
||||
#elif defined(BOARD_maple_RET6)
|
||||
/*
|
||||
* **NOT** MAPLE REV6. This the **Maple RET6 EDITION**, which is a
|
||||
* Maple with an STM32F103RET6 (...RET6) instead of an STM32F103RBT6
|
||||
* (...RBT6) on it. Maple Rev6 (as of March 2011) DOES NOT EXIST.
|
||||
*/
|
||||
#include "maple_RET6.h"
|
||||
#elif defined(BOARD_aeroquad32) || defined(BOARD_aeroquad32f1)
|
||||
#if defined(BOARD_aeroquad32) || defined(BOARD_aeroquad32f1)
|
||||
#include "aeroquad32.h"
|
||||
#elif defined(BOARD_aeroquad32mini)
|
||||
#include "aeroquad32mini.h"
|
||||
|
|
|
@ -56,19 +56,19 @@
|
|||
#define RX5 BOARD_UART5_RX_PIN
|
||||
#endif
|
||||
|
||||
HardwareSerial Serial(USART1, TX1, RX1);
|
||||
HardwareSerial Serial1(USART1, TX1, RX1);
|
||||
|
||||
#ifdef TX2
|
||||
HardwareSerial Serial1(USART2, TX2, RX2);
|
||||
HardwareSerial Serial2(USART2, TX2, RX2);
|
||||
#endif
|
||||
|
||||
#ifdef TX3
|
||||
HardwareSerial Serial2(USART3, TX3, RX3);
|
||||
HardwareSerial Serial3(USART3, TX3, RX3);
|
||||
#endif
|
||||
|
||||
#if defined(STM32_HIGH_DENSITY) && !defined(BOARD_maple_RET6)
|
||||
HardwareSerial Serial3(UART4, TX4, RX4);
|
||||
HardwareSerial Serial4(UART5, TX5, RX5);
|
||||
HardwareSerial Serial4(UART4, TX4, RX4);
|
||||
HardwareSerial Serial5(UART5, TX5, RX5);
|
||||
#endif
|
||||
|
||||
HardwareSerial::HardwareSerial(usart_dev *usart_device,
|
||||
|
@ -90,25 +90,23 @@ void HardwareSerial::begin(uint32 baud) {
|
|||
return;
|
||||
}
|
||||
|
||||
const stm32_pin_info *txi = &PIN_MAP[tx_pin];
|
||||
const stm32_pin_info *rxi = &PIN_MAP[rx_pin];
|
||||
#ifdef STM32F4
|
||||
// int af = 7<<8;
|
||||
if (usart_device == UART4 || usart_device == UART5) {
|
||||
gpio_set_af_mode(txi->gpio_device, txi->gpio_bit, 8);
|
||||
gpio_set_af_mode(rxi->gpio_device, rxi->gpio_bit, 8);
|
||||
gpio_set_af_mode(tx_pin, 8);
|
||||
gpio_set_af_mode(rx_pin, 8);
|
||||
}
|
||||
else {
|
||||
gpio_set_af_mode(txi->gpio_device, txi->gpio_bit, 7);
|
||||
gpio_set_af_mode(rxi->gpio_device, rxi->gpio_bit, 7);
|
||||
gpio_set_af_mode(tx_pin, 7);
|
||||
gpio_set_af_mode(rx_pin, 7);
|
||||
}
|
||||
gpio_set_mode(txi->gpio_device, txi->gpio_bit, (gpio_pin_mode)(GPIO_AF_OUTPUT_PP | GPIO_PUPD_INPUT_PU | 0x700));
|
||||
gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, (gpio_pin_mode)(GPIO_MODE_AF | GPIO_PUPD_INPUT_PU | 0x700));
|
||||
gpio_set_mode(tx_pin, (gpio_pin_mode)(GPIO_AF_OUTPUT_PP | GPIO_PUPD_INPUT_PU | 0x700));
|
||||
gpio_set_mode(rx_pin, (gpio_pin_mode)(GPIO_MODE_AF | GPIO_PUPD_INPUT_PU | 0x700));
|
||||
//gpio_set_mode(txi->gpio_device, txi->gpio_bit, (gpio_pin_mode)(GPIO_PUPD_INPUT_PU));
|
||||
//gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, (gpio_pin_mode)(GPIO_PUPD_INPUT_PU));
|
||||
#else
|
||||
gpio_set_mode(txi->gpio_device, txi->gpio_bit, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(tx_pin, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(rx_pin, GPIO_INPUT_FLOATING);
|
||||
#endif
|
||||
#if 0
|
||||
if (txi->timer_device != NULL) {
|
||||
|
|
|
@ -75,12 +75,12 @@ private:
|
|||
uint8 rx_pin;
|
||||
};
|
||||
|
||||
extern HardwareSerial Serial;
|
||||
extern HardwareSerial Serial1;
|
||||
extern HardwareSerial Serial2;
|
||||
#if defined(STM32_HIGH_DENSITY) && !defined(BOARD_maple_RET6)
|
||||
extern HardwareSerial Serial3;
|
||||
extern HardwareSerial Serial4;
|
||||
extern HardwareSerial Serial5;
|
||||
#endif
|
||||
extern HardwareSerial &SerialDebug;
|
||||
#endif
|
||||
|
|
|
@ -126,11 +126,11 @@ void dac_enable_channel(const dac_dev *dev, uint8 channel) {
|
|||
*/
|
||||
switch (channel) {
|
||||
case 1:
|
||||
gpio_set_mode(GPIOA, 4, GPIO_INPUT_ANALOG);
|
||||
gpio_set_mode((uint8_t)PA4, GPIO_INPUT_ANALOG);
|
||||
dev->regs->CR |= DAC_CR_EN1;
|
||||
break;
|
||||
case 2:
|
||||
gpio_set_mode(GPIOA, 5, GPIO_INPUT_ANALOG);
|
||||
gpio_set_mode((uint8_t)PA5, GPIO_INPUT_ANALOG);
|
||||
dev->regs->CR |= DAC_CR_EN2;
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -39,27 +39,28 @@
|
|||
*/
|
||||
void fsmc_sram_init_gpios(void) {
|
||||
/* Data lines... */
|
||||
gpio_set_mode(GPIOD, 0, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOD, 1, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOD, 8, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOD, 9, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOD, 10, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOD, 14, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOD, 15, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOE, 7, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOE, 8, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOE, 9, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOE, 10, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOE, 11, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOE, 12, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOE, 13, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOE, 14, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOE, 15, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PD0, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PD1, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PD8, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PD9, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PD10, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PD14, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PD15, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PE7, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PE8, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PE9, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PE10, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PE11, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PE12, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PE13, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PE14, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PE15, GPIO_AF_OUTPUT_PP);
|
||||
|
||||
/* Address lines... */
|
||||
gpio_set_mode(GPIOD, 11, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOD, 12, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOD, 13, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PD11, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PD12, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(PD13, GPIO_AF_OUTPUT_PP);
|
||||
#if 0 // not available on LQFP package
|
||||
gpio_set_mode(GPIOF, 0, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOF, 1, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOF, 2, GPIO_AF_OUTPUT_PP);
|
||||
|
@ -76,18 +77,20 @@ void fsmc_sram_init_gpios(void) {
|
|||
gpio_set_mode(GPIOG, 3, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOG, 4, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(GPIOG, 5, GPIO_AF_OUTPUT_PP);
|
||||
|
||||
#endif // not available on LQFP package
|
||||
/* And control lines... */
|
||||
gpio_set_mode(GPIOD, 4, GPIO_AF_OUTPUT_PP); // NOE
|
||||
gpio_set_mode(GPIOD, 5, GPIO_AF_OUTPUT_PP); // NWE
|
||||
gpio_set_mode(PD4, GPIO_AF_OUTPUT_PP); // NOE
|
||||
gpio_set_mode(PD5, GPIO_AF_OUTPUT_PP); // NWE
|
||||
|
||||
gpio_set_mode(GPIOD, 7, GPIO_AF_OUTPUT_PP); // NE1
|
||||
gpio_set_mode(PD7, GPIO_AF_OUTPUT_PP); // NE1
|
||||
#if 0 // not available on LQFP package
|
||||
gpio_set_mode(GPIOG, 9, GPIO_AF_OUTPUT_PP); // NE2
|
||||
gpio_set_mode(GPIOG, 10, GPIO_AF_OUTPUT_PP); // NE3
|
||||
gpio_set_mode(GPIOG, 12, GPIO_AF_OUTPUT_PP); // NE4
|
||||
#endif // not available on LQFP package
|
||||
|
||||
gpio_set_mode(GPIOE, 0, GPIO_AF_OUTPUT_PP); // NBL0
|
||||
gpio_set_mode(GPIOE, 1, GPIO_AF_OUTPUT_PP); // NBL1
|
||||
gpio_set_mode(PE0, GPIO_AF_OUTPUT_PP); // NBL0
|
||||
gpio_set_mode(PE1, GPIO_AF_OUTPUT_PP); // NBL1
|
||||
}
|
||||
|
||||
#endif /* STM32_HIGH_DENSITY */
|
||||
|
|
|
@ -31,5 +31,102 @@
|
|||
* (AFIO) prototypes, defines, and inlined access functions.
|
||||
*/
|
||||
|
||||
#ifndef _GPIO_H_
|
||||
#define _GPIO_H_
|
||||
|
||||
#include "libmaple.h"
|
||||
#include "boards.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"{
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get a GPIO port's corresponding afio_exti_port.
|
||||
* @param dev GPIO device whose afio_exti_port to return.
|
||||
*/
|
||||
static inline afio_exti_port gpio_exti_port(gpio_dev *dev) {
|
||||
return dev->exti_port;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set or reset a GPIO pin.
|
||||
*
|
||||
* Pin must have previously been configured to output mode.
|
||||
*
|
||||
* @param dev GPIO device whose pin to set.
|
||||
* @param pin Pin on to set or reset
|
||||
* @param val If true, set the pin. If false, reset the pin.
|
||||
*/
|
||||
static inline void gpio_write_pin(uint8_t pin, uint8 val) {
|
||||
if (val) {
|
||||
(PIN_MAP[pin].gpio_device)->regs->BSRRL = BIT(PIN_MAP[pin].gpio_bit);
|
||||
} else {
|
||||
(PIN_MAP[pin].gpio_device)->regs->BSRRH = BIT(PIN_MAP[pin].gpio_bit);
|
||||
}
|
||||
}
|
||||
|
||||
static inline void gpio_set_pin(uint8_t pin) {
|
||||
(PIN_MAP[pin].gpio_device)->regs->BSRRL = BIT(PIN_MAP[pin].gpio_bit);
|
||||
}
|
||||
|
||||
static inline void gpio_clear_pin(uint8_t pin) {
|
||||
(PIN_MAP[pin].gpio_device)->regs->BSRRH = BIT(PIN_MAP[pin].gpio_bit);
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine whether or not a GPIO pin is set.
|
||||
*
|
||||
* Pin must have previously been configured to input mode.
|
||||
*
|
||||
* @param dev GPIO device whose pin to test.
|
||||
* @param pin Pin on dev to test.
|
||||
* @return True if the pin is set, false otherwise.
|
||||
*/
|
||||
static inline uint32 gpio_read_pin(uint8_t pin) {
|
||||
return (PIN_MAP[pin].gpio_device)->regs->IDR & BIT(PIN_MAP[pin].gpio_bit);
|
||||
}
|
||||
|
||||
/**
|
||||
* Toggle a pin configured as output push-pull.
|
||||
* @param dev GPIO device.
|
||||
* @param pin Pin on dev to toggle.
|
||||
*/
|
||||
static inline void gpio_toggle_pin(uint8_t pin) {
|
||||
(PIN_MAP[pin].gpio_device)->regs->ODR = (PIN_MAP[pin].gpio_device)->regs->ODR ^ BIT(PIN_MAP[pin].gpio_bit);
|
||||
}
|
||||
|
||||
/*
|
||||
* GPIO Convenience routines
|
||||
*/
|
||||
|
||||
extern void gpio_init(gpio_dev *dev);
|
||||
extern void gpio_init_all(void);
|
||||
extern void gpio_set_mode(uint8_t pin, gpio_pin_mode mode);
|
||||
extern void gpio_set_af_mode(uint8_t pin, int mode);
|
||||
|
||||
/*
|
||||
* AFIO convenience routines
|
||||
*/
|
||||
|
||||
extern void afio_init(void);
|
||||
extern void afio_exti_select(afio_exti_num exti, afio_exti_port gpio_port);
|
||||
extern void afio_remap(afio_remap_peripheral p);
|
||||
|
||||
/**
|
||||
* @brief Enable or disable the JTAG and SW debug ports.
|
||||
* @param config Desired debug port configuration
|
||||
* @see afio_debug_cfg
|
||||
*/
|
||||
static inline void afio_cfg_debug_ports(afio_debug_cfg config) {
|
||||
//__io uint32 *mapr = &AFIO_BASE->MAPR;
|
||||
//*mapr = (*mapr & ~AFIO_MAPR_SWJ_CFG) | config;
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#include "gpioF4.h"
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
* SOFTWARE.
|
||||
*****************************************************************************/
|
||||
|
||||
#ifdef STM32F4
|
||||
#ifdef STM32F4
|
||||
|
||||
/**
|
||||
* @file gpio.c
|
||||
|
@ -79,6 +79,7 @@ gpio_dev gpioe = {
|
|||
/** GPIO port E device. */
|
||||
gpio_dev* const GPIOE = &gpioe;
|
||||
|
||||
#if 0 // not available on LQFP 100 package
|
||||
gpio_dev gpiof = {
|
||||
.regs = GPIOF_BASE,
|
||||
.clk_id = RCC_GPIOF,
|
||||
|
@ -94,6 +95,7 @@ gpio_dev gpiog = {
|
|||
};
|
||||
/** GPIO port G device. */
|
||||
gpio_dev* const GPIOG = &gpiog;
|
||||
#endif // not available on LQFP 100 package
|
||||
#endif
|
||||
|
||||
/*
|
||||
|
@ -122,9 +124,11 @@ void gpio_init_all(void) {
|
|||
gpio_init(GPIOD);
|
||||
|
||||
#ifdef STM32_HIGH_DENSITY
|
||||
gpio_init(GPIOE);
|
||||
gpio_init(GPIOF);
|
||||
gpio_init(GPIOG);
|
||||
gpio_init(GPIOE);
|
||||
#if 0 // not available on LQFP 100 package
|
||||
gpio_init(GPIOF);
|
||||
gpio_init(GPIOG);
|
||||
#endif // not available on LQFP 100 package
|
||||
#endif
|
||||
|
||||
#ifdef ARDUINO_STM32F4_NETDUINO2PLUS
|
||||
|
@ -148,8 +152,9 @@ void gpio_init_all(void) {
|
|||
* @param mode General purpose or alternate function mode to set the pin to.
|
||||
* @see gpio_pin_mode
|
||||
*/
|
||||
void gpio_set_mode(gpio_dev *dev, uint8 pin, gpio_pin_mode mode) {
|
||||
gpio_reg_map *regs = dev->regs;
|
||||
void gpio_set_mode(uint8_t io_pin, gpio_pin_mode mode) {
|
||||
gpio_reg_map *regs = (PIN_MAP[io_pin].gpio_device)->regs;
|
||||
uint8_t pin = PIN_MAP[io_pin].gpio_bit;
|
||||
|
||||
//regs->AFR[pin/8] = (regs->AFR[pin/8] & ~(15 << (4*(pin&7)))) | (((mode >> 8) & 15) << (4*(pin&7)));
|
||||
//gpio_set_af_mode(dev, pin, mode>>8);
|
||||
|
@ -168,10 +173,11 @@ void gpio_set_mode(gpio_dev *dev, uint8 pin, gpio_pin_mode mode) {
|
|||
* @param mode alternate function mode to set the pin to.
|
||||
* @see gpio_pin_mode
|
||||
*/
|
||||
void gpio_set_af_mode(gpio_dev *dev, uint8 pin, int mode) {
|
||||
gpio_reg_map *regs = dev->regs;
|
||||
void gpio_set_af_mode(uint8_t io_pin, int mode) {
|
||||
gpio_reg_map *regs = (PIN_MAP[io_pin].gpio_device)->regs;
|
||||
uint8_t pin = PIN_MAP[io_pin].gpio_bit;
|
||||
|
||||
regs->AFR[pin/8] = (regs->AFR[pin/8] & ~(15 << (4*(pin&7)))) | (((mode >> 0) & 15) << (4*(pin&7)));
|
||||
regs->AFR[pin>>3] = (regs->AFR[pin>>3] & ~(15 << (4*(pin&7)))) | (((mode >> 0) & 15) << (4*(pin&7)));
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -31,11 +31,12 @@
|
|||
* (AFIO) prototypes, defines, and inlined access functions.
|
||||
*/
|
||||
|
||||
#ifndef _GPIO_H_
|
||||
#define _GPIO_H_
|
||||
#ifndef _GPIO_DEF_H_
|
||||
#define _GPIO_DEF_H_
|
||||
|
||||
#include "libmaple.h"
|
||||
#include "rcc.h"
|
||||
#include "wirish_types.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"{
|
||||
|
@ -74,11 +75,14 @@ typedef enum afio_exti_port {
|
|||
AFIO_EXTI_PD, /**< Use port D (PDx) pin. */
|
||||
#ifdef STM32_HIGH_DENSITY
|
||||
AFIO_EXTI_PE, /**< Use port E (PEx) pin. */
|
||||
#if 0 // not available on LQFP 100 package
|
||||
AFIO_EXTI_PF, /**< Use port F (PFx) pin. */
|
||||
AFIO_EXTI_PG, /**< Use port G (PGx) pin. */
|
||||
#endif // not available on LQFP 100 package
|
||||
#endif
|
||||
} afio_exti_port;
|
||||
|
||||
|
||||
/** GPIO device type */
|
||||
typedef struct gpio_dev {
|
||||
gpio_reg_map *regs; /**< Register map */
|
||||
|
@ -97,10 +101,12 @@ extern gpio_dev* const GPIOD;
|
|||
#ifdef STM32_HIGH_DENSITY
|
||||
extern gpio_dev gpioe;
|
||||
extern gpio_dev* const GPIOE;
|
||||
#if 0 // not available on LQFP 100 package
|
||||
extern gpio_dev gpiof;
|
||||
extern gpio_dev* const GPIOF;
|
||||
extern gpio_dev gpiog;
|
||||
extern gpio_dev* const GPIOG;
|
||||
#endif // not available on LQFP 100 package
|
||||
#endif
|
||||
|
||||
/** GPIO port register map base pointer */
|
||||
|
@ -110,8 +116,10 @@ extern gpio_dev* const GPIOG;
|
|||
#define GPIOD_BASE ((struct gpio_reg_map*)0x40020C00)
|
||||
#ifdef STM32_HIGH_DENSITY
|
||||
#define GPIOE_BASE ((struct gpio_reg_map*)0x40021000)
|
||||
#if 0 // not available on LQFP 100 package
|
||||
#define GPIOF_BASE ((struct gpio_reg_map*)0x40021400)
|
||||
#define GPIOG_BASE ((struct gpio_reg_map*)0x40021800)
|
||||
#endif // not available on LQFP 100 package
|
||||
#endif
|
||||
|
||||
/*
|
||||
|
@ -190,61 +198,6 @@ typedef enum gpio_pin_mode {
|
|||
GPIO_BIGNUMBER = 0xfff
|
||||
} gpio_pin_mode;
|
||||
|
||||
/*
|
||||
* GPIO Convenience routines
|
||||
*/
|
||||
|
||||
void gpio_init(gpio_dev *dev);
|
||||
void gpio_init_all(void);
|
||||
void gpio_set_mode(gpio_dev *dev, uint8 pin, gpio_pin_mode mode);
|
||||
void gpio_set_af_mode(gpio_dev *dev, uint8 pin, int mode);
|
||||
|
||||
/**
|
||||
* @brief Get a GPIO port's corresponding afio_exti_port.
|
||||
* @param dev GPIO device whose afio_exti_port to return.
|
||||
*/
|
||||
static inline afio_exti_port gpio_exti_port(gpio_dev *dev) {
|
||||
return dev->exti_port;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set or reset a GPIO pin.
|
||||
*
|
||||
* Pin must have previously been configured to output mode.
|
||||
*
|
||||
* @param dev GPIO device whose pin to set.
|
||||
* @param pin Pin on to set or reset
|
||||
* @param val If true, set the pin. If false, reset the pin.
|
||||
*/
|
||||
static inline void gpio_write_bit(gpio_dev *dev, uint8 pin, uint8 val) {
|
||||
if (val) {
|
||||
dev->regs->BSRRL = BIT(pin);
|
||||
} else {
|
||||
dev->regs->BSRRH = BIT(pin);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine whether or not a GPIO pin is set.
|
||||
*
|
||||
* Pin must have previously been configured to input mode.
|
||||
*
|
||||
* @param dev GPIO device whose pin to test.
|
||||
* @param pin Pin on dev to test.
|
||||
* @return True if the pin is set, false otherwise.
|
||||
*/
|
||||
static inline uint32 gpio_read_bit(gpio_dev *dev, uint8 pin) {
|
||||
return dev->regs->IDR & BIT(pin);
|
||||
}
|
||||
|
||||
/**
|
||||
* Toggle a pin configured as output push-pull.
|
||||
* @param dev GPIO device.
|
||||
* @param pin Pin on dev to toggle.
|
||||
*/
|
||||
static inline void gpio_toggle_bit(gpio_dev *dev, uint8 pin) {
|
||||
dev->regs->ODR = dev->regs->ODR ^ BIT(pin);
|
||||
}
|
||||
|
||||
/*
|
||||
* AFIO register map
|
||||
|
@ -532,15 +485,6 @@ typedef enum afio_debug_cfg {
|
|||
for use as GPIOs. */
|
||||
} afio_debug_cfg;
|
||||
|
||||
/**
|
||||
* @brief Enable or disable the JTAG and SW debug ports.
|
||||
* @param config Desired debug port configuration
|
||||
* @see afio_debug_cfg
|
||||
*/
|
||||
static inline void afio_cfg_debug_ports(afio_debug_cfg config) {
|
||||
//__io uint32 *mapr = &AFIO_BASE->MAPR;
|
||||
//*mapr = (*mapr & ~AFIO_MAPR_SWJ_CFG) | config;
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
|
@ -41,9 +41,9 @@
|
|||
|
||||
static i2c_dev i2c_dev1 = {
|
||||
.regs = I2C1_BASE,
|
||||
.gpio_port = &gpiob,
|
||||
.sda_pin = 7,
|
||||
.scl_pin = 6,
|
||||
//.gpio_port = &gpiob,
|
||||
.sda_pin = PB7,
|
||||
.scl_pin = PB6,
|
||||
.clk_id = RCC_I2C1,
|
||||
.ev_nvic_line = NVIC_I2C1_EV,
|
||||
.er_nvic_line = NVIC_I2C1_ER,
|
||||
|
@ -54,9 +54,9 @@ i2c_dev* const I2C1 = &i2c_dev1;
|
|||
|
||||
static i2c_dev i2c_dev2 = {
|
||||
.regs = I2C2_BASE,
|
||||
.gpio_port = &gpiob,
|
||||
.sda_pin = 11,
|
||||
.scl_pin = 10,
|
||||
//.gpio_port = &gpiob,
|
||||
.sda_pin = PB11,
|
||||
.scl_pin = PB10,
|
||||
.clk_id = RCC_I2C2,
|
||||
.ev_nvic_line = NVIC_I2C2_EV,
|
||||
.er_nvic_line = NVIC_I2C2_ER,
|
||||
|
@ -336,38 +336,38 @@ void __irq_i2c2_er(void) {
|
|||
*/
|
||||
void i2c_bus_reset(const i2c_dev *dev) {
|
||||
/* Release both lines */
|
||||
gpio_write_bit(dev->gpio_port, dev->scl_pin, 1);
|
||||
gpio_write_bit(dev->gpio_port, dev->sda_pin, 1);
|
||||
gpio_set_mode(dev->gpio_port, dev->scl_pin, GPIO_OUTPUT_OD);
|
||||
gpio_set_mode(dev->gpio_port, dev->sda_pin, GPIO_OUTPUT_OD);
|
||||
gpio_set_pin(dev->scl_pin);
|
||||
gpio_set_pin(dev->sda_pin);
|
||||
gpio_set_mode(dev->scl_pin, GPIO_OUTPUT_OD);
|
||||
gpio_set_mode(dev->sda_pin, GPIO_OUTPUT_OD);
|
||||
|
||||
/*
|
||||
* Make sure the bus is free by clocking it until any slaves release the
|
||||
* bus.
|
||||
*/
|
||||
while (!gpio_read_bit(dev->gpio_port, dev->sda_pin)) {
|
||||
while (!gpio_read_pin(dev->sda_pin)) {
|
||||
/* Wait for any clock stretching to finish */
|
||||
while (!gpio_read_bit(dev->gpio_port, dev->scl_pin))
|
||||
while (!gpio_read_pin(dev->scl_pin))
|
||||
;
|
||||
delay_us(10);
|
||||
|
||||
/* Pull low */
|
||||
gpio_write_bit(dev->gpio_port, dev->scl_pin, 0);
|
||||
gpio_clear_pin(dev->scl_pin);
|
||||
delay_us(10);
|
||||
|
||||
/* Release high again */
|
||||
gpio_write_bit(dev->gpio_port, dev->scl_pin, 1);
|
||||
gpio_set_pin(dev->scl_pin);
|
||||
delay_us(10);
|
||||
}
|
||||
|
||||
/* Generate start then stop condition */
|
||||
gpio_write_bit(dev->gpio_port, dev->sda_pin, 0);
|
||||
gpio_clear_pin(dev->sda_pin);
|
||||
delay_us(10);
|
||||
gpio_write_bit(dev->gpio_port, dev->scl_pin, 0);
|
||||
gpio_clear_pin(dev->scl_pin);
|
||||
delay_us(10);
|
||||
gpio_write_bit(dev->gpio_port, dev->scl_pin, 1);
|
||||
gpio_set_pin(dev->scl_pin);
|
||||
delay_us(10);
|
||||
gpio_write_bit(dev->gpio_port, dev->sda_pin, 1);
|
||||
gpio_set_pin(dev->sda_pin);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -413,8 +413,8 @@ void i2c_master_enable(i2c_dev *dev, uint32 flags) {
|
|||
|
||||
/* Turn on clock and set GPIO modes */
|
||||
i2c_init(dev);
|
||||
gpio_set_mode(dev->gpio_port, dev->sda_pin, GPIO_AF_OUTPUT_OD);
|
||||
gpio_set_mode(dev->gpio_port, dev->scl_pin, GPIO_AF_OUTPUT_OD);
|
||||
gpio_set_mode(dev->sda_pin, GPIO_AF_OUTPUT_OD);
|
||||
gpio_set_mode(dev->scl_pin, GPIO_AF_OUTPUT_OD);
|
||||
|
||||
/* I2C1 and I2C2 are fed from APB1, clocked at 36MHz */
|
||||
i2c_set_input_clk(dev, I2C_CLK);
|
||||
|
|
|
@ -78,7 +78,7 @@ typedef struct i2c_msg {
|
|||
*/
|
||||
typedef struct i2c_dev {
|
||||
i2c_reg_map *regs; /**< Register map */
|
||||
gpio_dev *gpio_port; /**< SDA, SCL pins' GPIO port */
|
||||
//gpio_dev *gpio_port; /**< SDA, SCL pins' GPIO port */
|
||||
uint8 sda_pin; /**< SDA bit on gpio_port */
|
||||
uint8 scl_pin; /**< SCL bit on gpio_port */
|
||||
rcc_clk_id clk_id; /**< RCC clock information */
|
||||
|
|
|
@ -33,6 +33,9 @@
|
|||
#ifndef _LIBMAPLE_TYPES_H_
|
||||
#define _LIBMAPLE_TYPES_H_
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
typedef unsigned char uint8;
|
||||
typedef unsigned short uint16;
|
||||
typedef unsigned int uint32;
|
||||
|
|
|
@ -166,7 +166,6 @@ typedef struct
|
|||
#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE)
|
||||
#define RESET 0
|
||||
|
||||
typedef uint32 uint32_t;
|
||||
|
||||
void InitMCO1()
|
||||
{
|
||||
|
@ -175,8 +174,8 @@ void InitMCO1()
|
|||
RCC->CFGR &= RCC_CFGR_MCO1_RESET_MASK;
|
||||
RCC->CFGR |= RCC_CFGR_MCO1Source_HSE | RCC_CFGR_MCO1Div_1;
|
||||
// PA8 Output the Master Clock MCO1
|
||||
gpio_set_af_mode(GPIOA, 8, 0);
|
||||
gpio_set_mode(GPIOA, 8, GPIO_MODE_AF | GPIO_OTYPE_PP | GPIO_OSPEED_100MHZ);
|
||||
gpio_set_af_mode(PA8, 0);
|
||||
gpio_set_mode(PA8, GPIO_MODE_AF | GPIO_OTYPE_PP | GPIO_OSPEED_100MHZ);
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -230,14 +230,10 @@ struct gpio_dev;
|
|||
*/
|
||||
extern void spi_config_gpios(spi_dev *dev,
|
||||
uint8 as_master,
|
||||
struct gpio_dev *nss_dev,
|
||||
uint8 nss_bit,
|
||||
struct gpio_dev *sck_dev,
|
||||
uint8 sck_bit,
|
||||
struct gpio_dev *miso_dev,
|
||||
uint8 miso_bit,
|
||||
struct gpio_dev *mosi_dev,
|
||||
uint8 mosi_bit);
|
||||
uint8 nss_pin,
|
||||
uint8 sck_pin,
|
||||
uint8 miso_pin,
|
||||
uint8 mosi_pin);
|
||||
|
||||
/**
|
||||
* @brief SPI mode configuration.
|
||||
|
|
|
@ -62,17 +62,6 @@ extern struct spi_dev *SPI2;
|
|||
extern struct spi_dev *SPI3;
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Routines
|
||||
*/
|
||||
|
||||
/* spi_gpio_cfg(): Backwards compatibility shim to spi_config_gpios() */
|
||||
struct gpio_dev;
|
||||
extern void spi_config_gpios(struct spi_dev*, uint8,
|
||||
struct gpio_dev*, uint8,
|
||||
struct gpio_dev*, uint8,
|
||||
struct gpio_dev*, uint8,
|
||||
struct gpio_dev*, uint8);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
|
|
@ -56,25 +56,21 @@ spi_dev *SPI3 = &spi3;
|
|||
|
||||
void spi_config_gpios(spi_dev *ignored,
|
||||
uint8 as_master,
|
||||
gpio_dev *nss_dev,
|
||||
uint8 nss_bit,
|
||||
gpio_dev *sck_dev,
|
||||
uint8 sck_bit,
|
||||
gpio_dev *miso_dev,
|
||||
uint8 miso_bit,
|
||||
gpio_dev *mosi_dev,
|
||||
uint8 mosi_bit) {
|
||||
uint8 nss_pin,
|
||||
uint8 sck_pin,
|
||||
uint8 miso_pin,
|
||||
uint8 mosi_pin) {
|
||||
if (as_master) {
|
||||
// gpio_set_mode(nss_dev, nss_bit, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(sck_dev, sck_bit, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(sck_pin, GPIO_AF_OUTPUT_PP);
|
||||
// gpio_set_mode(comm_dev, miso_bit, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(miso_dev, miso_bit, GPIO_AF_INPUT_PD);
|
||||
gpio_set_mode(mosi_dev, mosi_bit, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(miso_pin, GPIO_AF_INPUT_PD);
|
||||
gpio_set_mode(mosi_pin, GPIO_AF_OUTPUT_PP);
|
||||
} else {
|
||||
gpio_set_mode(nss_dev, nss_bit, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(sck_dev, sck_bit, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(miso_dev, miso_bit, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(mosi_dev, mosi_bit, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(nss_pin, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(sck_pin, GPIO_INPUT_FLOATING);
|
||||
gpio_set_mode(miso_pin, GPIO_AF_OUTPUT_PP);
|
||||
gpio_set_mode(mosi_pin, GPIO_INPUT_FLOATING);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -97,10 +97,10 @@ void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev)
|
|||
{
|
||||
// ala42
|
||||
#define GPIO_AF_OTG1_FS ((uint8_t)0xA) /* OTG_FS Alternate Function mapping */
|
||||
gpio_set_mode(GPIOA,11,GPIO_MODE_AF | GPIO_OTYPE_PP | GPIO_OSPEED_100MHZ);
|
||||
gpio_set_mode(GPIOA,12,GPIO_MODE_AF | GPIO_OTYPE_PP | GPIO_OSPEED_100MHZ);
|
||||
gpio_set_af_mode(GPIOA,11,GPIO_AF_OTG1_FS) ; // OTG_FS_DM
|
||||
gpio_set_af_mode(GPIOA,12,GPIO_AF_OTG1_FS) ; // OTG_FS_DP
|
||||
gpio_set_mode(BOARD_USB_DM_PIN,GPIO_MODE_AF | GPIO_OTYPE_PP | GPIO_OSPEED_100MHZ);
|
||||
gpio_set_mode(BOARD_USB_DP_PIN,GPIO_MODE_AF | GPIO_OTYPE_PP | GPIO_OSPEED_100MHZ);
|
||||
gpio_set_af_mode(BOARD_USB_DM_PIN,GPIO_AF_OTG1_FS) ; // OTG_FS_DM
|
||||
gpio_set_af_mode(BOARD_USB_DP_PIN,GPIO_AF_OTG1_FS) ; // OTG_FS_DP
|
||||
#ifdef USB_OTG_FS_SOF_OUTPUT_ENABLED
|
||||
gpio_set_mode(GPIOA, 8,GPIO_MODE_AF | GPIO_OTYPE_PP | GPIO_OSPEED_100MHZ);
|
||||
gpio_set_af_mode(GPIOA, 8,GPIO_AF_OTG1_FS) ; // OTG_FS_SOF
|
||||
|
@ -122,10 +122,10 @@ void USB_OTG_BSP_DeInit(USB_OTG_CORE_HANDLE *pdev)
|
|||
{
|
||||
// ala42
|
||||
#define GPIO_AF0 ((uint8_t)0) /* OTG_FS Alternate Function mapping */
|
||||
gpio_set_mode(GPIOA,11, GPIO_MODE_INPUT);
|
||||
gpio_set_mode(GPIOA,12, GPIO_MODE_INPUT);
|
||||
gpio_set_af_mode(GPIOA,11,GPIO_AF0) ; // OTG_FS_DM
|
||||
gpio_set_af_mode(GPIOA,12,GPIO_AF0) ; // OTG_FS_DP
|
||||
gpio_set_mode(BOARD_USB_DM_PIN, GPIO_MODE_INPUT);
|
||||
gpio_set_mode(BOARD_USB_DP_PIN, GPIO_MODE_INPUT);
|
||||
gpio_set_af_mode(BOARD_USB_DM_PIN,GPIO_AF0) ; // OTG_FS_DM
|
||||
gpio_set_af_mode(BOARD_USB_DP_PIN,GPIO_AF0) ; // OTG_FS_DP
|
||||
#ifdef USB_OTG_FS_SOF_OUTPUT_ENABLED
|
||||
gpio_set_mode(GPIOA, 8,GPIO_MODE_INPUT);
|
||||
gpio_set_af_mode(GPIOA, 8,GPIO_AF0) ; // OTG_FS_SOF
|
||||
|
|
|
@ -5,23 +5,22 @@
|
|||
#include <gpio.h>
|
||||
#include <rccF4.h>
|
||||
#include <usbd_cdc_vcp.h>
|
||||
#include <boards.h>
|
||||
|
||||
USB_OTG_CORE_HANDLE USB_OTG_dev;
|
||||
|
||||
|
||||
|
||||
void setupUSB (void) {
|
||||
#define USB_DISC_DEV GPIOA
|
||||
#define USB_DISC_PIN 12
|
||||
|
||||
gpio_set_mode(USB_DISC_DEV, USB_DISC_PIN, GPIO_OUTPUT_OD); // ala42
|
||||
void setupUSB (void)
|
||||
{
|
||||
gpio_set_mode(BOARD_USB_DP_PIN, GPIO_OUTPUT_OD); // ala42
|
||||
#ifdef USB_DISC_OD
|
||||
//gpio_set_mode(USB_DISC_DEV, USB_DISC_PIN, GPIO_OUTPUT_OD); // ala42
|
||||
#else
|
||||
//gpio_set_mode(USB_DISC_DEV, USB_DISC_PIN, GPIO_OUTPUT_PP); // ala42 for active pull-up on disconnect pin
|
||||
#endif
|
||||
|
||||
gpio_write_bit(USB_DISC_DEV, USB_DISC_PIN,0); // ala42
|
||||
gpio_clear_pin(BOARD_USB_DP_PIN); // ala42
|
||||
delay_us(200000);
|
||||
|
||||
/* setup the apb1 clock for USB */
|
||||
|
@ -29,7 +28,7 @@ void setupUSB (void) {
|
|||
//pRCC->APB1ENR |= RCC_APB1ENR_USBEN;
|
||||
|
||||
/* initialize the usb application */
|
||||
gpio_write_bit(USB_DISC_DEV, USB_DISC_PIN, 1); // ala42 // presents us to the host
|
||||
gpio_set_pin(BOARD_USB_DP_PIN); // ala42 // presents us to the host
|
||||
USBD_Init(&USB_OTG_dev,
|
||||
USB_OTG_FS_CORE_ID,
|
||||
&USR_desc,
|
||||
|
|
|
@ -128,7 +128,7 @@ void throb(void) {
|
|||
uint32 TOP_CNT = 0x0800;
|
||||
uint32 i = 0;
|
||||
|
||||
gpio_set_mode(ERROR_LED_PORT, ERROR_LED_PIN, GPIO_OUTPUT_PP);
|
||||
gpio_set_mode(ERROR_LED_PIN, GPIO_OUTPUT_PP);
|
||||
/* Error fade. */
|
||||
while (1) {
|
||||
if (CC == TOP_CNT) {
|
||||
|
@ -143,9 +143,9 @@ void throb(void) {
|
|||
}
|
||||
|
||||
if (i < CC) {
|
||||
gpio_write_bit(ERROR_LED_PORT, ERROR_LED_PIN, 1);
|
||||
gpio_set_pin(ERROR_LED_PIN);
|
||||
} else {
|
||||
gpio_write_bit(ERROR_LED_PORT, ERROR_LED_PIN, 0);
|
||||
gpio_clear_pin(ERROR_LED_PIN);
|
||||
}
|
||||
i++;
|
||||
}
|
||||
|
|
|
@ -33,6 +33,8 @@
|
|||
#include "wirish.h"
|
||||
#include "usb.h"
|
||||
|
||||
#ifdef SERIAL_USB
|
||||
|
||||
#define USB_TIMEOUT 50
|
||||
|
||||
USBSerial::USBSerial(void) {
|
||||
|
@ -153,3 +155,5 @@ void USBSerial::disableBlockingTx(void) {
|
|||
}
|
||||
|
||||
USBSerial SerialUSB;
|
||||
|
||||
#endif
|
||||
|
|
|
@ -33,6 +33,8 @@
|
|||
|
||||
#include "Stream.h"
|
||||
|
||||
#ifdef SERIAL_USB
|
||||
|
||||
/**
|
||||
* @brief Virtual serial terminal.
|
||||
*/
|
||||
|
@ -68,3 +70,6 @@ extern USBSerial SerialUSB;
|
|||
|
||||
#endif
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -54,8 +54,8 @@
|
|||
#define HIGH 0x1
|
||||
#define LOW 0x0
|
||||
|
||||
#define true 0x1
|
||||
#define false 0x0
|
||||
//#define true 0x1
|
||||
//#define false 0x0
|
||||
|
||||
|
||||
#define lowByte(w) ((w) & 0xFF)
|
||||
|
|
|
@ -72,7 +72,7 @@ void pinMode(uint8 pin, WiringPinMode mode) {
|
|||
return;
|
||||
}
|
||||
|
||||
gpio_set_mode(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit, outputMode);
|
||||
gpio_set_mode(pin, outputMode);
|
||||
|
||||
if (PIN_MAP[pin].timer_device != NULL) {
|
||||
/* Enable/disable timer channels if we're switching into or
|
||||
|
@ -84,29 +84,32 @@ void pinMode(uint8 pin, WiringPinMode mode) {
|
|||
}
|
||||
|
||||
|
||||
uint32 digitalRead(uint8 pin) {
|
||||
uint32 digitalRead(uint8 pin)
|
||||
{
|
||||
if (pin >= BOARD_NR_GPIO_PINS) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
return gpio_read_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit) ?
|
||||
return gpio_read_pin(pin) ?
|
||||
HIGH : LOW;
|
||||
}
|
||||
|
||||
void digitalWrite(uint8 pin, uint8 val) {
|
||||
void digitalWrite(uint8 pin, uint8 val)
|
||||
{
|
||||
if (pin >= BOARD_NR_GPIO_PINS) {
|
||||
return;
|
||||
}
|
||||
|
||||
gpio_write_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit, val);
|
||||
gpio_write_pin(pin, val);
|
||||
}
|
||||
|
||||
void togglePin(uint8 pin) {
|
||||
void togglePin(uint8 pin)
|
||||
{
|
||||
if (pin >= BOARD_NR_GPIO_PINS) {
|
||||
return;
|
||||
}
|
||||
|
||||
gpio_toggle_bit(PIN_MAP[pin].gpio_device, PIN_MAP[pin].gpio_bit);
|
||||
gpio_toggle_pin(pin);
|
||||
}
|
||||
|
||||
#define BUTTON_DEBOUNCE_DELAY 1
|
||||
|
|
|
@ -30,14 +30,14 @@
|
|||
* @brief Wirish library type definitions.
|
||||
*/
|
||||
|
||||
#include "libmaple_types.h"
|
||||
#include "gpio.h"
|
||||
#include "timer.h"
|
||||
#include "adc.h"
|
||||
|
||||
#ifndef _WIRISH_TYPES_H_
|
||||
#define _WIRISH_TYPES_H_
|
||||
|
||||
#include "libmaple_types.h"
|
||||
#include "gpio_def.h"
|
||||
#include "timer.h"
|
||||
#include "adc.h"
|
||||
|
||||
/**
|
||||
* Invalid stm32_pin_info adc_channel value.
|
||||
* @see stm32_pin_info
|
||||
|
@ -73,6 +73,7 @@ typedef struct stm32_pin_info {
|
|||
} stm32_pin_info;
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Variable attribute, instructs the linker to place the marked
|
||||
* variable in Flash instead of RAM. */
|
||||
|
|
|
@ -64,7 +64,7 @@ compiler.libs.c.flags=-I{build.core.path} -I{build.core.path}/libmaple -I{build.
|
|||
# ---------------------
|
||||
|
||||
## Compile c files
|
||||
recipe.c.o.pattern="{compiler.path}{compiler.c.cmd}" {compiler.c.flags} -mcpu={build.mcu} -DF_CPU={build.f_cpu} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} {compiler.c.extra_flags} {build.extra_flags} {compiler.libs.c.flags} {includes} "{source_file}" -o "{object_file}"
|
||||
recipe.c.o.pattern="{compiler.path}{compiler.c.cmd}" {compiler.c.flags} -mcpu={build.mcu} -DF_CPU={build.f_cpu} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} {compiler.c.extra_flags} {build.extra_flags} {build.cpu_flags} {compiler.libs.c.flags} {includes} "{source_file}" -o "{object_file}"
|
||||
|
||||
## Compile c++ files
|
||||
recipe.cpp.o.pattern="{compiler.path}{compiler.cpp.cmd}" {compiler.cpp.flags} -mcpu={build.mcu} -DF_CPU={build.f_cpu} -DARDUINO={runtime.ide.version} -DARDUINO_{build.board} -DARDUINO_ARCH_{build.arch} {compiler.cpp.extra_flags} {build.extra_flags} {build.cpu_flags} {build.hs_flag} {build.common_flags} {compiler.libs.c.flags} {includes} "{source_file}" -o "{object_file}"
|
||||
|
|
|
@ -124,7 +124,7 @@ PE0,PE1,PE2,PE3,PE4,PE5,PE6,PE7,PE8,PE9,PE10,PE11,PE12,PE13,PE14,PE15,
|
|||
#if 0 // not available on LQFP100 package
|
||||
PF0,PF1,PF2,PF3,PF4,PF5,PF6,PF7,PF8,PF9,PF10,PF11,PF12,PF13,PF14,PF15,
|
||||
PG0,PG1,PG2,PG3,PG4,PG5,PG6,PG7,PG8,PG9,PG10,PG11,PG12,PG13,PG14,PG15
|
||||
#endif
|
||||
#endif // not available on LQFP100 package
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
|
||||
MEMORY
|
||||
{
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue