diff --git a/.cproject b/.cproject
index 4c9acd0..b0563cb 100755
--- a/.cproject
+++ b/.cproject
@@ -267,6 +267,7 @@
make
+
all
true
true
@@ -274,6 +275,7 @@
make
+
clean
true
true
@@ -281,6 +283,7 @@
make
+
all
true
true
@@ -288,6 +291,7 @@
make
+
all
true
true
@@ -295,6 +299,7 @@
make
+
clean
true
true
@@ -302,6 +307,7 @@
make
+
distclean
true
false
@@ -355,9 +361,16 @@
false
true
+
+ make
+ APP=test BOARD=stm32f4-discovery DEBUG=y
+ build
+ true
+ false
+ true
+
make
-
distclean
true
false
diff --git a/source/Makefile b/source/Makefile
index dacbd36..a0dbca5 100755
--- a/source/Makefile
+++ b/source/Makefile
@@ -73,7 +73,7 @@ clean:
distclean:
-rm -rf $(ROOT_DIR)/release
-install: all
+install: build
$(PRE_PROGRAM)
$(PROGRAM)
diff --git a/source/application/test/main.c b/source/application/test/main.c
index 321c3eb..3f8fa99 100644
--- a/source/application/test/main.c
+++ b/source/application/test/main.c
@@ -27,14 +27,30 @@ void task1(void *arg)
while(1) {
sleep_ms(1000);
gpio_toggle(&led_1);
+ uart_write(&uart_1, "Hello world\r\n", 13);
}
}
+char rx_buf[80];
+void task2(void *arg)
+{
+ while(1) {
+ int i = uart_read(&uart_1, rx_buf, 80);
+ if(i > 0) {
+ uart_write(&uart_1, rx_buf, i);
+ }
+ }
+}
+
+stack_t tc_2_stack[STACK_SIZE];
+struct thread_context tc_2;
int main(void)
{
board_init();
sys_tick_init(&timer_1);
+ uart_open(&uart_1);
thread_create(&tc_1, tc_1_stack, STACK_SIZE, task1, NULL, THREAD_PRIO_LOW);
+ thread_create(&tc_2, tc_2_stack, STACK_SIZE, task2, NULL, THREAD_PRIO_LOW);
schedule_start();
diff --git a/source/firmware/arch/stm32f4xx/board/stm32f4-discovery/bsp_stm32f4-discovery.c b/source/firmware/arch/stm32f4xx/board/stm32f4-discovery/bsp_stm32f4-discovery.c
index 0960cdc..11daeb9 100755
--- a/source/firmware/arch/stm32f4xx/board/stm32f4-discovery/bsp_stm32f4-discovery.c
+++ b/source/firmware/arch/stm32f4xx/board/stm32f4-discovery/bsp_stm32f4-discovery.c
@@ -6,17 +6,17 @@
*/
#include "bsp_stm32f4-discovery.h"
+#if 0
#include "usbd_cdc_vcp.h"
-//-----------------------------------------------------------------------------
volatile int32_t ITM_RxBuffer;
+#endif
-//-----------------------------------------------------------------------------
void board_init(void) {
SystemInit();
NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0);
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4);
SysTick_CLKSourceConfig(RCC_SYSCLKSource_PLLCLK);
- USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb);
+// USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb);
}
diff --git a/source/firmware/arch/stm32f4xx/board/stm32f4-discovery/bsp_stm32f4-discovery.h b/source/firmware/arch/stm32f4xx/board/stm32f4-discovery/bsp_stm32f4-discovery.h
index f158f9b..ce85bb1 100755
--- a/source/firmware/arch/stm32f4xx/board/stm32f4-discovery/bsp_stm32f4-discovery.h
+++ b/source/firmware/arch/stm32f4xx/board/stm32f4-discovery/bsp_stm32f4-discovery.h
@@ -6,6 +6,8 @@
#ifndef BSP_STM32F4_DISCOVERY_H_
#define BSP_STM32F4_DISCOVERY_H_
+#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
+
#include
#include
@@ -14,9 +16,12 @@
#include "ringbuffer.h"
#include "stm32f4xx.h"
#include "stm32f4_gpio.h"
+#include "stm32f4_uart.h"
#include "stm32_sys_tick.h"
+#if 0
#include "usb_vport.h"
+#endif
// SYSTEM TICK
static const enum stm32_sys_tick_time_base stm23_sys_tick_time_base =
@@ -32,7 +37,16 @@ static const struct loki_timer timer_1 = {
&timer_fp
};
+#if 0
// USB
+static const stm32_usb_vport_t stm32_usb_vport;
+static const struct uart uart_0 = {
+ &stm32_usb_vport,
+ &usb_vport_fp,
+ &console_buffer
+};
+#endif
+
static char console_linear_buffer[80];
static struct ringbuffer console_buffer = {
console_linear_buffer,
@@ -41,11 +55,46 @@ static struct ringbuffer console_buffer = {
sizeof(console_linear_buffer),
0
};
-static const stm32_usb_vport_t stm32_usb_vport;
-static const struct uart uart_0 = {
- &stm32_usb_vport,
- &usb_vport_fp,
- &console_buffer
+static const GPIO_InitTypeDef stm32f4_discovery_uart1_gpio = {
+ GPIO_Pin_6 | GPIO_Pin_7,
+ GPIO_Mode_AF,
+ GPIO_Speed_50MHz,
+ GPIO_OType_PP,
+ GPIO_PuPd_UP
+};
+
+static const USART_InitTypeDef stm32f4_discovery_uart1_usart_init = {
+ 115200,
+ USART_WordLength_8b,
+ USART_StopBits_1,
+ USART_Parity_No,
+ USART_Mode_Tx | USART_Mode_Rx,
+ USART_HardwareFlowControl_None,
+};
+
+static const NVIC_InitTypeDef stm32f4_discovery_uart1_nvic_init = {
+ USART1_IRQn,
+ 0,
+ 0,
+ ENABLE,
+};
+
+static const struct stm32f4_uart stm32f4_uart1 = {
+ &stm32f4_discovery_uart1_gpio,
+ GPIOB,
+ GPIO_PinSource7,
+ GPIO_PinSource6,
+ &stm32f4_discovery_uart1_usart_init,
+ USART1,
+ USART_IT_RXNE /* | USART_IT_TXE*/,
+ &stm32f4_discovery_uart1_nvic_init,
+
+};
+
+static const struct uart uart_1 = {
+ &stm32f4_uart1,
+ &stm32f4_uart_fp,
+ &console_buffer,
};
// STATUS LED
diff --git a/source/firmware/arch/stm32f4xx/driver/driver.mk b/source/firmware/arch/stm32f4xx/driver/driver.mk
index 52667a8..e8167d7 100755
--- a/source/firmware/arch/stm32f4xx/driver/driver.mk
+++ b/source/firmware/arch/stm32f4xx/driver/driver.mk
@@ -1,4 +1,5 @@
include firmware/arch/stm32f4xx/driver/gpio/gpio.mk
include firmware/arch/stm32f4xx/driver/timer/timer.mk
-include firmware/arch/stm32f4xx/driver/usb/usb.mk
-include firmware/arch/stm32f4xx/driver/usb_vport/usb_vport.mk
+include firmware/arch/stm32f4xx/driver/uart/uart.mk
+#include firmware/arch/stm32f4xx/driver/usb/usb.mk
+#include firmware/arch/stm32f4xx/driver/usb_vport/usb_vport.mk
diff --git a/source/firmware/arch/stm32f4xx/driver/uart/stm32f4_uart.c b/source/firmware/arch/stm32f4xx/driver/uart/stm32f4_uart.c
new file mode 100644
index 0000000..a5165db
--- /dev/null
+++ b/source/firmware/arch/stm32f4xx/driver/uart/stm32f4_uart.c
@@ -0,0 +1,102 @@
+/*
+ * stm32f4_uart.c
+ *
+ * Created on: Jul 24, 2016
+ * Author: tkl
+ */
+
+#include
+#include
+
+#include "stm32f4xx.h"
+#include "stm32f4xx_isr.h"
+#include "stm32f4_uart.h"
+
+struct stm32f4_uart_obj {
+ const void *callback; //!< Interrupt callback.
+ const void *parameter; //!< argument for the callback.
+};
+
+static volatile struct stm32f4_uart_obj uart1_obj;
+
+int stm32f4_uart_open(const void *this)
+{
+ struct stm32f4_uart *uart = (struct stm32f4_uart *)this;
+ uint8_t gpio_af = 0;
+ uint32_t rcc_apb_uart = 0, rcc_apb_gpio = 0;
+
+ if(uart->usart_port == USART1) {
+ gpio_af = GPIO_AF_USART1;
+ rcc_apb_uart = RCC_APB2Periph_USART1;
+ }
+ if(uart->gpio_port == GPIOA) {
+ rcc_apb_gpio = RCC_AHB1Periph_GPIOA;
+ }
+ else if(uart->gpio_port == GPIOB) {
+ rcc_apb_gpio = RCC_AHB1Periph_GPIOB;
+ }
+
+ RCC_APB2PeriphClockCmd(rcc_apb_uart, ENABLE);
+ RCC_AHB1PeriphClockCmd(rcc_apb_gpio, ENABLE);
+
+ GPIO_Init(uart->gpio_port, (GPIO_InitTypeDef *)uart->gpio_init);
+
+ GPIO_PinAFConfig(uart->gpio_port, uart->pin_src_rx, gpio_af);
+ GPIO_PinAFConfig(uart->gpio_port, uart->pin_src_tx, gpio_af);
+
+ USART_Init(uart->usart_port, (USART_InitTypeDef *)uart->usart_init);
+ USART_ITConfig(uart->usart_port, uart->usart_it_select, ENABLE);
+ NVIC_Init((NVIC_InitTypeDef *)uart->nvic_init);
+ USART_Cmd(uart->usart_port, ENABLE);
+ return (0);
+}
+
+int stm32f4_uart_close(const void *this)
+{
+ struct stm32f4_uart *uart = (struct stm32f4_uart *)this;
+ USART_Cmd(uart->usart_port, DISABLE);
+ return (0);
+}
+
+int stm32f4_uart_read(const void *this, char *buffer, int len)
+{
+ struct stm32f4_uart *uart = (struct stm32f4_uart *)this;
+ *buffer = uart->usart_port->DR;
+ return (1);
+}
+
+int stm32f4_uart_write(const void *this, const char *buffer, int len)
+{
+ struct stm32f4_uart *uart = (struct stm32f4_uart *)this;
+ int i;
+ for(i = 0; i < len; i++) {
+ // wait until data register is empty
+ while(!(uart->usart_port->SR & 0x00000040));
+ USART_SendData(uart->usart_port, buffer[i]);
+ }
+ return (i);
+}
+
+int stm32f4_uart_set_cb(const void *this, const void *callback, const void *param)
+{
+ struct stm32f4_uart *uart = (struct stm32f4_uart *)this;
+ if(uart->usart_port == USART1) {
+ uart1_obj.callback = callback;
+ uart1_obj.parameter = param;
+ }
+ return (0);
+}
+
+// this is the interrupt request handler (IRQ) for ALL USART1 interrupts
+void USART1_IRQHandler(void)
+{
+ enter_isr();
+ // check if the USART1 receive interrupt flag was set
+ if(USART_GetITStatus(USART1, USART_IT_RXNE)) {
+ if(uart1_obj.callback) {
+ void (*cb)(const void *) = uart1_obj.callback;
+ cb(uart1_obj.parameter);
+ }
+ }
+ exit_isr();
+}
diff --git a/source/firmware/arch/stm32f4xx/driver/uart/stm32f4_uart.h b/source/firmware/arch/stm32f4xx/driver/uart/stm32f4_uart.h
new file mode 100644
index 0000000..3dd611d
--- /dev/null
+++ b/source/firmware/arch/stm32f4xx/driver/uart/stm32f4_uart.h
@@ -0,0 +1,64 @@
+/*
+ * stm32_uart.h
+ *
+ * Created on: Jul 24, 2016
+ * Author: tkl
+ */
+
+#ifndef SOURCE_FIRMWARE_ARCH_STM32F4XX_DRIVER_UART_STM32_UART_H_
+#define SOURCE_FIRMWARE_ARCH_STM32F4XX_DRIVER_UART_STM32_UART_H_
+
+#include "uart.h"
+
+//! \brief Stm32f4 uart device.
+struct stm32f4_uart {
+ const GPIO_InitTypeDef *gpio_init;
+ GPIO_TypeDef *gpio_port;
+ uint8_t pin_src_rx;
+ uint8_t pin_src_tx;
+ const USART_InitTypeDef *usart_init;
+ USART_TypeDef *usart_port;
+ uint16_t usart_it_select;
+ const NVIC_InitTypeDef *nvic_init;
+};
+
+//! \brief Open an uart device.
+//! \param this The uart to open.
+//! \retval -1 in error case.
+int stm32f4_uart_open(const void *this);
+
+//! \brief Close an uart device.
+//! \param this The uart to close.
+//! \retval -1 in error case.
+int stm32f4_uart_close(const void *this);
+
+//! \brief Read from an uart device.
+//! \param this The uart to read from.
+//! \param buffer The buffer to read to.
+//! \param len The length of the buffer.
+//! \retval -1 in error case, otherwise number of read characters.
+int stm32f4_uart_read(const void *this, char *buffer, int len);
+
+//! \brief Write to an uart device.
+//! \param this The uart to write to.
+//! \param buffer The buffer to write.
+//! \param len The number of characters to write.
+//! \retval -1 in error case, otherwise number of written characters.
+int stm32f4_uart_write(const void *this, const char *buffer, int len);
+
+//! \brief Set a callback for interrupt handling of the uart.
+//! \param this The uart.
+//! \param callback The callback to execute in interrupt case.
+//! \param param The argument for the callback.
+//! \retval -1 in error case.
+int stm32f4_uart_set_cb(const void *this, const void *callback, const void *param);
+
+static const struct uart_fp stm32f4_uart_fp = {
+ stm32f4_uart_open,
+ stm32f4_uart_close,
+ stm32f4_uart_read,
+ stm32f4_uart_write,
+ stm32f4_uart_set_cb
+};
+
+#endif /* SOURCE_FIRMWARE_ARCH_STM32F4XX_DRIVER_UART_STM32_UART_H_ */
diff --git a/source/firmware/arch/stm32f4xx/driver/uart/uart.mk b/source/firmware/arch/stm32f4xx/driver/uart/uart.mk
new file mode 100755
index 0000000..6f3ec54
--- /dev/null
+++ b/source/firmware/arch/stm32f4xx/driver/uart/uart.mk
@@ -0,0 +1,4 @@
+CHECK_FOLDER += firmware/arch/stm32f4xx/driver/uart
+SUB_FOLDER += firmware/arch/stm32f4xx/driver/uart
+INCLUDES += firmware/arch/stm32f4xx/driver/uart
+DOC_SRC += firmware/arch/stm32f4xx/driver/uart
diff --git a/source/firmware/arch/stm32f4xx/lib/lib.mk b/source/firmware/arch/stm32f4xx/lib/lib.mk
index edf2f17..638ce82 100755
--- a/source/firmware/arch/stm32f4xx/lib/lib.mk
+++ b/source/firmware/arch/stm32f4xx/lib/lib.mk
@@ -2,5 +2,5 @@
#INCLUDES += firmware/arch/stm32f4xx/lib
include firmware/arch/stm32f4xx/lib/stdperiph/stdperiph.mk
-include firmware/arch/stm32f4xx/lib/STM32_USB_Device_Library/dev_lib.mk
-include firmware/arch/stm32f4xx/lib/STM32_USB_OTG_Driver/otg_driver.mk
+#include firmware/arch/stm32f4xx/lib/STM32_USB_Device_Library/dev_lib.mk
+#include firmware/arch/stm32f4xx/lib/STM32_USB_OTG_Driver/otg_driver.mk
diff --git a/source/firmware/arch/stm32f4xx/syscalls.c b/source/firmware/arch/stm32f4xx/syscalls.c
index aa627e4..d511f74 100755
--- a/source/firmware/arch/stm32f4xx/syscalls.c
+++ b/source/firmware/arch/stm32f4xx/syscalls.c
@@ -12,8 +12,9 @@
#include
#include
+#if 0
#include "usbd_cdc_vcp.h"
-
+#endif
#include "board.h"
#undef errno
diff --git a/source/firmware/kernel/driver/uart.c b/source/firmware/kernel/driver/uart.c
index 274e1a5..70266cd 100755
--- a/source/firmware/kernel/driver/uart.c
+++ b/source/firmware/kernel/driver/uart.c
@@ -22,7 +22,7 @@ int uart_open(const struct uart *this)
if(NULL == this)
return (-1);
- int ret = this->fp->set_cb(this, uart_it_callback, this);
+ int ret = this->fp->set_cb(this->arch_dep_device, uart_it_callback, this);
ret |= this->fp->open(this->arch_dep_device);
return (ret);
}