diff --git a/port/max32665-evkit/.gitignore b/port/max32665-evkit/.gitignore new file mode 100644 index 0000000000..4bd3a5c4b0 --- /dev/null +++ b/port/max32665-evkit/.gitignore @@ -0,0 +1,18 @@ +.swp +.*.sw[op] +*~ +*.o +*.a +*.xml +*.d +*.map +*.elf +build/ +GPATH +GRTAGS +GTAGS +tags +*.txt +*.log +core +example/* \ No newline at end of file diff --git a/port/max32665-evkit/BLE5_ctr_bin/ble5_ctr.elffff b/port/max32665-evkit/BLE5_ctr_bin/ble5_ctr.elffff new file mode 100755 index 0000000000..c7cc0e6230 Binary files /dev/null and b/port/max32665-evkit/BLE5_ctr_bin/ble5_ctr.elffff differ diff --git a/port/max32665-evkit/Makefile b/port/max32665-evkit/Makefile new file mode 100644 index 0000000000..61a73d8d95 --- /dev/null +++ b/port/max32665-evkit/Makefile @@ -0,0 +1,11 @@ +.phony: examples +all: examples + +examples: + scripts/create_examples.py + +clean: + scripts/delete_examples.py + @rm -rf example/Makefile + @echo "Deleting CC2564B Init Script in src folder" + @rm -rf src/cc256x* bluetooth_init* diff --git a/port/max32665-evkit/README.md b/port/max32665-evkit/README.md new file mode 100644 index 0000000000..d3a60b5f71 --- /dev/null +++ b/port/max32665-evkit/README.md @@ -0,0 +1,56 @@ +# BTstack Port for the Maxim MAX32665 EvKit-V1 + +This port uses the [MAX32665/6 ARM Cortex M4F Board](https://www.analog.com/en/design-center/evaluation-hardware-and-software/evaluation-boards-kits/max32666evkit.html). All EvKits come with an external CMSIS-DAP programmer used to flash the boards. + +## Software + +The [Analog Devices MSDK](https://github.com/Analog-Devices-MSDK/msdk) is a free development kit that includes all the necessary drivers for the board's operation. + + +## Toolchain Setup + +Please follow the directions given in the [MSDK README.md](https://github.com/Analog-Devices-MSDK/msdk#readme) + + + + + +## Build + +Ensure that the `MAXIM_PATH` points to the root directory where MSDK installed. +Then, navigate to the port/max32665-evkit folder and run the make command in the terminal to generate example projects in the example folder. + +In each example folder, e.g. port/max323630-fthr/example/spp_and_le_streamer, you can run make again to build an .elf file. The build folder will contain this file, making it conveniently accessible for debugging with Eclipse or GDB. + + +## Flashing MAX32665 +There are two methods to program the board. The easiest is to drag and drop the generated .bin file to the DAPLINK mass storage drive. Once the file is copied, the DAPLINK should program and then run the new firmware. + +Alternatively, OpenOCD can be used to flash and debug the device. A suitable programming script is available in the scripts folder. + +## Usage + +The project is designed to connect over HCI via the H4 transport (UART) to another MAX32 BLE capable device (MAX32665 is BLE capable). + +For the controller, build and flash the BLE5_ctr project found in the MSDK under [Examples/MAX32665/BLE5_ctr](https://github.com/Analog-Devices-MSDK/msdk/tree/main/Examples/MAX32665/BLE5_ctr) to another MAX32665 EV Kit or FTHR. For comvenience, the ELF file can also be found in this directory under BLE5_ctr_bin. + +After this code is flashed onto a secondary board, flash an example onto the primary EVKIT running the BTstack host software. + +To connect the boards, use a jumper wire to link UART3 from one board to the other. UART3 can be found on the EVKIT at JP9 and JP10. After the connection and flashing are complete, reset both boards to start the example. + +The HCI uart can be found and modified in the MSDK under Libraries/Boards/MAX32665/EvKit_V1/Include/board.h +## Debugging + +OpenOCD can be used for both development and debugging. Step-by-step debugging can be achieved with either Eclipse or GDB via OpenOCD. + +## Debug output + +printf messages are redirected to UART0, which can be accessed via the onboard USB to serial converter. + + + +Additional debugging information can be enabled by uncommenting ENABLE_LOG_INFO in the src/btstack_config.h header file and performing a clean rebuild. + + + +Debug output is available on both the host and controller. \ No newline at end of file diff --git a/port/max32665-evkit/scripts/create_examples.py b/port/max32665-evkit/scripts/create_examples.py new file mode 100755 index 0000000000..a6eec10e82 --- /dev/null +++ b/port/max32665-evkit/scripts/create_examples.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python3 +# +# Create project files for all BTstack embedded examples in WICED/apps/btstack + +import os +import re +import shutil +import subprocess +import sys + +# build all template +build_all = ''' +SUBDIRS = \\ +%s + +all: +\techo Building all examples +\tfor dir in $(SUBDIRS); do \\ +\t$(MAKE) -C $$dir || exit 1; \\ +\tdone + +clean: +\techo Cleaning all ports +\tfor dir in $(SUBDIRS); do \\ +\t$(MAKE) -C $$dir clean; \\ +\tdone +''' + +# get script path +script_path = os.path.abspath(os.path.dirname(sys.argv[0])) + '/../' + +# get btstack root +btstack_root = script_path + '../../' + + + +# path to examples +examples_embedded = btstack_root + 'example/' + +# path to generated example projects +projects_path = script_path + "example/" + +# path to template +template_path = script_path + 'template/Makefile' + +print("Creating example projects:") + +# iterate over btstack examples +example_files = os.listdir(examples_embedded) + +examples = [] + +for file in example_files: + if not file.endswith(".c"): + continue + if file in ['panu_demo.c', 'sco_demo_util.c', 'ant_test.c']: + continue + example = file[:-2] + examples.append(example) + + # create folder + project_folder = projects_path + example + "/" + if not os.path.exists(project_folder): + os.makedirs(project_folder) + + # check if .gatt file is present + gatt_path = examples_embedded + example + ".gatt" + gatt_h = "" + if os.path.exists(gatt_path): + gatt_h = example+'.h' + + # create makefile + with open(project_folder + 'Makefile', 'wt') as fout: + with open(template_path, 'rt') as fin: + for line in fin: + if 'PROJECT=spp_and_le_streamer' in line: + fout.write('PROJECT=%s\n' % example) + continue + if 'all: spp_and_le_streamer.h' in line: + if len(gatt_h): + fout.write("all: %s\n" % gatt_h) + continue + fout.write(line) + + print("- %s" % example) + +with open(projects_path+'Makefile', 'wt') as fout: + fout.write(build_all % ' \\\n'.join(examples)) + +print("Projects are ready for compile in example folder. See README for details.") diff --git a/port/max32665-evkit/scripts/delete_examples.py b/port/max32665-evkit/scripts/delete_examples.py new file mode 100755 index 0000000000..6e8e9b5a30 --- /dev/null +++ b/port/max32665-evkit/scripts/delete_examples.py @@ -0,0 +1,31 @@ +#!/usr/bin/env python3 +# +# Delete project files for all BTstack embedded examples in local port/esp32 folder + +import os +import shutil +import sys +import time +import subprocess + +# get script path +script_path = os.path.abspath(os.path.dirname(sys.argv[0])) + +# path to examples +examples_embedded = script_path + "/../../../example/" + +# path to port/esp32 +apps_btstack = "example/" + +print("Deleting examples in local folder") + +# iterate over btstack examples +for file in os.listdir(examples_embedded): + if not file.endswith(".c"): + continue + example = file[:-2] + apps_folder = apps_btstack + example + "/" + if os.path.exists(apps_folder): + shutil.rmtree(apps_folder) + print("- %s" % example) + diff --git a/port/max32665-evkit/src/btstack_config.h b/port/max32665-evkit/src/btstack_config.h new file mode 100644 index 0000000000..5e9bfe67fc --- /dev/null +++ b/port/max32665-evkit/src/btstack_config.h @@ -0,0 +1,62 @@ + +#ifndef BTSTACK_CONFIG_H +#define BTSTACK_CONFIG_H + +#include + +// Port related features +// #define HAVE_BTSTACK_STDIN +#define HAVE_EMBEDDED_TIME_MS +#define HAVE_INIT_SCRIPT + +// BTstack features that can be enabled +#define ENABLE_BLE +#define ENABLE_MESH +#define ENABLE_CLASSIC +#define ENABLE_LE_CENTRAL +#define ENABLE_MICRO_ECC_FOR_LE_SECURE_CONNECTIONS +#define ENABLE_PRINTF_HEXDUMP +#define ENABLE_SCO_OVER_HCI +#define ENABLE_HFP_WIDE_BAND_SPEECH +#define ENABLE_MICRO_ECC_FOR_LE_SECURE_CONNECTIONS +#define ENABLE_L2CAP_LE_CREDIT_BASED_FLOW_CONTROL_MODE +#define ENABLE_LE_PERIPHERAL +#define ENABLE_LE_SECURE_CONNECTIONS +#define ENABLE_LOG_INFO +#define ENABLE_LOG_ERROR +#define ENABLE_PRINTF_HEXDUMP +#define ENABLE_SCO_OVER_HCI + + +// BTstack configuration. buffers, sizes, ... +#define HCI_ACL_PAYLOAD_SIZE 1021 +#define MAX_NR_AVDTP_CONNECTIONS 1 +#define MAX_NR_AVDTP_STREAM_ENDPOINTS 1 +#define MAX_NR_AVRCP_CONNECTIONS 2 +#define MAX_NR_BNEP_CHANNELS 1 +#define MAX_NR_BNEP_SERVICES 1 +#define MAX_NR_BTSTACK_LINK_KEY_DB_MEMORY_ENTRIES 2 +#define MAX_NR_GATT_CLIENTS 1 +#define MAX_NR_HCI_CONNECTIONS 1 +#define MAX_NR_HID_HOST_CONNECTIONS 1 +#define MAX_NR_HIDS_CLIENTS 1 +#define MAX_NR_HFP_CONNECTIONS 1 +#define MAX_NR_L2CAP_CHANNELS 3 +#define MAX_NR_L2CAP_SERVICES 3 +#define MAX_NR_RFCOMM_CHANNELS 1 +#define MAX_NR_RFCOMM_MULTIPLEXERS 1 +#define MAX_NR_RFCOMM_SERVICES 1 +#define MAX_NR_SERVICE_RECORD_ITEMS 4 +#define MAX_NR_SM_LOOKUP_ENTRIES 3 +#define MAX_NR_WHITELIST_ENTRIES 1 + + +#define MAX_NR_MESH_VIRTUAL_ADDRESSES 4 +#define MAX_NR_MESH_NETWORK_KEYS 4 +#define MAX_NR_MESH_TRANSPORT_KEYS 4 + +// Link Key DB and LE Device DB using TLV on top of Flash Sector interface +#define NVM_NUM_DEVICE_DB_ENTRIES 16 +#define NVM_NUM_LINK_KEYS 16 + +#endif diff --git a/port/max32665-evkit/src/btstack_port.c b/port/max32665-evkit/src/btstack_port.c new file mode 100644 index 0000000000..59dfa76308 --- /dev/null +++ b/port/max32665-evkit/src/btstack_port.c @@ -0,0 +1,381 @@ +/* ***************************************************************************** +* Copyright (C) Analog Devices, All rights Reserved. +* +* This software is protected by copyright laws of the United States and +* of foreign countries. This material may also be protected by patent laws +* and technology transfer regulations of the United States and of foreign +* countries. This software is furnished under a license agreement and/or a +* nondisclosure agreement and may only be used or reproduced in accordance +* with the terms of those agreements. Dissemination of this information to +* any party or parties not specified in the license agreement and/or +* nondisclosure agreement is expressly prohibited. +* +* The above copyright notice and this permission notice shall be included +* in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS +* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF +* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. +* IN NO EVENT SHALL MAXIM INTEGRATED BE LIABLE FOR ANY CLAIM, DAMAGES +* OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, +* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR +* OTHER DEALINGS IN THE SOFTWARE. +* +* Except as contained in this notice, the name of Maxim Integrated +* Products, Inc. shall not be used except as stated in the Maxim Integrated +* Products, Inc. Branding Policy. +* +* The mere transfer of this software does not imply any licenses +* of trade secrets, proprietary technology, copyrights, patents, +* trademarks, maskwork rights, or any other form of intellectual +* property whatsoever. Analog Devices, Inc. retains all +* ownership rights. +**************************************************************************** */ + + +#include +#include + +// MXC +#include "lp.h" +#include "uart.h" +#include "board.h" +#include "mxc_device.h" +#include "uart_regs.h" +#include "uart.h" +#include "led.h" + +// BTstack Core +#include "btstack_debug.h" +#include "btstack.h" +#include "btstack_config.h" +#include "btstack_run_loop_embedded.h" +#include "btstack_tlv_none.h" + +#include "hci_dump_embedded_stdout.h" +#include "hci_transport.h" +#include "hci_transport_h4.h" + +// BTstack HALs +#include "hal_tick.h" +#include "hal_stdin.h" +// hal_led.h implementation +#include "hal_led.h" +#include "btstack_port.h" + +#include "hal_flash_bank_mxc.h" +#include "btstack_tlv.h" +#include "btstack_tlv_flash_bank.h" +#include "btstack_link_key_db_tlv.h" +#include "le_device_db_tlv.h" + +#define HAL_FLASH_BANK_SIZE 0x2000 +#define HAL_FLASH_BANK_1_ADDR 0x1007FFFF +#define HAL_FLASH_BANK_0_ADDR 0x10080000 + +static uint32_t baud_rate; +volatile uint8_t transaction_complete = 1; +volatile mxc_uart_req_t hci_tx_request; +volatile mxc_uart_req_t hci_rx_request; + +// rx state +static int bytes_to_read = 0; +static uint8_t *rx_buffer_ptr = 0; + +// tx state +static int bytes_to_write = 0; +static uint8_t *tx_buffer_ptr = 0; + +static void dummy_handler(void){}; +static void (*rx_done_handler)(void) = dummy_handler; +static void (*tx_done_handler)(void) = dummy_handler; +void DMA_Handler(void) +{ + MXC_DMA_Handler(MXC_DMA0); +} +void UART0_IRQHandler(void) +{ + LED_On(0); + MXC_UART_AsyncHandler(MXC_UART0); + LED_Off(0); +} +void UART1_IRQHandler(void) +{ + LED_On(0); + MXC_UART_AsyncHandler(MXC_UART1); + LED_Off(0); +} +void UART2_IRQHandler(void) +{ + LED_On(0); + MXC_UART_AsyncHandler(MXC_UART2); + LED_Off(0); +} + +void hal_cpu_disable_irqs(void) +{ + __disable_irq(); +} + +void hal_cpu_enable_irqs(void) +{ + __enable_irq(); +} +void hal_cpu_enable_irqs_and_sleep(void) +{ + __enable_irq(); + /* TODO: Add sleep mode */ +} +static void send_handler() +{ + + transaction_complete = 1; + (*tx_done_handler)(); +} + +void hal_uart_dma_send_block(const uint8_t *buffer, uint16_t len) +{ + + hci_tx_request.callback = send_handler; + hci_tx_request.uart = MXC_UART_GET_UART(HCI_UART); + hci_tx_request.txData = buffer; + hci_tx_request.txLen = len; + hci_tx_request.rxData = NULL; + hci_tx_request.rxLen = 0; + + int ret = MXC_UART_TransactionAsync(&hci_tx_request); + + if (ret != E_NO_ERROR) + { + printf("Failed to start transaction"); + } + +} +static void read_handler(mxc_uart_req_t *req, int error) +{ + transaction_complete = 1; + (*rx_done_handler)(); +} +void hal_uart_dma_receive_block(uint8_t *buffer, uint16_t len) +{ + + + rx_buffer_ptr = buffer; + bytes_to_read = len; + +} + +void hal_uart_init(void) +{ + uint8_t uartNum; + mxc_uart_regs_t *uart; + uint32_t irqn; + int result; + + uartNum = HCI_UART; + uart = MXC_UART_GET_UART(uartNum); + irqn = MXC_UART_GET_IRQ(uartNum); + + result = MXC_UART_Init(uart, baud_rate, HCI_UART_MAP); + + MXC_UART_SetDataSize(uart, 8); + MXC_UART_SetStopBits(uart, MXC_UART_STOP_1); + MXC_UART_SetParity(uart, MXC_UART_PARITY_DISABLE); + + NVIC_EnableIRQ(irqn); + /* Set the interrupt priority lower than the default */ + NVIC_SetPriority(irqn, 1); + + return result; +} + +void hal_btstack_run_loop_execute_once(void) +{ + int rx_avail; + int num_rx_bytes; + int tx_avail; + int rx_bytes; + int tx_bytes; + int ret; + + while (bytes_to_read) + { + rx_avail = MXC_UART_GetRXFIFOAvailable(MXC_UART_GET_UART(HCI_UART)); + if (!rx_avail) + break; + + if (bytes_to_read > rx_avail) + num_rx_bytes = rx_avail; + else + num_rx_bytes = bytes_to_read; + + ret = MXC_UART_Read(MXC_UART_GET_UART(HCI_UART), rx_buffer_ptr, &num_rx_bytes); + if (ret < 0) + break; + + rx_buffer_ptr += num_rx_bytes; + bytes_to_read -= num_rx_bytes; + + if (bytes_to_read < 0) + { + bytes_to_read = 0; + } + + if (bytes_to_read == 0) + { + (*rx_done_handler)(); + } + } + + + btstack_run_loop_embedded_execute_once(); +} + +int hal_uart_dma_set_baud(uint32_t baud) +{ + baud_rate = baud; + printf("BAUD RATE IS = %d \n", baud); + hal_uart_init(); + return baud_rate; +} + +void hal_uart_dma_init(void) +{ + bytes_to_write = 0; + bytes_to_read = 0; + hal_uart_dma_set_baud(115200); +} + +void hal_uart_dma_set_block_received(void (*block_handler)(void)) +{ + rx_done_handler = block_handler; +} + +void hal_uart_dma_set_block_sent(void (*block_handler)(void)) +{ + + tx_done_handler = block_handler; +} + +void hal_uart_dma_set_csr_irq_handler(void (*csr_irq_handler)(void)) +{ +} + +void hal_uart_dma_set_sleep(uint8_t sleep) +{ +} + +void init_slow_clock(void) +{ +} + +int bt_comm_init() +{ + int error = 0; + int cnt = 0; + + hal_tick_init(); + hal_delay_us(1); + + return 0; +} + +static hci_transport_config_uart_t config = { + HCI_TRANSPORT_CONFIG_UART, + 115200, + 0, + 1, // flow control + "max32665", +}; + +void hal_led_off(void) +{ + LED_Off(0); +} + +void hal_led_on(void) +{ + LED_On(0); +} + +void hal_led_toggle(void) +{ + LED_Toggle(0); +} + +// hal_stdin.h +static uint8_t stdin_buffer[1]; +static void (*stdin_handler)(char c); + +static volatile mxc_uart_req_t uart_byte_request; + +static void uart_rx_handler(mxc_uart_req_t *request, int error) +{ + if (stdin_handler) + { + (*stdin_handler)(stdin_buffer[0]); + } + MXC_UART_ReadAsync(MXC_UART_GET_UART(CONSOLE_UART), &uart_byte_request); +} + +void hal_stdin_setup(void (*handler)(char c)) +{ + // set handler + stdin_handler = handler; + + /* set input handler */ + + uart_byte_request.uart = MXC_UART_GET_UART(CONSOLE_UART); + uart_byte_request.rxData = stdin_buffer; + uart_byte_request.txData = NULL; + uart_byte_request.rxLen = sizeof(uint8_t); + uart_byte_request.txLen = 0; + + MXC_UART_Transaction(&uart_byte_request); +} + +static hal_flash_bank_mxc_t hal_flash_bank_context; +static btstack_tlv_flash_bank_t btstack_tlv_flash_bank_context; + +/******************************************************************************/ +int bluetooth_main(void) +{ + LED_Off(1); + LED_On(1); + LED_Off(0); + + + + bt_comm_init(); + /* BT Stack Initialization */ + btstack_memory_init(); + btstack_run_loop_init(btstack_run_loop_embedded_get_instance()); + gap_discoverable_control(1); + + // enable packet logger + hci_dump_init(hci_dump_embedded_stdout_get_instance()); + + + + /* Init HCI */ + const hci_transport_t *transport = hci_transport_h4_instance(btstack_uart_block_embedded_instance()); + + + + // setup TLV Flash Bank implementation + + + const btstack_tlv_t *btstack_tlv_impl = btstack_tlv_none_init_instance(); + // setup global tlv + btstack_tlv_set_instance(btstack_tlv_impl, NULL); + + // setup LE Device DB using TLV + le_device_db_tlv_configure(btstack_tlv_impl, NULL); + + // hci_set_chipset(btstack_chipset_cc256x_instance()); + hci_init(transport, &config); + + // go + btstack_main(0, (void *)NULL); + return 0; +} diff --git a/port/max32665-evkit/src/btstack_port.h b/port/max32665-evkit/src/btstack_port.h new file mode 100644 index 0000000000..26a3c48ea4 --- /dev/null +++ b/port/max32665-evkit/src/btstack_port.h @@ -0,0 +1,49 @@ +/******************************************************************************* +* Copyright (C) Analog Devices, Inc., All Rights Reserved. +* Author: Ismail H. Kose +* +* Permission is hereby granted, free of charge, to any person obtaining a +* copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation +* the rights to use, copy, modify, merge, publish, distribute, sublicense, +* and/or sell copies of the Software, and to permit persons to whom the +* Software is furnished to do so, subject to the following conditions: +* +* The above copyright notice and this permission notice shall be included +* in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS +* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF +* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. +* IN NO EVENT SHALL MAXIM INTEGRATED BE LIABLE FOR ANY CLAIM, DAMAGES +* OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, +* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR +* OTHER DEALINGS IN THE SOFTWARE. +* +* Except as contained in this notice, the name of Maxim Integrated +* Products, Inc. shall not be used except as stated in the Maxim Integrated +* Products, Inc. Branding Policy. +* +* The mere transfer of this software does not imply any licenses +* of trade secrets, proprietary technology, copyrights, patents, +* trademarks, maskwork rights, or any other form of intellectual +* property whatsoever. Analog Devices, Inc. retains all +* ownership rights. +******************************************************************************* +*/ + +#ifndef BTSTACK_MAX32630FTHR_PORT_H +#define BTSTACK_MAX32630FTHR_PORT_H + +#if defined __cplusplus +extern "C" { +#endif + +int bluetooth_main(void); +void hal_btstack_run_loop_execute_once(void); +int btstack_main(int argc, const char * argv[]); + +#if defined __cplusplus +} +#endif +#endif /* BTSTACK_MAX32630FTHR_PORT_H */ diff --git a/port/max32665-evkit/src/hal_flash_bank_mxc.c b/port/max32665-evkit/src/hal_flash_bank_mxc.c new file mode 100644 index 0000000000..702cb99ef3 --- /dev/null +++ b/port/max32665-evkit/src/hal_flash_bank_mxc.c @@ -0,0 +1,107 @@ +/* + * Copyright (C) 2017 BlueKitchen GmbH + * + * 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. Neither the name of the copyright holders nor the names of + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY BLUEKITCHEN GMBH AND CONTRIBUTORS + * ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL BLUEKITCHEN + * GMBH OR CONTRIBUTORS 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. + * + */ + +/* + * hal_flash_bank_mxc.c + * + * HAL abstraction for Flash memory that can be written anywhere + * after being erased implemented with memory + */ + +#include +#include // memcpy + +#include "hal_flash_bank_mxc.h" + +#include "flc.h" // Maxim Flash Controller + +static uint32_t hal_flash_bank_mxc_get_size(void * context){ + hal_flash_bank_mxc_t * self = (hal_flash_bank_mxc_t *) context; + return self->sector_size; +} + +static uint32_t hal_flash_bank_mxc_get_alignment(void * context){ + (void)(context); + return 4; +} + +static void hal_flash_bank_mxc_erase(void * context, int bank){ + hal_flash_bank_mxc_t * self = (hal_flash_bank_mxc_t *) context; + + if (bank > 1) return; + + // Erase page + MXC_FLC_PageErase(self->banks[bank]); +} + +static void hal_flash_bank_mxc_read(void * context, int bank, uint32_t offset, uint8_t * buffer, uint32_t size){ + hal_flash_bank_mxc_t * self = (hal_flash_bank_mxc_t *) context; + + + + + if (bank > 1) return; + if (offset > self->sector_size) return; + if ((offset + size) > self->sector_size) return; + + memcpy(buffer, ((uint8_t *) self->banks[bank]) + offset, size); +} + +static void hal_flash_bank_mxc_write(void * context, int bank, uint32_t offset, const uint8_t * data, uint32_t size){ + hal_flash_bank_mxc_t * self = (hal_flash_bank_mxc_t *) context; + + if (bank > 1) return; + if (offset > self->sector_size) return; + if ((offset + size) > self->sector_size) return; + + MXC_FLC_Write(self->banks[bank] + offset, data, size); +} + +static const hal_flash_bank_t hal_flash_bank_mxc_impl = { + /* uint32_t (*get_size)() */ &hal_flash_bank_mxc_get_size, + /* uint32_t (*get_alignment)(..); */ &hal_flash_bank_mxc_get_alignment, + /* void (*erase)(..); */ &hal_flash_bank_mxc_erase, + /* void (*read)(..); */ &hal_flash_bank_mxc_read, + /* void (*write)(..); */ &hal_flash_bank_mxc_write, +}; + +const hal_flash_bank_t * hal_flash_bank_mxc_init_instance(hal_flash_bank_mxc_t * context, uint32_t sector_size, + uintptr_t bank_0_addr, uintptr_t bank_1_addr){ + context->sector_size = sector_size; + context->banks[0] = bank_0_addr; + context->banks[1] = bank_1_addr; + + // prepare FLC + MXC_FLC_Init(); + + return &hal_flash_bank_mxc_impl; +} + diff --git a/port/max32665-evkit/src/hal_flash_bank_mxc.h b/port/max32665-evkit/src/hal_flash_bank_mxc.h new file mode 100644 index 0000000000..8687673ee8 --- /dev/null +++ b/port/max32665-evkit/src/hal_flash_bank_mxc.h @@ -0,0 +1,69 @@ +/* + * Copyright (C) 2017 BlueKitchen GmbH + * + * 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. Neither the name of the copyright holders nor the names of + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY BLUEKITCHEN GMBH AND CONTRIBUTORS + * ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL BLUEKITCHEN + * GMBH OR CONTRIBUTORS 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. + * + */ + +/* + * hal_flash_sector_maxim.h + * + * HAL abstraction for Flash memory that can be written anywhere + * after being erased implemented with memory + */ + +#ifndef __HAL_FLASH_BANK_MAXIM_H +#define __HAL_FLASH_BANK_MAXIM_H + +#include +#include "hal_flash_bank.h" + +#if defined __cplusplus +extern "C" { +#endif + +typedef struct { + uint32_t sector_size; + uintptr_t banks[2]; + +} hal_flash_bank_mxc_t; + +/** + * Configure MXC HAL Flash Implementation + * + * @param context of hal_flash_bank_mxc_t + * @param sector_size + * @param bank_0_addr + * @param bank_1_addr + * @return + */ +const hal_flash_bank_t * hal_flash_bank_mxc_init_instance(hal_flash_bank_mxc_t * context, uint32_t sector_size, uintptr_t bank_0_addr, uintptr_t bank_1_addr); + +#if defined __cplusplus +} +#endif +#endif diff --git a/port/max32665-evkit/src/hal_tick.c b/port/max32665-evkit/src/hal_tick.c new file mode 100644 index 0000000000..353140f779 --- /dev/null +++ b/port/max32665-evkit/src/hal_tick.c @@ -0,0 +1,159 @@ +/******************************************************************************* + * Copyright (C) Analog Devices, Inc., All Rights Reserved. + * Author: Ismail H. Kose + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS + * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL MAXIM INTEGRATED BE LIABLE FOR ANY CLAIM, DAMAGES + * OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, + * ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR + * OTHER DEALINGS IN THE SOFTWARE. + * + * Except as contained in this notice, the name of Maxim Integrated + * Products, Inc. shall not be used except as stated in the Maxim Integrated + * Products, Inc. Branding Policy. + * + * The mere transfer of this software does not imply any licenses + * of trade secrets, proprietary technology, copyrights, patents, + * trademarks, maskwork rights, or any other form of intellectual + * property whatsoever. Analog Devices, Inc. retains all + * ownership rights. + ******************************************************************************* + */ + +#include +#include +#include "max32665.h" +#include "core_cm4.h" +#include "mxc_delay.h" +#include "mxc_errors.h" +#include "tmr_regs.h" +#include "board.h" +#include "rtc.h" + +/***** Definitions *****/ +#define USE_RTC_SYSTEM_CLK 0 +#define SYSTICK_PERIOD_EXT_CLK 32768 + +/* Trigger interrupt every second */ +static const uint32_t sysTicks = SYSTICK_PERIOD_EXT_CLK; +static volatile uint32_t sys_tick_sec = 0; +/* ************************************************************************** */ +int MXC_SYS_SysTick_Config(uint32_t ticks, int clk_src) +{ + if (ticks == 0) + return E_BAD_PARAM; + + /* If SystemClock, call default CMSIS config and return */ + if (clk_src) + { + return SysTick_Config(ticks); + } + else + { /* External clock source requested. Enable RTC clock in run mode*/ + MXC_RTC_Init(0, 0); + MXC_RTC_Start(); + + /* Disable SysTick Timer */ + SysTick->CTRL = 0; + /* Check reload value for valid */ + if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) + { + /* Reload value impossible */ + return E_BAD_PARAM; + } + /* set reload register */ + SysTick->LOAD = ticks - 1; + + /* set Priority for Systick Interrupt */ + NVIC_SetPriority(SysTick_IRQn, (1 << __NVIC_PRIO_BITS) - 1); + + /* Load the SysTick Counter Value */ + SysTick->VAL = 0; + + /* Enable SysTick IRQ and SysTick Timer leaving clock source as external */ + SysTick->CTRL = SysTick_CTRL_TICKINT_Msk | SysTick_CTRL_ENABLE_Msk; + + /* Function successful */ + return E_NO_ERROR; + } +} +uint32_t MXC_SYS_SysTick_GetFreq(void) +{ + /* Determine is using internal (SystemCoreClock) or external (32768) clock */ + return SYSTICK_PERIOD_EXT_CLK; +} + +int32_t hal_tick_init(void) +{ + uint32_t ret; + ret = MXC_SYS_SysTick_Config(sysTicks, USE_RTC_SYSTEM_CLK); + printf("SysTick Clock = %d Hz\n", MXC_SYS_SysTick_GetFreq()); + if (ret != E_NO_ERROR) + { + printf("ERROR: Ticks is not valid"); + } + + return ret; +} + +void SysTick_Handler(void) +{ + sys_tick_sec++; +} + +uint64_t hal_get_tick(void) +{ + uint32_t usec_tick; + uint64_t tick_sec; + uint32_t systick_val = SysTick->VAL; + uint32_t _sys_tick_sec = sys_tick_sec; + uint32_t sys_freq = MXC_SYS_SysTick_GetFreq(); + + usec_tick = ((uint64_t)(sysTicks - systick_val) * 1000000) / sys_freq; + if (systick_val == 0) // to protect time overflow + _sys_tick_sec -= 1; + tick_sec = _sys_tick_sec * 1000000 + usec_tick; + return tick_sec; +} + +void hal_delay_ms(unsigned int ms) +{ + MXC_Delay(1000 * ms); +} + +void hal_delay_us(unsigned int us) +{ + MXC_Delay(us); +} + +uint32_t hal_get_time_ms(void) +{ + uint32_t usec_tick; + uint64_t tick_sec; + uint32_t systick_val = SysTick->VAL; + uint32_t _sys_tick_sec = sys_tick_sec; + uint32_t sys_freq = MXC_SYS_SysTick_GetFreq(); + + usec_tick = ((uint64_t)(sysTicks - systick_val) * 1000) / sys_freq; + if (systick_val == 0) // to protect time overflow + _sys_tick_sec -= 1; + tick_sec = _sys_tick_sec * 1000 + usec_tick; + return tick_sec; +} + +uint32_t hal_time_ms(void) +{ + return hal_get_time_ms(); +} diff --git a/port/max32665-evkit/src/hal_tick.h b/port/max32665-evkit/src/hal_tick.h new file mode 100644 index 0000000000..1a386c0e44 --- /dev/null +++ b/port/max32665-evkit/src/hal_tick.h @@ -0,0 +1,44 @@ +/******************************************************************************* +* Copyright (C) 2016 Maxim Integrated Products, Inc., All Rights Reserved. +* Author: Ismail H. Kose +* +* Permission is hereby granted, free of charge, to any person obtaining a +* copy of this software and associated documentation files (the "Software"), +* to deal in the Software without restriction, including without limitation +* the rights to use, copy, modify, merge, publish, distribute, sublicense, +* and/or sell copies of the Software, and to permit persons to whom the +* Software is furnished to do so, subject to the following conditions: +* +* The above copyright notice and this permission notice shall be included +* in all copies or substantial portions of the Software. +* +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS +* OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF +* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. +* IN NO EVENT SHALL MAXIM INTEGRATED BE LIABLE FOR ANY CLAIM, DAMAGES +* OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, +* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR +* OTHER DEALINGS IN THE SOFTWARE. +* +* Except as contained in this notice, the name of Maxim Integrated +* Products, Inc. shall not be used except as stated in the Maxim Integrated +* Products, Inc. Branding Policy. +* +* The mere transfer of this software does not imply any licenses +* of trade secrets, proprietary technology, copyrights, patents, +* trademarks, maskwork rights, or any other form of intellectual +* property whatsoever. Maxim Integrated Products, Inc. retains all +* ownership rights. +******************************************************************************* +*/ + +#ifndef MAX32630FTHR_HAL_TICK_H_ +#define MAX32630FTHR_HAL_TICK_H_ +#include +void hal_delay_us(unsigned int us); +void hal_delay_ms(unsigned int ms); +uint32_t hal_time_ms(void); +uint32_t hal_get_time_ms(void); +uint64_t hal_get_tick(void); +int32_t hal_tick_init(void); +#endif /* MAX32630FTHR_HAL_TICK_H_ */ diff --git a/port/max32665-evkit/src/main.c b/port/max32665-evkit/src/main.c new file mode 100644 index 0000000000..d6d60c5f3d --- /dev/null +++ b/port/max32665-evkit/src/main.c @@ -0,0 +1,59 @@ +/******************************************************************************* + * Copyright (C) Analog Devices, Inc., All Rights Reserved. + * Author: Ismail H. Kose + * + * Permission is hereby granted, free of charge, to any person obtaining a + * copy of this software and associated documentation files (the "Software"), + * to deal in the Software without restriction, including without limitation + * the rights to use, copy, modify, merge, publish, distribute, sublicense, + * and/or sell copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included + * in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS + * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + * IN NO EVENT SHALL MAXIM INTEGRATED BE LIABLE FOR ANY CLAIM, DAMAGES + * OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, + * ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR + * OTHER DEALINGS IN THE SOFTWARE. + * + * Except as contained in this notice, the name of Maxim Integrated + * Products, Inc. shall not be used except as stated in the Maxim Integrated + * Products, Inc. Branding Policy. + * + * The mere transfer of this software does not imply any licenses + * of trade secrets, proprietary technology, copyrights, patents, + * trademarks, maskwork rights, or any other form of intellectual + * property whatsoever. Analog Devices, Inc. retains all + * ownership rights. + + * + ******************************************************************************/ + +/***** Includes *****/ +#include +#include +#include "led.h" + +#include "btstack_port.h" + +/***** Definitions *****/ + +/***** Globals *****/ + +/***** Functions *****/ + +// ***************************************************************************** +int main(void) +{ + printf("max32665 btstack example\n"); + bluetooth_main(); + + while (1) + { + hal_btstack_run_loop_execute_once(); + } +} diff --git a/port/max32665-evkit/template/Makefile b/port/max32665-evkit/template/Makefile new file mode 100644 index 0000000000..30566f7933 --- /dev/null +++ b/port/max32665-evkit/template/Makefile @@ -0,0 +1,360 @@ +################################################################################ + # Copyright (C) 2016 Maxim Integrated Products, Inc., All Rights Reserved. + # Ismail H. Kose + # Permission is hereby granted, free of charge, to any person obtaining a + # copy of this software and associated documentation files (the "Software"), + # to deal in the Software without restriction, including without limitation + # the rights to use, copy, modify, merge, publish, distribute, sublicense, + # and/or sell copies of the Software, and to permit persons to whom the + # Software is furnished to do so, subject to the following conditions: + # + # The above copyright notice and this permission notice shall be included + # in all copies or substantial portions of the Software. + # + # THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS + # OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + # MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + # IN NO EVENT SHALL MAXIM INTEGRATED BE LIABLE FOR ANY CLAIM, DAMAGES + # OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, + # ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR + # OTHER DEALINGS IN THE SOFTWARE. + # + # Except as contained in this notice, the name of Maxim Integrated + # Products, Inc. shall not be used except as stated in the Maxim Integrated + # Products, Inc. Branding Policy. + # + # The mere transfer of this software does not imply any licenses + # of trade secrets, proprietary technology, copyrights, patents, + # trademarks, maskwork rights, or any other form of intellectual + # property whatsoever. Maxim Integrated Products, Inc. retains all + # ownership rights. + # + # $Date: 2016-03-23 13:28:53 -0700 (Wed, 23 Mar 2016) $ + # $Revision: 22067 $ + # + ############################################################################### + +# Maxim ARM Toolchain and Libraries +# https://www.maximintegrated.com/en/products/digital/microcontrollers/MAX32630.html + +# This is the name of the build output file +PROJECT=spp_and_le_streamer + +# Specify the target processor +TARGET=MAX32665 +PROJ_CFLAGS+=-DRO_FREQ=96000000 +PROJ_CFLAGS+=-g3 -ggdb -DDEBUG +CPPFLAGS+=-g3 -ggdb -DDEBUG + +# Create Target name variables +TARGET_UC:=$(shell echo $(TARGET) | tr a-z A-Z) +TARGET_LC:=$(shell echo $(TARGET) | tr A-Z a-z) + +CC2564B = bluetooth_init_cc2564B_1.8_BT_Spec_4.1.o + +# Select 'GCC' or 'IAR' compiler +COMPILER=GCC + +ifeq "$(MAXIM_PATH)" "" +LIBS_DIR=/$(subst \,/,$(subst :,,$(HOME))/Maxim//Libraries/) +$(warning "MAXIM_PATH need to be set. Please run setenv bash file in the Maxim Toolchain directory.") +else +LIBS_DIR=/$(subst \,/,$(subst :,,$(MAXIM_PATH))/Libraries/) +endif + +CMSIS_ROOT=$(LIBS_DIR)/CMSIS + +# Where to find source files for this test +VPATH= . ../../src + +# Where to find header files for this test +IPATH= . ../../src + +BOARD_DIR=$(LIBS_DIR)/Boards + +IPATH += ../../board/ +VPATH += ../../board/ +IPATH += $(LIBS_DIR)MiscDrivers/LED + +IPATH += $(LIBS_DIR)MiscDrivers/ExtMemory +IPATH += $(LIBS_DIR)MiscDrivers/PushButton +IPATH += $(LIBS_DIR)MiscDrivers/LED +IPATH += $(LIBS_DIR)MiscDrivers/Display + +IPATH += $(LIBS_DIR)PeriphDrivers/Include/$(TARGET_UC)/ +IPATH += $(LIBS_DIR)PeriphDrivers/Source/SYS/ +IPATH += $(LIBS_DIR)PeriphDrivers/Source/GPIO/ + + + +IPATH += $(LIBS_DIR)Boards/$(TARGET_UC)/EvKit_V1/Include +VPATH += $(LIBS_DIR)Boards/$(TARGET_UC)/EvKit_V1/Source +VPATH += $(LIBS_DIR)MiscDrivers/ + +VPATH += $(LIBS_DIR)MiscDrivers/ExtMemory +VPATH += $(LIBS_DIR)MiscDrivers/PushButton +VPATH += $(LIBS_DIR)MiscDrivers/LED +VPATH += $(LIBS_DIR)MiscDrivers/Display +VPATH += $(LIBS_DIR)PeriphDrivers/Source/SYS/ +VPATH += $(LIBS_DIR)PeriphDrivers/Source/ADC + + + + +VPATH += $(SOURCE_DIR)/CORE1/ +VPATH += $(SOURCE_DIR)/DMA/ +VPATH += $(SOURCE_DIR)/FLC/ +VPATH += $(SOURCE_DIR)/GPIO/ +VPATH += $(SOURCE_DIR)/HTMR/ +VPATH += $(SOURCE_DIR)/I2C/ +VPATH += $(SOURCE_DIR)/ICC/ +VPATH += $(SOURCE_DIR)/OWM/ +VPATH += $(SOURCE_DIR)/PT/ +VPATH += $(SOURCE_DIR)/RPU/ +VPATH += $(SOURCE_DIR)/RTC/ +VPATH += $(SOURCE_DIR)/SDHC/ +VPATH += $(SOURCE_DIR)/SEMA/ +VPATH += $(SOURCE_DIR)/SIMO/ +VPATH += $(SOURCE_DIR)/SPI/ +VPATH += $(SOURCE_DIR)/SPIXF/ +VPATH += $(SOURCE_DIR)/SPIXR/ +VPATH += $(SOURCE_DIR)/SRCC/ +VPATH += $(SOURCE_DIR)/TMR/ +VPATH += $(SOURCE_DIR)/TPU/ +VPATH += $(SOURCE_DIR)/TRNG/ +VPATH += $(SOURCE_DIR)/UART/ + +VPATH += $(SOURCE_DIR)/LP/ +VPATH += $(SOURCE_DIR)/WDT/ +VPATH += $(SOURCE_DIR)/WUT/ + + + +# Source files for this test (add path to VPATH below) +SRCS = main.c +SRCS += hal_tick.c +SRCS += btstack_port.c +SRCS += ${PROJECT}.c +SRCS += board.c +SRCS += stdio.c +SRCS += led.c +SRCS += pb.c +SRCS += mxc_assert.c +SRCS += btstack_tlv_none.c +SRCS += mx25.c + +# Where to find BSP source files +VPATH += $(BOARD_DIR)/Source + +# Where to find BSP header files +IPATH += $(BOARD_DIR)/Include + +# Include the peripheral driver +PERIPH_DRIVER_DIR=$(LIBS_DIR)/PeriphDrivers +include $(PERIPH_DRIVER_DIR)/$(TARGET_LC)_files.mk +IPATH+=$(PERIPH_DRIVER_INCLUDE_DIR) +SRCS += $(PERIPH_DRIVER_C_FILES) + +# BTstack +BTSTACK_ROOT ?= ../../../.. +VPATH += $(BTSTACK_ROOT)/chipset/cc256x +VPATH += $(BTSTACK_ROOT)/example +VPATH += $(BTSTACK_ROOT)/port/pegasus-max3263x +VPATH += $(BTSTACK_ROOT)/src +VPATH += $(BTSTACK_ROOT)/src/ble +VPATH += $(BTSTACK_ROOT)/src/classic +VPATH += ${BTSTACK_ROOT}/3rd-party/bluedroid/decoder/srce +VPATH += ${BTSTACK_ROOT}/3rd-party/bluedroid/encoder/srce +VPATH += ${BTSTACK_ROOT}/3rd-party/hxcmod-player +VPATH += ${BTSTACK_ROOT}/3rd-party/hxcmod-player/mods +VPATH += ${BTSTACK_ROOT}/3rd-party/lwip/core/src/core/ +VPATH += ${BTSTACK_ROOT}/3rd-party/lwip/core/src/core/ipv4 +VPATH += ${BTSTACK_ROOT}/3rd-party/lwip/core/src/core/ipv6 +VPATH += ${BTSTACK_ROOT}/3rd-party/lwip/core/src/netif +VPATH += ${BTSTACK_ROOT}/3rd-party/lwip/core/src/apps/http +VPATH += ${BTSTACK_ROOT}/3rd-party/lwip/dhcp-server +VPATH += ${BTSTACK_ROOT}/3rd-party/md5 +VPATH += ${BTSTACK_ROOT}/3rd-party/yxml +VPATH += ${BTSTACK_ROOT}/3rd-party/micro-ecc +VPATH += ${BTSTACK_ROOT}/platform/embedded +VPATH += ${BTSTACK_ROOT}/platform/lwip +VPATH += ${BTSTACK_ROOT}/platform/lwip/port +VPATH += ${BTSTACK_ROOT}/src/ble/gatt-service/ + +PROJ_CFLAGS += \ + -I$(BTSTACK_ROOT)/src \ + -I$(BTSTACK_ROOT)/src/ble \ + -I$(BTSTACK_ROOT)/src/classic \ + -I$(BTSTACK_ROOT)/chipset/cc256x \ + -I$(BTSTACK_ROOT)/platform/embedded \ + -I$(BTSTACK_ROOT)/platform/lwip \ + -I$(BTSTACK_ROOT)/platform/lwip/port \ + -I${BTSTACK_ROOT}/port/pegasus-max3263x \ + -I${BTSTACK_ROOT}/src/ble/gatt-service/ \ + -I${BTSTACK_ROOT}/example \ + -I${BTSTACK_ROOT}/3rd-party/bluedroid/decoder/include \ + -I${BTSTACK_ROOT}/3rd-party/bluedroid/encoder/include \ + -I${BTSTACK_ROOT}/3rd-party/md5 \ + -I${BTSTACK_ROOT}/3rd-party/yxml \ + -I${BTSTACK_ROOT}/3rd-party/micro-ecc \ + -I${BTSTACK_ROOT}/3rd-party/hxcmod-player \ + -I${BTSTACK_ROOT}/3rd-party/lwip/core/src/include \ + -I${BTSTACK_ROOT}/3rd-party/lwip/dhcp-server \ + -DEXT_FLASH_MX25 \ + +CORE = \ + ad_parser.o \ + btstack_linked_list.o \ + btstack_memory.o \ + btstack_memory_pool.o \ + btstack_run_loop.o \ + btstack_util.o \ + l2cap.o \ + l2cap_signaling.o \ + btstack_run_loop_embedded.o \ + hci_transport_h4.o + +COMMON = \ + btstack_chipset_cc256x.o \ + hci.o \ + hci_cmd.o \ + hci_dump.o \ + hci_dump_embedded_stdout.o \ + btstack_uart_block_embedded.o \ + hal_flash_bank_mxc.o \ + btstack_audio.o \ + btstack_tlv.o \ + btstack_tlv_flash_bank.o \ + btstack_stdin_embedded.o \ + btstack_crypto.o \ + +CLASSIC = \ + btstack_link_key_db_tlv.o \ + hid_device.o \ + hid_host.o \ + rfcomm.o \ + sdp_util.o \ + spp_server.o \ + sdp_server.o \ + sdp_client.o \ + sdp_client_rfcomm.o + +BLE = \ + att_db.o \ + att_server.o \ + le_device_db_tlv.o \ + att_dispatch.o \ + sm.o \ + ancs_client.o \ + gatt_client.o \ + hid_device.o \ + battery_service_server.o \ + uECC.o \ + +AVDTP += \ + avdtp_util.c \ + avdtp.c \ + avdtp_initiator.c \ + avdtp_acceptor.c \ + avdtp_source.c \ + avdtp_sink.c \ + a2dp.c \ + a2dp_source.c \ + a2dp_sink.c \ + btstack_ring_buffer.c \ + btstack_resample.c \ + avrcp.c \ + avrcp_target.c \ + avrcp_controller.c \ + +HFP_OBJ += sco_demo_util.o btstack_ring_buffer.o hfp.o hfp_gsm_model.o hfp_ag.o hfp_hf.o + +# List of files for Bluedroid SBC codec +include ${BTSTACK_ROOT}/3rd-party/bluedroid/decoder/Makefile.inc +include ${BTSTACK_ROOT}/3rd-party/bluedroid/encoder/Makefile.inc + +SBC_DECODER += \ + btstack_sbc_plc.c \ + btstack_sbc_decoder_bluedroid.c \ + +SBC_ENCODER += \ + btstack_sbc_encoder_bluedroid.c \ + hfp_msbc.c \ + hfp_codec.c + +HXCMOD_PLAYER = \ + hxcmod.c \ + nao-deceased_by_disease.c \ + +LWIP_CORE_SRC = init.c mem.c memp.c netif.c udp.c ip.c pbuf.c inet_chksum.c def.c tcp.c tcp_in.c tcp_out.c timeouts.c sys_arch.c +LWIP_IPV4_SRC = acd.c dhcp.c etharp.c icmp.c ip4.c ip4_frag.c ip4_addr.c +LWIP_NETIF_SRC = ethernet.c +LWIP_HTTPD = altcp_proxyconnect.c fs.c httpd.c +LWIP_SRC = ${LWIP_CORE_SRC} ${LWIP_IPV4_SRC} ${LWIP_NETIF_SRC} ${LWIP_HTTPD} dhserver.c + +ADDITION = + +CORE_OBJ = $(CORE:.c=.o) +COMMON_OBJ = $(COMMON:.c=.o) +BLE_OBJ = $(BLE:.c=.o) +CLASSIC_OBJ = $(CLASSIC:.c=.o) +AVDTP_OBJ = $(AVDTP:.c=.o) +SBC_DECODER_OBJ = $(SBC_DECODER:.c=.o) +SBC_ENCODER_OBJ = $(SBC_ENCODER:.c=.o) +CVSD_PLC_OBJ = $(CVSD_PLC:.c=.o) +HXCMOD_PLAYER_OBJ = $(HXCMOD_PLAYER:.c=.o) + +SRCS += $(CORE_OBJ) +SRCS += $(COMMON_OBJ) +SRCS += $(BLE_OBJ) +SRCS += $(CLASSIC_OBJ) +SRCS += $(AVDTP_OBJ) +SRCS += $(SBC_DECODER_OBJ) +SRCS += $(SBC_ENCODER_OBJ) +SRCS += $(CVSD_PLC_OBJ) +SRCS += $(HXCMOD_PLAYER_OBJ) +SRCS += $(HFP_OBJ) +SRCS += hsp_hs.o hsp_ag.o +SRCS += obex_parser.o goep_client.o pbap_client.o md5.o yxml.o +SRCS += pan.c bnep.c bnep_lwip.c +SRCS += ${LWIP_SRC} + +# Enable assertion checking for development +PROJ_CFLAGS+=-DMXC_ASSERT_ENABLE + +# Use this variables to specify and alternate tool path +#TOOL_DIR=/opt/gcc-arm-none-eabi-4_8-2013q4/bin + +# Use these variables to add project specific tool options +#PROJ_CFLAGS+=--specs=nano.specs +#PROJ_LDFLAGS+=--specs=nano.specs + +# Point this variable to a startup file to override the default file +#STARTUPFILE=start.S + +# Point this variable to a linker file to override the default file +# LINKERFILE=$(CMSIS_ROOT)/Device/Maxim/$(TARGET_UC)/Source/GCC/$(TARGET_LC).ld + +%.h: %.gatt + python3 ${BTSTACK_ROOT}/tool/compile_gatt.py $< $@ + +all: spp_and_le_streamer.h + + +################################################################################ +# Include the rules for building for this target. All other makefiles should be +# included before this one. +include $(CMSIS_ROOT)/Device/Maxim/$(TARGET_UC)/Source/$(COMPILER)/$(TARGET_LC).mk + +# fetch and convert init scripts +# use bluetooth_init_cc2564B_1.8_BT_Spec_4.1.c +include ${BTSTACK_ROOT}/chipset/cc256x/Makefile.inc + +rm-compiled-gatt-file: + rm -f spp_and_le_counter.h + +clean: rm-compiled-gatt-file + +# The rule to clean out all the build products. +distclean: clean + $(MAKE) -C ${PERIPH_DRIVER_DIR} clean