From 58a1b1bbd780fce065cc682a3cd9375e3ada0688 Mon Sep 17 00:00:00 2001 From: Matthias Ringwald Date: Wed, 26 Jul 2017 19:19:33 +0200 Subject: [PATCH] samv71-xplained-atwilc3000: add BTstack files --- port/samv71-xplained-atwilc3000/config.mk | 49 +- port/samv71-xplained-atwilc3000/main.c | 974 ++++++++++++---------- 2 files changed, 586 insertions(+), 437 deletions(-) diff --git a/port/samv71-xplained-atwilc3000/config.mk b/port/samv71-xplained-atwilc3000/config.mk index 687b5c28d..f756319d8 100644 --- a/port/samv71-xplained-atwilc3000/config.mk +++ b/port/samv71-xplained-atwilc3000/config.mk @@ -52,6 +52,7 @@ TARGET_SRAM = getting-started_sram.elf # List of C source files. CSRCS = \ + ../main \ common/services/clock/samv71/sysclk.c \ common/services/serial/usart_serial.c \ common/utils/interrupt/interrupt_sam_nvic.c \ @@ -70,7 +71,6 @@ CSRCS = \ sam/utils/cmsis/samv71/source/templates/gcc/startup_samv71.c \ sam/utils/cmsis/samv71/source/templates/system_samv71.c \ sam/utils/syscalls/gcc/syscalls.c \ - ../main \ # List of assembler source files. ASSRCS = @@ -81,6 +81,7 @@ INC_PATH = \ common/services/clock \ common/services/gpio \ common/services/ioport \ + common/services/delay \ common/services/serial \ common/services/serial/sam_uart \ common/utils \ @@ -96,6 +97,7 @@ INC_PATH = \ sam/drivers/tc \ sam/drivers/uart \ sam/drivers/usart \ + sam/drivers/xdmac \ sam/utils \ sam/utils/cmsis/samv71/include \ sam/utils/cmsis/samv71/source/templates \ @@ -106,6 +108,51 @@ INC_PATH = \ thirdparty/CMSIS/Lib/GCC \ .. +BTSTACK_ROOT = ../../.. +INC_PATH += ${BTSTACK_ROOT}/src/ble +INC_PATH += ${BTSTACK_ROOT}/src/ble/gatt-service +INC_PATH += ${BTSTACK_ROOT}/src/classic +INC_PATH += ${BTSTACK_ROOT}/src +INC_PATH += ${BTSTACK_ROOT}/3rd-party/micro-ecc +INC_PATH += ${BTSTACK_ROOT}/platform/embedded +INC_PATH += ${BTSTACK_ROOT}/chipset/atwilc3000 + +# VPATH += ${BTSTACK_ROOT}/src +# VPATH += ${BTSTACK_ROOT}/src/ble +# VPATH += ${BTSTACK_ROOT}/src/ble/gatt-service +# VPATH += ${BTSTACK_ROOT}/src/classic +# VPATH += ${BTSTACK_ROOT}/platform/embedded +# VPATH += ${BTSTACK_ROOT}/example +# VPATH += ${BTSTACK_ROOT}/3rd-party/micro-ecc + +CSRCS += \ + ${BTSTACK_ROOT}/src/ad_parser.c \ + ${BTSTACK_ROOT}/src/ble/ancs_client.c \ + ${BTSTACK_ROOT}/src/ble/att_db.c \ + ${BTSTACK_ROOT}/src/ble/att_dispatch.c \ + ${BTSTACK_ROOT}/src/ble/att_server.c \ + ${BTSTACK_ROOT}/src/ble/gatt-service/battery_service_server.c \ + ${BTSTACK_ROOT}/src/btstack_linked_list.c \ + ${BTSTACK_ROOT}/src/btstack_memory.c \ + ${BTSTACK_ROOT}/src/btstack_memory_pool.c \ + ${BTSTACK_ROOT}/src/btstack_ring_buffer.c \ + ${BTSTACK_ROOT}/src/btstack_run_loop.c \ + ${BTSTACK_ROOT}/platform/embedded/btstack_run_loop_embedded.c \ + ${BTSTACK_ROOT}/platform/embedded/btstack_uart_block_embedded.c \ + ${BTSTACK_ROOT}/src/btstack_util.c \ + ${BTSTACK_ROOT}/src/ble/gatt-service/device_information_service_server.c \ + ${BTSTACK_ROOT}/src/ble/gatt_client.c \ + ${BTSTACK_ROOT}/src/hci.c \ + ${BTSTACK_ROOT}/src/hci_cmd.c \ + ${BTSTACK_ROOT}/src/hci_dump.c \ + ${BTSTACK_ROOT}/src/hci_transport_h4.c \ + ${BTSTACK_ROOT}/src/l2cap.c \ + ${BTSTACK_ROOT}/src/l2cap_signaling.c \ + ${BTSTACK_ROOT}/src/ble/le_device_db_memory.c \ + ${BTSTACK_ROOT}/src/ble/sm.c \ + ${BTSTACK_ROOT}/3rd-party/micro-ecc/uECC.c \ + ${BTSTACK_ROOT}/example/led_counter.c \ + # Additional search paths for libraries. LIB_PATH = \ thirdparty/CMSIS/Lib/GCC diff --git a/port/samv71-xplained-atwilc3000/main.c b/port/samv71-xplained-atwilc3000/main.c index 9704f5d88..e94b7977b 100644 --- a/port/samv71-xplained-atwilc3000/main.c +++ b/port/samv71-xplained-atwilc3000/main.c @@ -1,436 +1,538 @@ -/** - * \file - * - * \brief Getting Started Application. - * - * Copyright (c) 2011-2016 Atmel Corporation. All rights reserved. - * - * \asf_license_start - * - * \page License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * 3. The name of Atmel may not be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * 4. This software may only be redistributed and used in connection with an - * Atmel microcontroller product. - * - * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED - * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE - * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR - * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS - * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) - * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * \asf_license_stop - * - */ - -/** - * \mainpage Getting Started Application - * - * \section Purpose - * - * The Getting Started example will help new users get familiar with Atmel's - * SAM family of microcontrollers. This basic application shows the startup - * sequence of a chip and how to use its core peripherals. - * - * \section Requirements - * - * This package can be used with SAM evaluation kits. - * - * \section Description - * - * The demonstration program makes the LED(s) on the board blink at a fixed rate. - * This rate is generated by using Time tick timer. The blinking can be stopped - * using the push button. - * - * \section Usage - * - * -# Build the program and download it inside the evaluation board. - * -# On the computer, open and configure a terminal application - * (e.g. HyperTerminal on Microsoft Windows) with these settings: - * - 115200 bauds - * - 8 bits of data - * - No parity - * - 1 stop bit - * - No flow control - * -# Start the application. - * -# The LED(s) should start blinking on the board. In the terminal window, the - * following text should appear (values depend on the board and chip used): - * \code - -- Getting Started Example xxx -- - -- xxxxxx-xx - -- Compiled: xxx xx xxxx xx:xx:xx -- -\endcode - * -# Pressing and release button 1 should make one LED stop & restart - * blinking. - * -# If the button 2 available, pressing button 2 should make the other LED - * stop & restart blinking. - * - */ -/* - * Support and FAQ: visit Atmel Support - */ - -#include "asf.h" -#include "stdio_serial.h" -#include "conf_board.h" -#include "conf_clock.h" - -/** IRQ priority for PIO (The lower the value, the greater the priority) */ -// [main_def_pio_irq_prior] -#define IRQ_PRIOR_PIO 0 -// [main_def_pio_irq_prior] - -/** LED0 blink time, LED1 blink half this time, in ms */ -#define BLINK_PERIOD 1000 - -#define STRING_EOL "\r" -#define STRING_HEADER "-- Getting Started Example --\r\n" \ - "-- "BOARD_NAME" --\r\n" \ - "-- Compiled: "__DATE__" "__TIME__" --"STRING_EOL - -/** LED0 blinking control. */ -// [main_var_led0_control] -volatile bool g_b_led0_active = true; -// [main_var_led0_control] - -#ifdef LED1_GPIO -/** LED1 blinking control. */ -// [main_var_led1_control] -volatile bool g_b_led1_active = true; -// [main_var_led1_control] -#endif - -/** Global g_ul_ms_ticks in milliseconds since start of application */ -// [main_var_ticks] -volatile uint32_t g_ul_ms_ticks = 0; -// [main_var_ticks] - -/// @cond 0 -/**INDENT-OFF**/ -#ifdef __cplusplus -extern "C" { -#endif -/**INDENT-ON**/ -/// @endcond - -/** - * \brief Process Buttons Events - * - * Change active states of LEDs when corresponding button events happened. - */ -static void ProcessButtonEvt(uint8_t uc_button) -{ -// [main_button1_evnt_process] - if (uc_button == 0) { - g_b_led0_active = !g_b_led0_active; - if (!g_b_led0_active) { - ioport_set_pin_level(LED0_GPIO, IOPORT_PIN_LEVEL_HIGH); - } - } -// [main_button1_evnt_process] -#ifdef LED1_GPIO - else { -// [main_button2_evnt_process] - g_b_led1_active = !g_b_led1_active; - - /* Enable LED#2 and TC if they were enabled */ - if (g_b_led1_active) { - ioport_set_pin_level(LED1_GPIO, IOPORT_PIN_LEVEL_LOW); - tc_start(TC0, 0); - } - /* Disable LED#2 and TC if they were disabled */ - else { - ioport_set_pin_level(LED1_GPIO, IOPORT_PIN_LEVEL_HIGH); - tc_stop(TC0, 0); - } -// [main_button2_evnt_process] - } -#endif -} - -/** - * \brief Handler for System Tick interrupt. - * - * Process System Tick Event - * Increments the g_ul_ms_ticks counter. - */ -// [main_systick_handler] -void SysTick_Handler(void) -{ - g_ul_ms_ticks++; -} -// [main_systick_handler] - -/** - * \brief Handler for Button 1 rising edge interrupt. - * - * Handle process led1 status change. - */ -// [main_button1_handler] -static void Button1_Handler(uint32_t id, uint32_t mask) -{ - if (PIN_PUSHBUTTON_1_ID == id && PIN_PUSHBUTTON_1_MASK == mask) { - ProcessButtonEvt(0); - } -} -// [main_button1_handler] - -#ifndef BOARD_NO_PUSHBUTTON_2 -/** - * \brief Handler for Button 2 falling edge interrupt. - * - * Handle process led2 status change. - */ -// [main_button2_handler] -static void Button2_Handler(uint32_t id, uint32_t mask) -{ - if (PIN_PUSHBUTTON_2_ID == id && PIN_PUSHBUTTON_2_MASK == mask) { - ProcessButtonEvt(1); - } -} -// [main_button2_handler] -#endif - -/** - * \brief Configure the Pushbuttons - * - * Configure the PIO as inputs and generate corresponding interrupt when - * pressed or released. - */ -static void configure_buttons(void) -{ -// [main_button1_configure] - /* Configure Pushbutton 1 */ - pmc_enable_periph_clk(PIN_PUSHBUTTON_1_ID); - pio_set_debounce_filter(PIN_PUSHBUTTON_1_PIO, PIN_PUSHBUTTON_1_MASK, 10); - /* Interrupt on rising edge */ - pio_handler_set(PIN_PUSHBUTTON_1_PIO, PIN_PUSHBUTTON_1_ID, - PIN_PUSHBUTTON_1_MASK, PIN_PUSHBUTTON_1_ATTR, Button1_Handler); - NVIC_EnableIRQ((IRQn_Type) PIN_PUSHBUTTON_1_ID); - pio_handler_set_priority(PIN_PUSHBUTTON_1_PIO, - (IRQn_Type) PIN_PUSHBUTTON_1_ID, IRQ_PRIOR_PIO); - pio_enable_interrupt(PIN_PUSHBUTTON_1_PIO, PIN_PUSHBUTTON_1_MASK); -// [main_button1_configure] -#ifndef BOARD_NO_PUSHBUTTON_2 -// [main_button2_configure] - /* Configure Pushbutton 2 */ - pmc_enable_periph_clk(PIN_PUSHBUTTON_2_ID); - pio_set_debounce_filter(PIN_PUSHBUTTON_2_PIO, PIN_PUSHBUTTON_2_MASK, 10); - /* Interrupt on falling edge */ - pio_handler_set(PIN_PUSHBUTTON_2_PIO, PIN_PUSHBUTTON_2_ID, - PIN_PUSHBUTTON_2_MASK, PIN_PUSHBUTTON_2_ATTR, Button2_Handler); - NVIC_EnableIRQ((IRQn_Type) PIN_PUSHBUTTON_2_ID); - pio_handler_set_priority(PIN_PUSHBUTTON_2_PIO, - (IRQn_Type) PIN_PUSHBUTTON_2_ID, IRQ_PRIOR_PIO); - pio_enable_interrupt(PIN_PUSHBUTTON_2_PIO, PIN_PUSHBUTTON_2_MASK); -// [main_button2_configure] -#endif -} - -/** - * Interrupt handler for TC0 interrupt. Toggles the state of LED\#2. - */ -// [main_tc0_handler] -#ifndef BOARD_NO_LED_1 -void TC0_Handler(void) -{ - volatile uint32_t ul_dummy; - - /* Clear status bit to acknowledge interrupt */ - ul_dummy = tc_get_status(TC0, 0); - - /* Avoid compiler warning */ - UNUSED(ul_dummy); - -#ifdef LED1_GPIO - /** Toggle LED state. */ - ioport_toggle_pin_level(LED1_GPIO); -#endif - - printf("2 "); -} -// [main_tc0_handler] - -/** - * Configure Timer Counter 0 to generate an interrupt every 250ms. - */ -// [main_tc_configure] -static void configure_tc(void) -{ - uint32_t ul_div; - uint32_t ul_tcclks; - uint32_t ul_sysclk = sysclk_get_cpu_hz(); - - /* Configure PMC */ - pmc_enable_periph_clk(ID_TC0); -#if SAMG55 - /* Enable PCK output */ - pmc_disable_pck(PMC_PCK_3); - pmc_switch_pck_to_sclk(PMC_PCK_3, PMC_PCK_PRES(0)); - pmc_enable_pck(PMC_PCK_3); -#endif - - /** Configure TC for a 4Hz frequency and trigger on RC compare. */ - tc_find_mck_divisor(4, ul_sysclk, &ul_div, &ul_tcclks, ul_sysclk); - tc_init(TC0, 0, ul_tcclks | TC_CMR_CPCTRG); - tc_write_rc(TC0, 0, (ul_sysclk / ul_div) / 4); - - /* Configure and enable interrupt on RC compare */ - NVIC_EnableIRQ((IRQn_Type) ID_TC0); - tc_enable_interrupt(TC0, 0, TC_IER_CPCS); - -#ifdef LED1_GPIO - /** Start the counter if LED1 is enabled. */ - if (g_b_led1_active) { - tc_start(TC0, 0); - } -#else - tc_start(TC0, 0); -#endif -} -#endif -// [main_tc_configure] - -/** - * Configure UART console. - */ -// [main_console_configure] -static void configure_console(void) -{ - const usart_serial_options_t uart_serial_options = { - .baudrate = CONF_UART_BAUDRATE, -#ifdef CONF_UART_CHAR_LENGTH - .charlength = CONF_UART_CHAR_LENGTH, -#endif - .paritytype = CONF_UART_PARITY, -#ifdef CONF_UART_STOP_BITS - .stopbits = CONF_UART_STOP_BITS, -#endif - }; - - /* Configure console UART. */ - sysclk_enable_peripheral_clock(CONSOLE_UART_ID); - stdio_serial_init(CONF_UART, &uart_serial_options); -} - -// [main_console_configure] - -/** - * \brief Wait for the given number of milliseconds (using the g_ul_ms_ticks - * generated by the SAM's microcontrollers's system tick). - * - * \param ul_dly_ticks Delay to wait for, in milliseconds. - */ -// [main_ms_delay] -static void mdelay(uint32_t ul_dly_ticks) -{ - uint32_t ul_cur_ticks; - - ul_cur_ticks = g_ul_ms_ticks; - while ((g_ul_ms_ticks - ul_cur_ticks) < ul_dly_ticks); -} -// [main_ms_delay] - -/** - * \brief getting-started Application entry point. - * - * \return Unused (ANSI-C compatibility). - */ -// [main] -int main(void) -{ -//! [main_step_sys_init] - /* Initialize the SAM system */ - sysclk_init(); - board_init(); -//! [main_step_sys_init] - -#ifndef BOARD_NO_PUSHBUTTON_2 -#if (SAMV71 || SAMV70 || SAMS70 || SAME70) - if (GPIO_PUSH_BUTTON_2 == PIO_PB12_IDX) { - matrix_set_system_io(matrix_get_system_io() | CCFG_SYSIO_SYSIO12); - } - ioport_set_pin_dir(GPIO_PUSH_BUTTON_2, IOPORT_DIR_INPUT); - ioport_set_pin_mode(GPIO_PUSH_BUTTON_2, GPIO_PUSH_BUTTON_2_FLAGS); - ioport_set_pin_sense_mode(GPIO_PUSH_BUTTON_2, GPIO_PUSH_BUTTON_2_SENSE); -#endif -#endif -//! [main_step_console_init] - /* Initialize the console uart */ - configure_console(); -//! [main_step_console_init] - - /* Output example information */ - puts(STRING_HEADER); - - /* Configure systick for 1 ms */ - puts("Configure system tick to get 1ms tick period.\r"); -//! [main_step_systick_init] - if (SysTick_Config(sysclk_get_cpu_hz() / 1000)) { - puts("-F- Systick configuration error\r"); - while (1); - } -//! [main_step_systick_init] - -#ifndef BOARD_NO_LED_1 - puts("Configure TC.\r"); -//! [main_step_tc_init] - configure_tc(); -//! [main_step_tc_init] -#endif - - puts("Configure buttons with debouncing.\r"); -//! [main_step_btn_init] - configure_buttons(); -//! [main_step_btn_init] - - printf("Press %s to Start/Stop the %s blinking.\r\n", - PUSHBUTTON_1_NAME, LED_0_NAME); - -#ifndef BOARD_NO_PUSHBUTTON_2 - printf("Press %s to Start/Stop the %s blinking.\r\n", - PUSHBUTTON_2_NAME, LED_1_NAME); -#endif - -//! [main_step_loop] - while (1) { - /* Wait for LED to be active */ - while (!g_b_led0_active); - - /* Toggle LED state if active */ - if (g_b_led0_active) { - ioport_toggle_pin_level(LED0_GPIO); - printf("1 "); - } - - /* Wait for 500ms */ - mdelay(300); - } -//! [main_step_loop] -} -// [main] -/// @cond 0 -/**INDENT-OFF**/ -#ifdef __cplusplus -} -#endif -/**INDENT-ON**/ -/// @endcond +/** + * \file + * + * \brief Getting Started Application. + * + * Copyright (c) 2011-2015 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * 4. This software may only be redistributed and used in connection with an + * Atmel microcontroller product. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +/** + * \mainpage Getting Started Application + * + * \section Purpose + * + * BTstack port for SAM MCUs + * + * \section Requirements + * + * This package can be used with SAM evaluation kits. + * + * \section Description + * + * + * \section Usage + * + * -# Build the program and download it inside the evaluation board. + * -# On the computer, open and configure a terminal application + * (e.g. HyperTerminal on Microsoft Windows) with these settings: + * - 115200 bauds + * - 8 bits of data + * - No parity + * - 1 stop bit + * - No flow control + * -# Start the application. + * + */ + +#include "asf.h" +#include "stdio_serial.h" +#include "conf_board.h" +#include "conf_clock.h" + +// BTstack +#include "btstack_run_loop.h" +#include "btstack_run_loop_embedded.h" +#include "btstack_debug.h" +#include "hci.h" +#include "hci_dump.h" +#include "btstack_chipset_atwilc3000.h" +#include "btstack_memory.h" +#include "classic/btstack_link_key_db.h" + +#include "hal_uart_dma.h" +#include "hal_cpu.h" +#include "hal_tick.h" + +extern int btstack_main(int argc, const char * argv[]); + +#define USE_XDMAC_FOR_USART +#define XDMA_CH_UART_TX 0 +#define XDMA_CH_UART_RX 1 + +#define STRING_EOL "\r" +#define STRING_HEADER "-- Getting Started Example --\r\n" \ + "-- "BOARD_NAME" --\r\n" \ + "-- Compiled: "__DATE__" "__TIME__" --"STRING_EOL + +/** All interrupt mask. */ +#define ALL_INTERRUPT_MASK 0xffffffff + +static void dummy_handler(void){} +static void (*tick_handler)(void) = &dummy_handler; + +/** when porting to different setup, please + * disable baudrate change (use 0 instead of 4000000) + * and don't enable eHCILL mode (comment line below) + */ + +// after HCI Reset, use 115200. Then increase baud rate to X. +static hci_transport_config_uart_t hci_transport_config = { + HCI_TRANSPORT_CONFIG_UART, + 115200, + 4000000, // use 0 to skip baud rate change from 115200 to X for debugging purposes + 1, // flow control + NULL, +}; +/// @cond 0 +/**INDENT-OFF**/ +#ifdef __cplusplus +extern "C" { +#endif +/**INDENT-ON**/ +/// @endcond + +/** + * \brief Handler for System Tick interrupt. + */ +void SysTick_Handler(void) +{ + tick_handler(); +} + +/** + * Configure UART console. + */ +// [main_console_configure] +static void configure_console(void) +{ + const usart_serial_options_t uart_serial_options = { + .baudrate = CONF_UART_BAUDRATE, +#ifdef CONF_UART_CHAR_LENGTH + .charlength = CONF_UART_CHAR_LENGTH, +#endif + .paritytype = CONF_UART_PARITY, +#ifdef CONF_UART_STOP_BITS + .stopbits = CONF_UART_STOP_BITS, +#endif + }; + + /* Configure console UART. */ + sysclk_enable_peripheral_clock(CONSOLE_UART_ID); + stdio_serial_init(CONF_UART, &uart_serial_options); +} + +// [main_console_configure] + +/** + * \brief Wait for the given number of milliseconds (ticks + * generated by the SAM's microcontrollers's system tick). + * + * \param ul_dly_ticks Delay to wait for, in milliseconds. + */ +// [main_ms_delay] +static void mdelay(uint32_t delay_in_ms) +{ + // delay_ms(delay_in_ms); + uint32_t time_to_wait = btstack_run_loop_get_time_ms() + delay_in_ms; + while (btstack_run_loop_get_time_ms() < time_to_wait); +} +// [main_ms_delay] + +//////////////////////////////////////////////////////////////////////////////// +// hal_cpu.h implementation +//////////////////////////////////////////////////////////////////////////////// +// hal_led.h implementation +#include "hal_led.h" +void hal_led_off(void); +void hal_led_on(void); + +void hal_led_off(void){ + // gpio_set_pin_low(GPIOA, GPIO_LED2); +} +void hal_led_on(void){ + // gpio_set_pin_high(GPIOA, GPIO_LED2); +} +void hal_led_toggle(void){ + // gpio_toggle_pin(GPIOA, GPIO_LED2); +} + +// hal_cpu.h implementation +#include "hal_cpu.h" + +void hal_cpu_disable_irqs(void){ + //__disable_irq(); +} + +void hal_cpu_enable_irqs(void){ + // __enable_irq(); +} + +void hal_cpu_enable_irqs_and_sleep(void){ + hal_led_off(); + // __enable_irq(); + // __asm__("wfe"); // go to sleep if event flag isn't set. if set, just clear it. IRQs set event flag + + // note: hal_uart_needed_during_sleep can be used to disable peripheral clock if it's not needed for a timer + hal_led_on(); +} + + +#ifndef USE_XDMAC_FOR_USART +// RX state +static volatile uint16_t bytes_to_read = 0; +static volatile uint8_t * rx_buffer_ptr = 0; + +// TX state +static volatile uint16_t bytes_to_write = 0; +static volatile uint8_t * tx_buffer_ptr = 0; +#endif + +// handlers +static void (*rx_done_handler)(void) = dummy_handler; +static void (*tx_done_handler)(void) = dummy_handler; +static void (*cts_irq_handler)(void) = dummy_handler; + +// @note While the Atmel SAM S7x data sheet states +// "The hardware handshaking feature enables an out-of-band flow control by automatic management +// of the pins RTS and CTS.", +// I didn't see RTS going up automatically up, ever. So, at least for RTS, the automatic management +// is just a glorified GPIO pin control feature, which provides no benefit, but irritates a lot + +static void hal_uart_rts_high(void){ + BOARD_USART->US_CR = US_CR_RTSEN; +} +static void hal_uart_rts_low(void){ + BOARD_USART->US_CR = US_CR_RTSDIS; +} + +/** + */ +void hal_uart_dma_init(void) +{ + // configure n_shutdown pin, and reset Bluetooth + ioport_set_pin_dir(N_SHUTDOWN, IOPORT_DIR_OUTPUT); + ioport_set_pin_level(N_SHUTDOWN, IOPORT_PIN_LEVEL_LOW); + mdelay(100); + ioport_set_pin_level(N_SHUTDOWN, IOPORT_PIN_LEVEL_HIGH); + mdelay(500); + + // configure Bluetooth USART + const sam_usart_opt_t bluetooth_settings = { + 115200, + US_MR_CHRL_8_BIT, + US_MR_PAR_NO, + US_MR_NBSTOP_1_BIT, + US_MR_CHMODE_NORMAL, + /* This field is only used in IrDA mode. */ + 0 + }; + + /* Enable the peripheral clock in the PMC. */ + sysclk_enable_peripheral_clock(BOARD_ID_USART); + + /* Configure USART mode. */ + usart_init_hw_handshaking(BOARD_USART, &bluetooth_settings, sysclk_get_peripheral_hz()); + + /* Disable all the interrupts. */ + usart_disable_interrupt(BOARD_USART, ALL_INTERRUPT_MASK); + + // RX not ready yet + // usart_drive_RTS_pin_high(BOARD_USART); + + /* Enable TX & RX function. */ + usart_enable_tx(BOARD_USART); + usart_enable_rx(BOARD_USART); + + /* Configure and enable interrupt of USART. */ + NVIC_EnableIRQ(USART_IRQn); + +#ifdef USE_XDMAC_FOR_USART + + // setup XDMAC + + /* Initialize and enable DMA controller */ + pmc_enable_periph_clk(ID_XDMAC); + + /* Enable XDMA interrupt */ + NVIC_ClearPendingIRQ(XDMAC_IRQn); + NVIC_SetPriority( XDMAC_IRQn ,1); + NVIC_EnableIRQ(XDMAC_IRQn); + + // Setup XDMA Channel for USART TX + xdmac_channel_set_destination_addr(XDMAC, XDMA_CH_UART_TX, (uint32_t)&BOARD_USART->US_THR); + xdmac_channel_set_config(XDMAC, XDMA_CH_UART_TX, + XDMAC_CC_TYPE_PER_TRAN | + XDMAC_CC_DSYNC_MEM2PER | + XDMAC_CC_MEMSET_NORMAL_MODE | + XDMAC_CC_MBSIZE_SINGLE | + XDMAC_CC_DWIDTH_BYTE | + XDMAC_CC_SIF_AHB_IF0 | + XDMAC_CC_DIF_AHB_IF1 | + XDMAC_CC_SAM_INCREMENTED_AM | + XDMAC_CC_DAM_FIXED_AM | + XDMAC_CC_CSIZE_CHK_1 | + XDMAC_CC_PERID(XDAMC_CHANNEL_HWID_USART0_TX) + ); + xdmac_channel_set_descriptor_control(XDMAC, XDMA_CH_UART_TX, 0); + xdmac_channel_set_source_microblock_stride(XDMAC, XDMA_CH_UART_TX, 0); + xdmac_channel_set_destination_microblock_stride(XDMAC, XDMA_CH_UART_TX, 0); + xdmac_channel_set_datastride_mempattern(XDMAC, XDMA_CH_UART_TX, 0); + xdmac_channel_set_block_control(XDMAC, XDMA_CH_UART_TX, 0); + xdmac_enable_interrupt(XDMAC, XDMA_CH_UART_TX); + xdmac_channel_enable_interrupt(XDMAC, XDMA_CH_UART_TX, XDMAC_CIE_BIE); + + // Setup XDMA Channel for USART RX + xdmac_channel_set_source_addr(XDMAC, XDMA_CH_UART_RX, (uint32_t)&BOARD_USART->US_RHR); + xdmac_channel_set_config(XDMAC, XDMA_CH_UART_RX, + XDMAC_CC_TYPE_PER_TRAN | + XDMAC_CC_DSYNC_PER2MEM | + XDMAC_CC_MEMSET_NORMAL_MODE | + XDMAC_CC_MBSIZE_SINGLE | + XDMAC_CC_DWIDTH_BYTE | + XDMAC_CC_SIF_AHB_IF1 | + XDMAC_CC_DIF_AHB_IF0 | + XDMAC_CC_SAM_FIXED_AM | + XDMAC_CC_DAM_INCREMENTED_AM | + XDMAC_CC_CSIZE_CHK_1 | + XDMAC_CC_PERID(XDAMC_CHANNEL_HWID_USART0_RX) + ); + xdmac_channel_set_descriptor_control(XDMAC, XDMA_CH_UART_RX, 0); + xdmac_channel_set_source_microblock_stride(XDMAC, XDMA_CH_UART_RX, 0); + xdmac_channel_set_destination_microblock_stride(XDMAC, XDMA_CH_UART_RX, 0); + xdmac_channel_set_datastride_mempattern(XDMAC, XDMA_CH_UART_RX, 0); + xdmac_channel_set_block_control(XDMAC, XDMA_CH_UART_RX, 0); + xdmac_enable_interrupt(XDMAC, XDMA_CH_UART_RX); + xdmac_channel_enable_interrupt(XDMAC, XDMA_CH_UART_RX, XDMAC_CIE_BIE); +#endif +} + +void hal_uart_dma_set_sleep(uint8_t sleep){ +} + +void hal_uart_dma_set_block_received( void (*the_block_handler)(void)){ + rx_done_handler = the_block_handler; +} + +void hal_uart_dma_set_block_sent( void (*the_block_handler)(void)){ + tx_done_handler = the_block_handler; +} + +void hal_uart_dma_set_csr_irq_handler( void (*the_irq_handler)(void)){ + cts_irq_handler = the_irq_handler; +} + +int hal_uart_dma_set_baud(uint32_t baud){ + /* Disable TX & RX function. */ + usart_disable_tx(BOARD_USART); + usart_disable_rx(BOARD_USART); + uint32_t res = usart_set_async_baudrate(BOARD_USART, baud, sysclk_get_peripheral_hz()); + if (res){ + log_error("hal_uart_dma_set_baud library call failed"); + } + + /* Enable TX & RX function. */ + usart_enable_tx(BOARD_USART); + usart_enable_rx(BOARD_USART); + + log_info("Bump baud rate"); + + return 0; +} + +void hal_uart_dma_send_block(const uint8_t *data, uint16_t size){ + +#ifdef USE_XDMAC_FOR_USART + xdmac_channel_get_interrupt_status( XDMAC, XDMA_CH_UART_TX); + xdmac_channel_set_source_addr(XDMAC, XDMA_CH_UART_TX, (uint32_t)data); + xdmac_channel_set_microblock_control(XDMAC, XDMA_CH_UART_TX, size); + xdmac_channel_enable(XDMAC, XDMA_CH_UART_TX); +#else + tx_buffer_ptr = (uint8_t *) data; + bytes_to_write = size; + usart_enable_interrupt(BOARD_USART, US_IER_TXRDY); +#endif +} + +void hal_uart_dma_receive_block(uint8_t *data, uint16_t size){ + + hal_uart_rts_low(); + +#ifdef USE_XDMAC_FOR_USART + xdmac_channel_get_interrupt_status( XDMAC, XDMA_CH_UART_RX); + xdmac_channel_set_destination_addr(XDMAC, XDMA_CH_UART_RX, (uint32_t)data); + xdmac_channel_set_microblock_control(XDMAC, XDMA_CH_UART_RX, size); + xdmac_channel_enable(XDMAC, XDMA_CH_UART_RX); +#else + rx_buffer_ptr = data; + bytes_to_read = size; + usart_enable_interrupt(BOARD_USART, US_IER_RXRDY); +#endif +} + +#ifdef USE_XDMAC_FOR_USART +void XDMAC_Handler(void) +{ + uint32_t dma_status; + dma_status = xdmac_channel_get_interrupt_status(XDMAC, XDMA_CH_UART_TX); + if (dma_status & XDMAC_CIS_BIS) { + tx_done_handler(); + } + dma_status = xdmac_channel_get_interrupt_status(XDMAC, XDMA_CH_UART_RX); + if (dma_status & XDMAC_CIS_BIS) { + hal_uart_rts_high(); + rx_done_handler(); + } +} +#else +void USART_Handler(void) +{ + uint32_t ul_status; + uint8_t uc_char; + + /* Read USART status. */ + ul_status = usart_get_status(BOARD_USART); + + // handle ready to send + if(ul_status & US_IER_TXRDY) { + if (bytes_to_write){ + // send next byte + usart_write(BOARD_USART, *tx_buffer_ptr); + tx_buffer_ptr++; + bytes_to_write--; + } else { + // done. disable tx ready interrupt to avoid starvation here + usart_disable_interrupt(BOARD_USART, US_IER_TXRDY); + tx_done_handler(); + } + } + + // handle byte available for read + if (ul_status & US_IER_RXRDY) { + uint32_t ch; + usart_read(BOARD_USART, (uint32_t *)&ch); + *rx_buffer_ptr++ = ch; + bytes_to_read--; + if (bytes_to_read == 0){ + // done. disable rx ready interrupt, raise RTS + hal_uart_rts_high(); + usart_disable_interrupt(BOARD_USART, US_IER_RXRDY); + rx_done_handler(); + } + } +} +#endif + +void hal_tick_init() +{ + /* Configure systick for 1 ms */ + puts("Configure system tick to get 1ms tick period.\r"); + if (SysTick_Config(sysclk_get_cpu_hz() / 1000)) { + puts("-F- Systick configuration error\r"); + while (1); + } +} + +void hal_tick_set_handler(void (*handler)(void)){ + if (handler == NULL){ + tick_handler = &dummy_handler; + return; + } + tick_handler = handler; +} + +int hal_tick_get_tick_period_in_ms(void){ + return 1; +} + + +/** + * \brief getting-started Application entry point. + * + * \return Unused (ANSI-C compatibility). + */ +// [main] +int main(void) +{ +//! [main_step_sys_init] + /* Initialize the SAM system */ + sysclk_init(); + board_init(); +//! [main_step_sys_init] + +//! [main_step_console_init] + /* Initialize the console uart */ + configure_console(); +//! [main_step_console_init] + + /* Output example information */ + puts(STRING_HEADER); + + printf("CPU %lu hz, peripheral clock %lu hz\n", sysclk_get_cpu_hz(), sysclk_get_peripheral_hz()); + + // start with BTstack init - especially configure HCI Transport + btstack_memory_init(); + btstack_run_loop_init(btstack_run_loop_embedded_get_instance()); + + // enable full log output while porting + // hci_dump_open(NULL, HCI_DUMP_STDOUT); + + // init HCI + // hci_init(hci_transport_h4_instance(), (void*) &hci_transport_config); + // hci_set_chipset(btstack_chipset_cc256x_instance()); + // hci_set_link_key_db(btstack_link_key_db_memory_instance()); + + // enable eHCILL + // bt_control_cc256x_enable_ehcill(1); + + // hand over to btstack embedded code + btstack_main(0, NULL); + + // go + btstack_run_loop_execute(); + + // compiler happy + while(1); +} +// [main] +/// @cond 0 +/**INDENT-OFF**/ +#ifdef __cplusplus +} +#endif +/**INDENT-ON**/ +/// @endcond