From 5f93f7162f23949050335e9b1518c90a9fc0944d Mon Sep 17 00:00:00 2001 From: Alexander Alashkin <alexander.alashkin@cesanta.com> Date: Mon, 5 Sep 2016 15:57:56 +0100 Subject: [PATCH] Add STM32F4/CC3100 example & Co PUBLISHED_FROM=7f805d89dcb795c9b3ee637ef1dbdcfcf3323469 --- examples/Makefile | 2 +- examples/STM32F4_CC3100/Makefile | 13 + examples/STM32F4_CC3100/Makefile.build | 92 +++ examples/STM32F4_CC3100/README.md | 85 +++ examples/STM32F4_CC3100/main.c | 149 +++++ examples/STM32F4_CC3100/sdk.version | 1 + examples/STM32F4_CC3100/startup_stm32f429xx.s | 561 ++++++++++++++++++ examples/STM32F4_CC3100/startup_utils.c | 29 + examples/STM32F4_CC3100/stm32f429xx.ld | 93 +++ examples/STM32F4_CC3100/stm32f4xx_hal_msp.h | 74 +++ examples/STM32F4_CC3100/user_params.h | 18 + examples/mqtt_broker/mqtt_broker.c | 2 + mongoose.c | 4 +- mongoose.h | 53 ++ 14 files changed, 1172 insertions(+), 4 deletions(-) create mode 100644 examples/STM32F4_CC3100/Makefile create mode 100644 examples/STM32F4_CC3100/Makefile.build create mode 100644 examples/STM32F4_CC3100/README.md create mode 100644 examples/STM32F4_CC3100/main.c create mode 100644 examples/STM32F4_CC3100/sdk.version create mode 100755 examples/STM32F4_CC3100/startup_stm32f429xx.s create mode 100644 examples/STM32F4_CC3100/startup_utils.c create mode 100755 examples/STM32F4_CC3100/stm32f429xx.ld create mode 100644 examples/STM32F4_CC3100/stm32f4xx_hal_msp.h create mode 100644 examples/STM32F4_CC3100/user_params.h diff --git a/examples/Makefile b/examples/Makefile index 5972212a3..e7dd23b94 100644 --- a/examples/Makefile +++ b/examples/Makefile @@ -3,7 +3,7 @@ # `wildcard ./*/` works in both linux and linux/wine, while `wildcard */` enumerates nothing under wine SUBDIRS = $(sort $(dir $(wildcard ./*/))) -SUBDIRS:=$(filter-out ./ ./CC3200/ ./ESP8266_RTOS/ ./MSP432/, $(SUBDIRS)) +SUBDIRS:=$(filter-out ./ ./CC3200/ ./ESP8266_RTOS/ ./MSP432/ ./STM32F4_CC3100/, $(SUBDIRS)) ifeq ($(OS), Windows_NT) SUBDIRS:=$(filter-out ./load_balancer/ ./netcat/ ./raspberry_pi_mjpeg_led/ ./captive_dns_server/, $(SUBDIRS)) diff --git a/examples/STM32F4_CC3100/Makefile b/examples/STM32F4_CC3100/Makefile new file mode 100644 index 000000000..77a6ca9e8 --- /dev/null +++ b/examples/STM32F4_CC3100/Makefile @@ -0,0 +1,13 @@ +SDK ?= $(shell cat sdk.version) +SRC_DIR ?= $(realpath ../../..) + +.PHONY: all clean + +MAKEFLAGS += w + +all clean: + docker run --rm -i -v $(SRC_DIR):/src $(SDK) \ + /bin/bash -c "\ + make -C /src/mongoose mongoose.c mongoose.h && \ + make -C /src/mongoose/examples/STM32F4_CC3100 -f Makefile.build $@ -$(MAKEFLAGS) \ + " diff --git a/examples/STM32F4_CC3100/Makefile.build b/examples/STM32F4_CC3100/Makefile.build new file mode 100644 index 000000000..ca4cceba8 --- /dev/null +++ b/examples/STM32F4_CC3100/Makefile.build @@ -0,0 +1,92 @@ +.PHONY: all clean + +CC3100_DRV_SRCS = driver.c device.c nonos.c socket.c netapp.c wlan.c + +CC3100_PLATFORM_SRCS = spi.c board.c cli_uart.c stm32f4xx_it.c system_stm32f4xx.c stm32f4xx_hal_msp.c + +STM32F4_SRCS = stm32f4xx_hal_spi.c stm32f4xx_hal_gpio.c stm32f4xx_hal_cortex.c\ + stm32f4xx_hal.c stm32f4xx_hal_rcc.c stm32f4xx_hal_dma.c \ + stm32f4xx_hal_pwr_ex.c stm32f4_discovery.c stm32f4xx_hal_i2c.c \ + stm32f4xx_hal_uart.c stm32f4xx_hal_tim.c \ + stm32f4xx_hal_tim_ex.c stm32f4xx_hal_rtc_ex.c stm32f4xx_hal_rtc.c + +SRCS = main.c mongoose.c startup_utils.c ${CC3100_DRV_SRCS} ${CC3100_PLATFORM_SRCS} ${STM32F4_SRCS} + +REPO_ROOT=./../../../ +CC3100_SDKROOT=/opt/CC3100SDK_1.2.0/cc3100-sdk +STM32CUBEF4_ROOT=/opt/STM32CubeF4 +STM32CUBEF4_DRV_PATH=${STM32CUBEF4_ROOT}/Drivers + +CC = arm-none-eabi-gcc +OBJCOPY = arm-none-eabi-objcopy + +FP_FLAGS = -mfloat-abi=hard -mfpu=fpv4-sp-d16 +ARCH_FLAGS = -mthumb -mcpu=cortex-m4 + +BUILD_DIR=.build +OUT_DIR=out +PROJECT=example +BOARD=STM32F429xx +STARTUP_SCRIPT=startup_stm32f429xx.s + +INCDIRS = $(addprefix -I,$(IPATH)) + +OBJS = $(addprefix $(BUILD_DIR)/,$(patsubst %.c,%.o,$(SRCS)) $(patsubst %.s,%.o,$(STARTUP_SCRIPT))) + +VPATH = ${CC3100_SDKROOT}/simplelink/source\ + ${CC3100_SDKROOT}/platform/stm32discovery\ + ${STM32CUBEF4_ROOT}/Drivers/STM32F4xx_HAL_Driver/Src\ + ${STM32CUBEF4_ROOT}/Drivers/BSP/STM32F4-Discovery\ + ${REPO_ROOT}/mongoose + +# CC3100 SDK and STM32 SDK include headers w/out path, just like +# #include "simplelink.h". As result, we have to add all required directories +# into IPATH + +IPATH = . \ + ${CC3100_SDKROOT}/simplelink/include\ + ${CC3100_SDKROOT}/platform/stm32discovery\ + ${STM32CUBEF4_DRV_PATH}/BSP/STM32F4-Discovery\ + ${STM32CUBEF4_DRV_PATH}/STM32F4xx_HAL_Driver/Inc\ + ${STM32CUBEF4_DRV_PATH}/CMSIS/Include\ + ${STM32CUBEF4_DRV_PATH}/CMSIS/Device/ST/STM32F4xx/Include + +LDFLAGS = --static -nostartfiles +LDLIBS = -Wl,--start-group -lc -lgcc -lnosys -Wl,--end-group +LDSCRIPT = stm32f429xx.ld + +INCDIRS = $(addprefix -I,$(IPATH)) + +CFLAGS = ${FP_FLAGS} ${ARCH_FLAGS} ${INCDIRS}\ + -D${BOARD} -DEXT_LIB_REGISTERED_GENERAL_EVENTS \ + -DSL_FULL\ + -DCS_PLATFORM=6\ + -D__STM32F407xx_H\ + -DMG_SIMPLELINK_NO_OSI \ + -g -fno-common -ffunction-sections -fdata-sections \ + +ELF = ${BUILD_DIR}/${PROJECT}.elf +BIN = ${OUT_DIR}/${PROJECT}.bin + +all: ${BUILD_DIR} ${OUT_DIR} ${OBJS} ${ELF} ${BIN} + +${BUILD_DIR}: + mkdir -p $@ + +${OUT_DIR}: + mkdir -p $@ + +$(BUILD_DIR)/%.o: %.c + $(CC) ${CFLAGS} $^ -c -o $@ + +$(BUILD_DIR)/%.o: %.s + $(CC) ${CFLAGS} $^ -c -o $@ + +${ELF}: ${OBJS} + $(CC) ${ARCH_FLAGS} ${FP_FLAGS} $(LDFLAGS) $(OBJS) $(LDLIBS) -T$(LDSCRIPT) -o $@ + +${BIN}: ${ELF} + $(OBJCOPY) -Obinary $^ $@ + +clean: + rm -rf ${BUILD_DIR} ${OUT_DIR} diff --git a/examples/STM32F4_CC3100/README.md b/examples/STM32F4_CC3100/README.md new file mode 100644 index 000000000..afff81ea5 --- /dev/null +++ b/examples/STM32F4_CC3100/README.md @@ -0,0 +1,85 @@ +# STM32F4 example project + +This example shows how to use mongoose on STM32 boards. +To run it you will need: +- [STM32F429-Discovery](http://www.st.com/content/st_com/en/products/evaluation-tools/product-evaluation-tools/mcu-eval-tools/stm32-mcu-eval-tools/stm32-mcu-discovery-kits/32f429idiscovery.html) dev board +- [CC3100](http://www.ti.com/product/CC3100) WiFi network processor + +## Wiring scheme + +By default, example uses SPI4 for communication with CC3100 and UART1 for +the debug output. All parameters are described in file `stm32f4xx_hal_msp.h`, +they can be changed to use another SPI and/or UART + +To use default scheme connect (CC3100 -> STM32-DISCO) connect: +``` +DO -> PE5 +DIN -> PE6 +CLK -> PE2 +CS -> PB12 +IRQ -> PA0 +HIB -> PB0 +``` + +## Building firmware + +Change `user_params.h`, put correct WiFi SSID and password there, +also change `MQTT_BROKER_ADDRESS` to the real broker address. + +`make` in `mongoose/STM32F4_CC3100` will download required docker image and make +firmware. Result will be in `STM32F4_CC3100/out` folder. + +## Uploading firmare + +Uploading firmware method depends on how you connected STM32 board to your +computer. If it is connected via USB ST-LINK connected it is appears as +a flash drive and in order to upload firmware just copy `out/example.bin` +to that drive. + +## Running + +Compile two additional samples: `mqtt_broker` and `mqtt_client` and run them +in different terminals. +Press `reset` (or repower) STM board. +The board will connect to broker and will start to publish its uptime in +`/stuff` channel. `mqtt_client` is subscribed on this channel as well, so +it should start to print + +``` +Got incoming message /stuff: Current tick: 99000 +Forwarding to /test +Got incoming message /stuff: Current tick: 100120 +Forwarding to /test +Got incoming message /stuff: Current tick: 101250 +Forwarding to /test +... + +``` + +If you connect UART to serial port monitor (pin PA9 or ST-LINK device, like /dev/ttyACM0) +you should see device output: +``` +**** Hello **** +Initializing CC3100 on SPI4 +Starting WiFi connect +Done, waiting for events +Connected to WiFi +Got IP +Connected to 192.168.1.108:1883 +Connected to broker +Subscribing to /test +Subscription acknowledged +Publishing message with tick=1 +Got incoming message /test: Current tick: 4487 +Publishing message with tick=2 +Got incoming message /test: Current tick: 5597 +Publishing message with tick=3 +Got incoming message /test: Current tick: 6717 +... + +``` + +This output looks like this because the device sends messages `Current tick: ....` +into `/stuff` channel, `mqtt_client` receives all messages in this channel +and sends them to `/test` channel. But the device is subscribed to this channel +so, it receives it back. diff --git a/examples/STM32F4_CC3100/main.c b/examples/STM32F4_CC3100/main.c new file mode 100644 index 000000000..d6c661ea5 --- /dev/null +++ b/examples/STM32F4_CC3100/main.c @@ -0,0 +1,149 @@ +/* + * Copyright (c) 2014-2016 Cesanta Software Limited + * All rights reserved + */ + +#include "./../../mongoose.h" +#include "stm32f4xx_hal_msp.h" +#include "stm32f4xx.h" +#include "user_params.h" + +enum SampleState { ssIniting, ssConnectedWLAN, ssWorking, ssStopped }; + +static enum SampleState state = ssIniting; +static struct mg_mgr mgr; +static int msg_id; + +void Error_Handler() { + /* Turn LED4 (red) on/off */ + while (1) { + BSP_LED_Toggle(LED4); + Delay(100); + } +} + +void SimpleLinkWlanEventHandler(SlWlanEvent_t *pWlanEvent) { + switch (pWlanEvent->Event) { + case SL_WLAN_CONNECT_EVENT: + CLI_Write("Connected to WiFi\r\n"); + break; + case SL_WLAN_DISCONNECT_EVENT: + CLI_Write("Disconnected WiFi\r\n"); + break; + default: + CLI_Write("Got Wlan event %d\r\n", pWlanEvent->Event); + break; + } +} + +void SimpleLinkNetAppEventHandler(SlNetAppEvent_t *pNetAppEvent) { + switch (pNetAppEvent->Event) { + case SL_NETAPP_IPV4_IPACQUIRED_EVENT: + CLI_Write("Got IP\r\n"); + state = ssConnectedWLAN; + break; + default: + CLI_Write("Got NetApp Event: %d\r\n", pNetAppEvent->Event); + break; + } +} + +struct mg_mqtt_topic_expression topic_expressions[] = {{"/test", 0}}; + +static void ev_handler(struct mg_connection *nc, int ev, void *p) { + struct mg_mqtt_message *msg = (struct mg_mqtt_message *) p; + + switch (ev) { + case MG_EV_CONNECT: + if (*(int *) p != 0) { + CLI_Write("Failed to connect to %s\r\n", MQTT_BROKER_ADDRESS); + } else { + CLI_Write("Connected to %s\r\n", MQTT_BROKER_ADDRESS); + } + struct mg_send_mqtt_handshake_opts opts; + memset(&opts, 0, sizeof(opts)); + opts.user_name = MQTT_USER_NAME; + opts.password = MQTT_USER_PWD; + mg_set_protocol_mqtt(nc); + mg_send_mqtt_handshake_opt(nc, "STM32", opts); + break; + case MG_EV_MQTT_CONNACK: + if (msg->connack_ret_code != MG_EV_MQTT_CONNACK_ACCEPTED) { + CLI_Write("Got mqtt connection error %d\n\r", msg->connack_ret_code); + } else { + CLI_Write("Connected to broker\n\r"); + } + CLI_Write("Subscribing to /test\n\r"); + mg_mqtt_subscribe(nc, topic_expressions, + sizeof(topic_expressions) / sizeof(*topic_expressions), + ++msg_id); + break; + case MG_EV_MQTT_SUBACK: + CLI_Write("Subscription acknowledged\r\n"); + state = ssWorking; + break; + case MG_EV_MQTT_PUBLISH: + CLI_Write("Got incoming message %s: %.*s\r\n", msg->topic, + (int) msg->payload.len, msg->payload.p); + break; + case MG_EV_POLL: + if (state == ssWorking) { + char msg[100]; + uint32_t tick = HAL_GetTick(); + int len = snprintf(msg, sizeof(msg), "Current tick: %u", tick); + CLI_Write("Publishing message with tick=%u\r\n", tick); + mg_mqtt_publish(nc, "/stuff", ++msg_id, MG_MQTT_QOS(0), msg, len); + } + break; + case MG_EV_CLOSE: + CLI_Write("Connection to broker is closed\r\n"); + state = ssStopped; + break; + default: + break; + } +} + +int main(void) { + stopWDT(); + initClk(); + + BSP_LED_Init(LED3); + BSP_LED_Init(LED4); + + CLI_Configure(); + CLI_Write("\n\n\n**** Hello ****\r\n"); + CLI_Write("Initializing CC3100 on SPI%d\r\n", SPIx_NUMBER); + + int ret = sl_Start(NULL, NULL, NULL); + + SlSecParams_t sec_params; + memset(&sec_params, 0, sizeof(sec_params)); + sec_params.Key = NET_PWD; + sec_params.KeyLen = sizeof(NET_PWD) - 1; + sec_params.Type = NET_SECURITY; + + CLI_Write("Starting WiFi connect\r\n"); + + ret = sl_WlanConnect(NET_SSID, sizeof(NET_SSID) - 1, 0, &sec_params, NULL); + + CLI_Write("Done, waiting for events\n\r"); + + while (1) { + BSP_LED_Toggle(LED3); + _SlNonOsMainLoopTask(); + if (state == 1) { + mg_mgr_init(&mgr, NULL); + if (mg_connect(&mgr, MQTT_BROKER_ADDRESS, ev_handler) == NULL) { + CLI_Write("Failed to create connection\n\r"); + } + state = 2; + } + mg_mgr_poll(&mgr, 1000); + } +} + +void HAL_UART_ErrorCallback(UART_HandleTypeDef *UartHandle) { + /* Turn LED4 (red) on: Transfer error in reception/transmission process */ + BSP_LED_On(LED4); +} diff --git a/examples/STM32F4_CC3100/sdk.version b/examples/STM32F4_CC3100/sdk.version new file mode 100644 index 000000000..04df6826a --- /dev/null +++ b/examples/STM32F4_CC3100/sdk.version @@ -0,0 +1 @@ +docker.cesanta.com/stm32-cc3100-build:stm32-1.10.0_cc3100-1.2.0-r1 diff --git a/examples/STM32F4_CC3100/startup_stm32f429xx.s b/examples/STM32F4_CC3100/startup_stm32f429xx.s new file mode 100755 index 000000000..31632477f --- /dev/null +++ b/examples/STM32F4_CC3100/startup_stm32f429xx.s @@ -0,0 +1,561 @@ +/** + ****************************************************************************** + * @file startup_stm32f429xx.s + * @author MCD Application Team + * @version V1.2.4 + * @date 13-November-2015 + * @brief STM32F429xx Devices vector table for Atollic TrueSTUDIO toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M4 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * <h2><center>© COPYRIGHT 2015 STMicroelectronics</center></h2> + * + * 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 STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS 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 THE COPYRIGHT HOLDER 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. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m4 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr sp, =_estack /* set stack pointer */ + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + +g_pfnVectors: + .word _estack + .word Reset_Handler + + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + + /* External Interrupts */ + .word WWDG_IRQHandler /* Window WatchDog */ + .word PVD_IRQHandler /* PVD through EXTI Line detection */ + .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ + .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ + .word FLASH_IRQHandler /* FLASH */ + .word RCC_IRQHandler /* RCC */ + .word EXTI0_IRQHandler /* EXTI Line0 */ + .word EXTI1_IRQHandler /* EXTI Line1 */ + .word EXTI2_IRQHandler /* EXTI Line2 */ + .word EXTI3_IRQHandler /* EXTI Line3 */ + .word EXTI4_IRQHandler /* EXTI Line4 */ + .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ + .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ + .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ + .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ + .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ + .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ + .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ + .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ + .word CAN1_TX_IRQHandler /* CAN1 TX */ + .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ + .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ + .word CAN1_SCE_IRQHandler /* CAN1 SCE */ + .word EXTI9_5_IRQHandler /* External Line[9:5]s */ + .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ + .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ + .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ + .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ + .word TIM2_IRQHandler /* TIM2 */ + .word TIM3_IRQHandler /* TIM3 */ + .word TIM4_IRQHandler /* TIM4 */ + .word I2C1_EV_IRQHandler /* I2C1 Event */ + .word I2C1_ER_IRQHandler /* I2C1 Error */ + .word I2C2_EV_IRQHandler /* I2C2 Event */ + .word I2C2_ER_IRQHandler /* I2C2 Error */ + .word SPI1_IRQHandler /* SPI1 */ + .word SPI2_IRQHandler /* SPI2 */ + .word USART1_IRQHandler /* USART1 */ + .word USART2_IRQHandler /* USART2 */ + .word USART3_IRQHandler /* USART3 */ + .word EXTI15_10_IRQHandler /* External Line[15:10]s */ + .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ + .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ + .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ + .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ + .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ + .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ + .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ + .word FMC_IRQHandler /* FMC */ + .word SDIO_IRQHandler /* SDIO */ + .word TIM5_IRQHandler /* TIM5 */ + .word SPI3_IRQHandler /* SPI3 */ + .word UART4_IRQHandler /* UART4 */ + .word UART5_IRQHandler /* UART5 */ + .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ + .word TIM7_IRQHandler /* TIM7 */ + .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ + .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ + .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ + .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ + .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ + .word ETH_IRQHandler /* Ethernet */ + .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ + .word CAN2_TX_IRQHandler /* CAN2 TX */ + .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ + .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ + .word CAN2_SCE_IRQHandler /* CAN2 SCE */ + .word OTG_FS_IRQHandler /* USB OTG FS */ + .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ + .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ + .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EV_IRQHandler /* I2C3 event */ + .word I2C3_ER_IRQHandler /* I2C3 error */ + .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ + .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ + .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ + .word OTG_HS_IRQHandler /* USB OTG HS */ + .word DCMI_IRQHandler /* DCMI */ + .word 0 /* Reserved */ + .word HASH_RNG_IRQHandler /* Hash and Rng */ + .word FPU_IRQHandler /* FPU */ + .word UART7_IRQHandler /* UART7 */ + .word UART8_IRQHandler /* UART8 */ + .word SPI4_IRQHandler /* SPI4 */ + .word SPI5_IRQHandler /* SPI5 */ + .word SPI6_IRQHandler /* SPI6 */ + .word SAI1_IRQHandler /* SAI1 */ + .word LTDC_IRQHandler /* LTDC_IRQHandler */ + .word LTDC_ER_IRQHandler /* LTDC_ER_IRQHandler */ + .word DMA2D_IRQHandler /* DMA2D */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMP_STAMP_IRQHandler + .thumb_set TAMP_STAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_IRQHandler + .thumb_set RTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Stream0_IRQHandler + .thumb_set DMA1_Stream0_IRQHandler,Default_Handler + + .weak DMA1_Stream1_IRQHandler + .thumb_set DMA1_Stream1_IRQHandler,Default_Handler + + .weak DMA1_Stream2_IRQHandler + .thumb_set DMA1_Stream2_IRQHandler,Default_Handler + + .weak DMA1_Stream3_IRQHandler + .thumb_set DMA1_Stream3_IRQHandler,Default_Handler + + .weak DMA1_Stream4_IRQHandler + .thumb_set DMA1_Stream4_IRQHandler,Default_Handler + + .weak DMA1_Stream5_IRQHandler + .thumb_set DMA1_Stream5_IRQHandler,Default_Handler + + .weak DMA1_Stream6_IRQHandler + .thumb_set DMA1_Stream6_IRQHandler,Default_Handler + + .weak ADC_IRQHandler + .thumb_set ADC_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTC_Alarm_IRQHandler + .thumb_set RTC_Alarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak DMA1_Stream7_IRQHandler + .thumb_set DMA1_Stream7_IRQHandler,Default_Handler + + .weak FMC_IRQHandler + .thumb_set FMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Stream0_IRQHandler + .thumb_set DMA2_Stream0_IRQHandler,Default_Handler + + .weak DMA2_Stream1_IRQHandler + .thumb_set DMA2_Stream1_IRQHandler,Default_Handler + + .weak DMA2_Stream2_IRQHandler + .thumb_set DMA2_Stream2_IRQHandler,Default_Handler + + .weak DMA2_Stream3_IRQHandler + .thumb_set DMA2_Stream3_IRQHandler,Default_Handler + + .weak DMA2_Stream4_IRQHandler + .thumb_set DMA2_Stream4_IRQHandler,Default_Handler + + .weak ETH_IRQHandler + .thumb_set ETH_IRQHandler,Default_Handler + + .weak ETH_WKUP_IRQHandler + .thumb_set ETH_WKUP_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler,Default_Handler + + .weak CAN2_SCE_IRQHandler + .thumb_set CAN2_SCE_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler,Default_Handler + + .weak DMA2_Stream5_IRQHandler + .thumb_set DMA2_Stream5_IRQHandler,Default_Handler + + .weak DMA2_Stream6_IRQHandler + .thumb_set DMA2_Stream6_IRQHandler,Default_Handler + + .weak DMA2_Stream7_IRQHandler + .thumb_set DMA2_Stream7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EV_IRQHandler + .thumb_set I2C3_EV_IRQHandler,Default_Handler + + .weak I2C3_ER_IRQHandler + .thumb_set I2C3_ER_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_OUT_IRQHandler + .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_IN_IRQHandler + .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler + + .weak OTG_HS_WKUP_IRQHandler + .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler + + .weak OTG_HS_IRQHandler + .thumb_set OTG_HS_IRQHandler,Default_Handler + + .weak DCMI_IRQHandler + .thumb_set DCMI_IRQHandler,Default_Handler + + .weak HASH_RNG_IRQHandler + .thumb_set HASH_RNG_IRQHandler,Default_Handler + + .weak FPU_IRQHandler + .thumb_set FPU_IRQHandler,Default_Handler + + .weak UART7_IRQHandler + .thumb_set UART7_IRQHandler,Default_Handler + + .weak UART8_IRQHandler + .thumb_set UART8_IRQHandler,Default_Handler + + .weak SPI4_IRQHandler + .thumb_set SPI4_IRQHandler,Default_Handler + + .weak SPI5_IRQHandler + .thumb_set SPI5_IRQHandler,Default_Handler + + .weak SPI6_IRQHandler + .thumb_set SPI6_IRQHandler,Default_Handler + + .weak SAI1_IRQHandler + .thumb_set SAI1_IRQHandler,Default_Handler + + .weak LTDC_IRQHandler + .thumb_set LTDC_IRQHandler,Default_Handler + + .weak LTDC_ER_IRQHandler + .thumb_set LTDC_ER_IRQHandler,Default_Handler + + .weak DMA2D_IRQHandler + .thumb_set DMA2D_IRQHandler,Default_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + + + diff --git a/examples/STM32F4_CC3100/startup_utils.c b/examples/STM32F4_CC3100/startup_utils.c new file mode 100644 index 000000000..aca2bed69 --- /dev/null +++ b/examples/STM32F4_CC3100/startup_utils.c @@ -0,0 +1,29 @@ +/* + * Copyright (c) 2014-2016 Cesanta Software Limited + * All rights reserved + */ + +#include <stdlib.h> + +/* + * STM's startup script requires __libc_init_array for successfull + * initialization. + * Oficially supported IDE (Keil, IAR...) provide this function. + * We use our own + */ + +extern void (*__preinit_array_start[])(void) __attribute__((weak)); +extern void (*__preinit_array_end[])(void) __attribute__((weak)); +extern void (*__init_array_start[])(void) __attribute__((weak)); +extern void (*__init_array_end[])(void) __attribute__((weak)); + +void __libc_init_array(void) { + size_t count; + size_t i; + + count = __preinit_array_end - __preinit_array_start; + for (i = 0; i < count; i++) __preinit_array_start[i](); + + count = __init_array_end - __init_array_start; + for (i = 0; i < count; i++) __init_array_start[i](); +} diff --git a/examples/STM32F4_CC3100/stm32f429xx.ld b/examples/STM32F4_CC3100/stm32f429xx.ld new file mode 100755 index 000000000..e09a650c1 --- /dev/null +++ b/examples/STM32F4_CC3100/stm32f429xx.ld @@ -0,0 +1,93 @@ +/* + * Copyright (c) 2016 Cesanta Software Limited + * All rights reserved + * GCC linker script for stm32f429. Based on startup sctipt + * (startup_stm32f429xx.s - COPYRIGHT 2015 STMicroelectronics) + */ +ENTRY(Reset_Handler) + +_estack = 0x2002FFFF; /* required by startup sctipt */ + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 1024K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 192K + CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = 64K +} + +SECTIONS +{ + .isr_vector : + { + . = ALIGN(4); + *(.isr_vector) + . = ALIGN(4); + } >FLASH + + .text : + { + . = ALIGN(4); + *(.text) + *(.text*) + *(.glue_7t) + *(.eh_frame) + *(.init) + *(.fini) + . = ALIGN(4); + _etext = .; + } >FLASH + + .rodata : + { + . = ALIGN(4); + *(.rodata) + *(.rodata*) + . = ALIGN(4); + } >FLASH + + _sidata = LOADADDR(.data); /* required by startup sctipt */ + + .data : + { + . = ALIGN(4); + _sdata = .; + *(.data) + *(.data*) + . = ALIGN(4); + _edata = .; + } >RAM AT> FLASH + + _siccmram = LOADADDR(.ccmram); /* required by startup sctipt */ + + .ccmram : + { + . = ALIGN(4); + _sccmram = .; + *(.ccmram) + *(.ccmram*) + + . = ALIGN(4); + _eccmram = .; + } >CCMRAM AT> FLASH + + . = ALIGN(4); + .bss : + { + _sbss = .; + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; + __bss_end__ = _ebss; + } >RAM + + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + . = ALIGN(4); + } >RAM +} diff --git a/examples/STM32F4_CC3100/stm32f4xx_hal_msp.h b/examples/STM32F4_CC3100/stm32f4xx_hal_msp.h new file mode 100644 index 000000000..a1b7ec995 --- /dev/null +++ b/examples/STM32F4_CC3100/stm32f4xx_hal_msp.h @@ -0,0 +1,74 @@ +/* + * Copyright (c) 2014-2016 Cesanta Software Limited + * All rights reserved + */ + +#ifndef CS_MONGOOSE_EXAMPLES_STM32F4_CC3100_STM32F4XX_HAL_MSP_H_ +#define CS_MONGOOSE_EXAMPLES_STM32F4_CC3100_STM32F4XX_HAL_MSP_H_ + +/* + * Definitions for SPI used to communicate with CC3100 + * All samples in STMCubeF4 use SPI4 for examples + * We do the same. See README.MD for details. + */ +#define SPIx_NUMBER 4 +#define SPIx SPI4 +#define SPIx_CLK_ENABLE() __HAL_RCC_SPI4_CLK_ENABLE() +#define SPIx_SCK_GPIO_CLK_ENABLE() __HAL_RCC_GPIOE_CLK_ENABLE() +#define SPIx_MISO_GPIO_CLK_ENABLE() __HAL_RCC_GPIOE_CLK_ENABLE() +#define SPIx_MOSI_GPIO_CLK_ENABLE() __HAL_RCC_GPIOE_CLK_ENABLE() +#define SPIx_NSS_GPIO_CLK_ENABLE() __HAL_RCC_GPIOE_CLK_ENABLE() + +#define SPIx_FORCE_RESET() __HAL_RCC_SPI4_FORCE_RESET() +#define SPIx_RELEASE_RESET() __HAL_RCC_SPI4_RELEASE_RESET() + +#define SPIx_SCK_PIN GPIO_PIN_2 +#define SPIx_SCK_GPIO_PORT GPIOE +#define SPIx_SCK_AF GPIO_AF5_SPI4 +#define SPIx_MISO_PIN GPIO_PIN_5 +#define SPIx_MISO_GPIO_PORT GPIOE +#define SPIx_MISO_AF GPIO_AF5_SPI4 +#define SPIx_MOSI_PIN GPIO_PIN_6 +#define SPIx_MOSI_GPIO_PORT GPIOE +#define SPIx_MOSI_AF GPIO_AF5_SPI4 + +#define SPIx_IRQn SPI4_IRQn +#define SPIx_IRQHandler SPI4_IRQHandler + +#define SPI_CS_PIN GPIO_PIN_12 +#define SPI_CS_PORT GPIOB + +/* + * CC3100 requires 2 additional pins for communication + * See http://processors.wiki.ti.com/index.php/CC31xx_SPI_Host_Interface + * for details + */ + +#define MCU_IRQ_PIN GPIO_PIN_0 +#define MCU_IRQ_PORT GPIOA +#define MCU_nHIB_PORT GPIOB +#define MCU_nHIB_PIN GPIO_PIN_0 + +/* + * Definitions used for debug uart. + * By default we use USART1, and this allows to connect serial port monitor + * to dedicated pin (PA9) and to ST-LINK port (/dev/ttyACM0 in Linux) + * See README.MD for details. + */ +#define USARTx USART1 +#define USART_SPEED 115200 +#define USARTx_CLK_ENABLE() __HAL_RCC_USART1_CLK_ENABLE(); +#define USARTx_RX_GPIO_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE() +#define USARTx_TX_GPIO_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE() + +#define USARTx_FORCE_RESET() __HAL_RCC_USART1_FORCE_RESET() +#define USARTx_RELEASE_RESET() __HAL_RCC_USART1_RELEASE_RESET() + +#define USARTx_TX_PIN GPIO_PIN_9 +#define USARTx_TX_GPIO_PORT GPIOA +#define USARTx_TX_AF GPIO_AF7_USART1 +#define USARTx_RX_PIN GPIO_PIN_10 +#define USARTx_RX_GPIO_PORT GPIOA +#define USARTx_RX_AF GPIO_AF7_USART1 + +#endif /* CS_MONGOOSE_EXAMPLES_STM32F4_CC3100_STM32F4XX_HAL_MSP_H_ */ diff --git a/examples/STM32F4_CC3100/user_params.h b/examples/STM32F4_CC3100/user_params.h new file mode 100644 index 000000000..d380b8273 --- /dev/null +++ b/examples/STM32F4_CC3100/user_params.h @@ -0,0 +1,18 @@ +/* + * Copyright (c) 2014-2016 Cesanta Software Limited + * All rights reserved + */ + +#ifndef CS_MONGOOSE_EXAMPLES_STM32F4_CC3100_USER_PARAMS_H_ +#define CS_MONGOOSE_EXAMPLES_STM32F4_CC3100_USER_PARAMS_H_ + +/* Put you WIFI parameters here */ +#define NET_SSID "my_ssid" +#define NET_PWD "my_password" +#define NET_SECURITY SL_SEC_TYPE_WPA_WPA2 + +#define MQTT_BROKER_ADDRESS "192.168.1.108:1883" +#define MQTT_USER_NAME NULL +#define MQTT_USER_PWD NULL + +#endif /* CS_MONGOOSE_EXAMPLES_STM32F4_CC3100_USER_PARAMS_H_ */ diff --git a/examples/mqtt_broker/mqtt_broker.c b/examples/mqtt_broker/mqtt_broker.c index 8cb465e9f..4c02f9b61 100644 --- a/examples/mqtt_broker/mqtt_broker.c +++ b/examples/mqtt_broker/mqtt_broker.c @@ -32,6 +32,8 @@ int main(void) { } nc->user_data = &brk; + printf("MQTT broker started on %s\n", address); + /* * TODO: Add a HTTP status page that shows current sessions * and subscriptions diff --git a/mongoose.c b/mongoose.c index e8ad3704d..3a38a1976 100644 --- a/mongoose.c +++ b/mongoose.c @@ -10440,8 +10440,6 @@ int sl_fs_init() { /* Amalgamated: #include "common/platform.h" */ -#include <simplelink/include/netapp.h> - const char *inet_ntop(int af, const void *src, char *dst, socklen_t size) { int res; struct in_addr *in = (struct in_addr *) src; @@ -10481,7 +10479,7 @@ int inet_pton(int af, const char *src, void *dst) { #ifdef MG_MODULE_LINES #line 1 "./src/../../common/platforms/simplelink/sl_mg_task.c" #endif -#if defined(MG_SOCKET_SIMPLELINK) +#if defined(MG_SOCKET_SIMPLELINK) && !defined(MG_SIMPLELINK_NO_OSI) /* Amalgamated: #include "mg_task.h" */ diff --git a/mongoose.h b/mongoose.h index 2047cda2e..ca7d5ebc8 100644 --- a/mongoose.h +++ b/mongoose.h @@ -76,6 +76,7 @@ #define CS_P_ESP_LWIP 3 #define CS_P_CC3200 4 #define CS_P_MSP432 5 +#define CS_P_CC3100 6 /* If not specified explicitly, we guess platform by defines. */ #ifndef CS_PLATFORM @@ -405,6 +406,57 @@ unsigned long os_random(void); * All rights reserved */ +#ifndef CS_COMMON_PLATFORMS_PLATFORM_CC3100_H_ +#define CS_COMMON_PLATFORMS_PLATFORM_CC3100_H_ +#if CS_PLATFORM == CS_P_CC3100 + +#include <assert.h> +#include <ctype.h> +#include <errno.h> +#include <inttypes.h> +#include <stdint.h> +#include <string.h> +#include <time.h> + +#define MG_SOCKET_SIMPLELINK 1 +#define MG_DISABLE_SOCKETPAIR 1 +#define MG_DISABLE_SYNC_RESOLVER 1 +#define MG_DISABLE_POPEN 1 +#define MG_DISABLE_CGI 1 +#define MG_DISABLE_DAV 1 +#define MG_DISABLE_DIRECTORY_LISTING 1 +#define MG_DISABLE_FILESYSTEM 1 + +/* + * CC3100 SDK and STM32 SDK include headers w/out path, just like + * #include "simplelink.h". As result, we have to add all required directories + * into Makefile IPATH and do the same thing (include w/out path) + */ + +#include <simplelink.h> +#include <netapp.h> + +typedef int sock_t; +#define INVALID_SOCKET (-1) + +#define to64(x) strtoll(x, NULL, 10) +#define INT64_FMT PRId64 +#define INT64_X_FMT PRIx64 +#define SIZE_T_FMT "u" + +#define SOMAXCONN 8 + +const char *inet_ntop(int af, const void *src, char *dst, socklen_t size); +char *inet_ntoa(struct in_addr in); +int inet_pton(int af, const char *src, void *dst); + +#endif /* CS_PLATFORM == CS_P_CC3100 */ +#endif /* CS_COMMON_PLATFORMS_PLATFORM_CC3100_H_ */ +/* + * Copyright (c) 2014-2016 Cesanta Software Limited + * All rights reserved + */ + #ifndef CS_COMMON_PLATFORMS_PLATFORM_CC3200_H_ #define CS_COMMON_PLATFORMS_PLATFORM_CC3200_H_ #if CS_PLATFORM == CS_P_CC3200 @@ -657,6 +709,7 @@ int _stat(const char *pathname, struct stat *st); #undef SL_INC_STD_BSD_API_NAMING #include <simplelink/include/simplelink.h> +#include <simplelink/include/netapp.h> /* Now define only the subset of the BSD API that we use. * Notably, close(), read() and write() are not defined. */ -- GitLab