diff --git a/arch/cpu/cc2538/Makefile.cc2538 b/arch/cpu/cc2538/Makefile.cc2538 index c7fe61496..e1b522443 100644 --- a/arch/cpu/cc2538/Makefile.cc2538 +++ b/arch/cpu/cc2538/Makefile.cc2538 @@ -76,7 +76,7 @@ CPU_STARTFILES = ${addprefix $(OBJECTDIR)/,${call oname, $(CPU_START_SOURCEFILES CONTIKI_SOURCEFILES += $(CONTIKI_CPU_SOURCEFILES) $(DEBUG_IO_SOURCEFILES) CONTIKI_SOURCEFILES += $(USB_SOURCEFILES) -MODULES += lib/newlib arch/cpu/arm/common/sys +MODULES += os/lib/newlib .SECONDEXPANSION: diff --git a/arch/cpu/cc26xx-cc13xx/Makefile.cc26xx-cc13xx b/arch/cpu/cc26xx-cc13xx/Makefile.cc26xx-cc13xx index f976eb85b..8a3efd07f 100644 --- a/arch/cpu/cc26xx-cc13xx/Makefile.cc26xx-cc13xx +++ b/arch/cpu/cc26xx-cc13xx/Makefile.cc26xx-cc13xx @@ -32,7 +32,7 @@ LDSCRIPT = $(CONTIKI_CPU)/cc26xx.ld CFLAGS += -mcpu=cortex-m3 -mthumb -mlittle-endian CFLAGS += -ffunction-sections -fdata-sections CFLAGS += -fshort-enums -fomit-frame-pointer -fno-strict-aliasing -CFLAGS += -Wall -std=c99 +CFLAGS += -Wall -std=c99 -DCMSIS_DEV_HDR=\"cc13x0-cc26x0-cm3.h\" LDFLAGS += -mcpu=cortex-m3 -mthumb -mlittle-endian -nostartfiles LDFLAGS += -T $(LDSCRIPT) @@ -62,10 +62,10 @@ endif CLEAN += *.d *.elf *.hex ### CPU-dependent directories -CONTIKI_CPU_DIRS = . dev rf-core rf-core/api $(TI_XXWARE_STARTUP_DIR) +CONTIKI_CPU_DIRS += . dev rf-core rf-core/api $(TI_XXWARE_STARTUP_DIR) -### Use the existing debug I/O in arch/cpu/arm/common -CONTIKI_CPU_DIRS += ../arm/common/dbg-io +### Use CMSIS and the existing debug I/O in arch/cpu/arm/common +CONTIKI_CPU_DIRS += ../arm/common/dbg-io ../arm/common/CMSIS ### CPU-dependent source files CONTIKI_CPU_SOURCEFILES += clock.c rtimer-arch.c soc-rtc.c uart.c @@ -106,7 +106,7 @@ $(OBJECTDIR)/ieee-addr.o: ieee-addr.c FORCE | $(OBJECTDIR) ### to make clean first $(OBJECTDIR)/ccfg.o: ccfg.c FORCE | $(OBJECTDIR) $(TRACE_CC) - $(Q)$(CC) $(CFLAGS) -include "contiki-conf.h" -c $< -o $@ + $(Q)$(CC) $(CFLAGS) -include "ccxxware-conf.h" -c $< -o $@ ### Compilation rules CUSTOM_RULE_LINK=1 diff --git a/arch/cpu/cc26xx-cc13xx/cc13x0-cc26x0-cm3.h b/arch/cpu/cc26xx-cc13xx/cc13x0-cc26x0-cm3.h new file mode 100644 index 000000000..bda2e2b07 --- /dev/null +++ b/arch/cpu/cc26xx-cc13xx/cc13x0-cc26x0-cm3.h @@ -0,0 +1,128 @@ +/* + * Template: + * Copyright (c) 2012 ARM LIMITED + * All rights reserved. + * + * CC13xx-CC26xx: + * Copyright (c) 2017, George Oikonomou - http://www.spd.gr + * All rights reserved. + * + * 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 holder 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup cc26xx + * @{ + * + * \defgroup cc26xx-cm3 CC13xx/CC26xx CMSIS + * + * CC13xx/CC26xx Cortex-M3 CMSIS definitions + * @{ + * + * \file + * CMSIS Cortex-M3 core peripheral access layer header file for CC13xx/CC26xx + */ +/*---------------------------------------------------------------------------*/ +#ifndef CC13XX_CC26XX_CM3_H_ +#define CC13XX_CC26XX_CM3_H_ +/*---------------------------------------------------------------------------*/ +/** + * \name Interrupt Number Definition + * @{ + */ +typedef enum cc13xx_cc26xx_cm3_irq_e { + /* Cortex-M3 Processor Exceptions */ + CC13XX_CC26XX_CM3_EXCEPTION_RESET = -15, /**< 1 Reset */ + CC13XX_CC26XX_CM3_EXCEPTION_NMI = -14, /**< 2 NMI */ + CC13XX_CC26XX_CM3_EXCEPTION_HARD_FAULT = -13, /**< 3 Hard fault */ + CC13XX_CC26XX_CM3_EXCEPTION_MPU_FAULT = -12, /**< 4 MPU fault */ + CC13XX_CC26XX_CM3_EXCEPTION_BUS_FAULT = -11, /**< 5 Bus fault */ + CC13XX_CC26XX_CM3_EXCEPTION_USAGE_FAULT = -10, /**< 6 Usage fault */ + CC13XX_CC26XX_CM3_EXCEPTION_SV_CALL = -5, /**< 11 SVCall */ + CC13XX_CC26XX_CM3_EXCEPTION_DEBUG_MON = -4, /**< 12 Debug monitor */ + CC13XX_CC26XX_CM3_EXCEPTION_PEND_SV = -2, /**< 14 PendSV */ + CC13XX_CC26XX_CM3_EXCEPTION_SYS_TICK = -1, /**< 15 SysTick */ + + /* CC13xx/CC26xx interrupts */ + CC13XX_CC26XX_CM3_IRQ_EDGE_DETECT = 0, /**< 16 AON edge detect */ + CC13XX_CC26XX_CM3_EXCEPTION_I2C = 1, /**< 17 I2C */ + CC13XX_CC26XX_CM3_EXCEPTION_RF_CPE1 = 2, /**< 18 RF Command and Packet Engine 1 */ + CC13XX_CC26XX_CM3_EXCEPTION_AON_SPI_SLAVE = 3, /**< 19 AON SpiSplave Rx, Tx and CS */ + CC13XX_CC26XX_CM3_EXCEPTION_AON_RTC = 4, /**< 20 AON RTC */ + CC13XX_CC26XX_CM3_EXCEPTION_UART0 = 5, /**< 21 UART0 Rx and Tx */ + CC13XX_CC26XX_CM3_EXCEPTION_AON_AUX_SWEV0 = 6, /**< 22 Sensor Controller software event 0, through AON domain*/ + CC13XX_CC26XX_CM3_EXCEPTION_SSI0 = 7, /**< 23 SSI0 Rx and Tx */ + CC13XX_CC26XX_CM3_EXCEPTION_SSI1 = 8, /**< 24 SSI1 Rx and Tx */ + CC13XX_CC26XX_CM3_EXCEPTION_RF_CPE0 = 9, /**< 25 RF Command and Packet Engine 0 */ + CC13XX_CC26XX_CM3_EXCEPTION_RF_HW = 10, /**< 26 RF Core Hardware */ + CC13XX_CC26XX_CM3_EXCEPTION_RF_CMD_ACK = 11, /**< 27 RF Core Command Acknowledge */ + CC13XX_CC26XX_CM3_EXCEPTION_I2S = 12, /**< 28 I2S */ + CC13XX_CC26XX_CM3_EXCEPTION_AON_AUX_SWEV1 = 13, /**< 29 Sensor Controller software event 1, through AON domain*/ + CC13XX_CC26XX_CM3_EXCEPTION_WATCHDOG = 14, /**< 30 Watchdog timer */ + CC13XX_CC26XX_CM3_EXCEPTION_GPTIMER_0A = 15, /**< 31 Timer 0 subtimer A */ + CC13XX_CC26XX_CM3_EXCEPTION_GPTIMER_0B = 16, /**< 32 Timer 0 subtimer B */ + CC13XX_CC26XX_CM3_EXCEPTION_GPTIMER_1A = 17, /**< 33 Timer 1 subtimer A */ + CC13XX_CC26XX_CM3_EXCEPTION_GPTIMER_1B = 18, /**< 34 Timer 1 subtimer B */ + CC13XX_CC26XX_CM3_EXCEPTION_GPTIMER_2A = 19, /**< 35 Timer 2 subtimer A */ + CC13XX_CC26XX_CM3_EXCEPTION_GPTIMER_2B = 20, /**< 36 Timer 2 subtimer B */ + CC13XX_CC26XX_CM3_EXCEPTION_GPTIMER_3A = 21, /**< 37 Timer 3 subtimer A */ + CC13XX_CC26XX_CM3_EXCEPTION_GPTIMER_3B = 22, /**< 38 Timer 3 subtimer B */ + CC13XX_CC26XX_CM3_EXCEPTION_CRYPTO = 23, /**< 39 Crypto Core Result available */ + CC13XX_CC26XX_CM3_EXCEPTION_UDMA = 24, /**< 40 uDMA Software */ + CC13XX_CC26XX_CM3_EXCEPTION_UDMA_ERR = 25, /**< 41 uDMA Error */ + CC13XX_CC26XX_CM3_EXCEPTION_FLASH_CTRL = 26, /**< 42 Flash controller */ + CC13XX_CC26XX_CM3_EXCEPTION_SW0 = 27, /**< 43 Software Event 0 */ + CC13XX_CC26XX_CM3_EXCEPTION_AUX_COM_EVENT = 28, /**< 44 AUX combined event, directly to MCU domain*/ + CC13XX_CC26XX_CM3_EXCEPTION_AON_PRG0 = 29, /**< 45 AON programmable 0 */ + CC13XX_CC26XX_CM3_EXCEPTION_PROG = 30, /**< 46 Dynamic Programmable interrupt (default source: PRCM)*/ + CC13XX_CC26XX_CM3_EXCEPTION_AUX_COMPA = 31, /**< 47 AUX Comparator A */ + CC13XX_CC26XX_CM3_EXCEPTION_AUX_ADC = 32, /**< 48 AUX ADC IRQ */ + CC13XX_CC26XX_CM3_EXCEPTION_TRNG = 33, /**< 49 TRNG event */ +} cc13xx_cc26xx_cm3_irq_t; + +typedef cc13xx_cc26xx_cm3_irq_t IRQn_Type; + +#define SysTick_IRQn CC13XX_CC26XX_CM3_EXCEPTION_SYS_TICK +/** @} */ +/*---------------------------------------------------------------------------*/ +/** \name Processor and Core Peripheral Section + * @{ + */ +/* Configuration of the Cortex-M3 Processor and Core Peripherals */ +#define __MPU_PRESENT 1 /**< MPU present or not */ +#define __NVIC_PRIO_BITS 3 /**< Number of Bits used for Priority Levels */ +#define __Vendor_SysTickConfig 0 /**< Set to 1 if different SysTick Config is used */ +/** @} */ +/*---------------------------------------------------------------------------*/ +#include "core_cm3.h" /* Cortex-M3 processor and core peripherals */ +/*---------------------------------------------------------------------------*/ +#endif /* CC13XX_CC26XX_CM3_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/arch/cpu/cc26xx-cc13xx/ccxxware-conf.h b/arch/cpu/cc26xx-cc13xx/ccxxware-conf.h new file mode 100644 index 000000000..97be16b5d --- /dev/null +++ b/arch/cpu/cc26xx-cc13xx/ccxxware-conf.h @@ -0,0 +1,76 @@ +/* + * Copyright (c) 2017, Alex Stanoev + * All rights reserved. + * + * 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 holder 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. + */ +/** + * \addtogroup cc26xx + * @{ + * + * \defgroup cc26xx-ccxxware-conf CCxxware-specific configuration + * + * @{ + * + * \file + * CCxxware-specific configuration for the cc26xx-cc13xx CPU family + */ +#ifndef CCXXWARE_CONF_H_ +#define CCXXWARE_CONF_H_ + +#include "contiki-conf.h" + +/*---------------------------------------------------------------------------*/ +/** + * \brief JTAG interface configuration + * + * Those values are not meant to be modified by the user + * @{ + */ +#if CCXXWARE_CONF_JTAG_INTERFACE_ENABLE +#define SET_CCFG_CCFG_TI_OPTIONS_TI_FA_ENABLE 0xC5 +#define SET_CCFG_CCFG_TAP_DAP_0_CPU_DAP_ENABLE 0xC5 +#define SET_CCFG_CCFG_TAP_DAP_0_PRCM_TAP_ENABLE 0xC5 +#define SET_CCFG_CCFG_TAP_DAP_0_TEST_TAP_ENABLE 0xC5 +#define SET_CCFG_CCFG_TAP_DAP_1_PBIST2_TAP_ENABLE 0xC5 +#define SET_CCFG_CCFG_TAP_DAP_1_PBIST1_TAP_ENABLE 0xC5 +#define SET_CCFG_CCFG_TAP_DAP_1_WUC_TAP_ENABLE 0xC5 +#else +#define SET_CCFG_CCFG_TI_OPTIONS_TI_FA_ENABLE 0x00 +#define SET_CCFG_CCFG_TAP_DAP_0_CPU_DAP_ENABLE 0x00 +#define SET_CCFG_CCFG_TAP_DAP_0_PRCM_TAP_ENABLE 0x00 +#define SET_CCFG_CCFG_TAP_DAP_0_TEST_TAP_ENABLE 0x00 +#define SET_CCFG_CCFG_TAP_DAP_1_PBIST2_TAP_ENABLE 0x00 +#define SET_CCFG_CCFG_TAP_DAP_1_PBIST1_TAP_ENABLE 0x00 +#define SET_CCFG_CCFG_TAP_DAP_1_WUC_TAP_ENABLE 0x00 +#endif +/** @} */ +#endif /* CCXXWARE_CONF_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/arch/cpu/cc26xx-cc13xx/lib/cc13xxware b/arch/cpu/cc26xx-cc13xx/lib/cc13xxware index f4800b7af..682cf5d60 160000 --- a/arch/cpu/cc26xx-cc13xx/lib/cc13xxware +++ b/arch/cpu/cc26xx-cc13xx/lib/cc13xxware @@ -1 +1 @@ -Subproject commit f4800b7af65e78fd45e0a1f72648abf70a9fe567 +Subproject commit 682cf5d60aa6b6be77c5519ff70fa18087fe3cf0 diff --git a/arch/cpu/cc26xx-cc13xx/lib/cc26xxware b/arch/cpu/cc26xx-cc13xx/lib/cc26xxware index 40916ad11..568511d65 160000 --- a/arch/cpu/cc26xx-cc13xx/lib/cc26xxware +++ b/arch/cpu/cc26xx-cc13xx/lib/cc26xxware @@ -1 +1 @@ -Subproject commit 40916ad11efdcac76775b9b18cebc8d0c37c48f2 +Subproject commit 568511d650601afdc80106d9b9d5c44882635d17 diff --git a/arch/cpu/cc26xx-cc13xx/rf-core/ieee-mode.c b/arch/cpu/cc26xx-cc13xx/rf-core/ieee-mode.c index d4c1c27e5..a354fdd4b 100644 --- a/arch/cpu/cc26xx-cc13xx/rf-core/ieee-mode.c +++ b/arch/cpu/cc26xx-cc13xx/rf-core/ieee-mode.c @@ -167,6 +167,9 @@ static uint8_t rf_stats[16] = { 0 }; /* How long to wait for the RF to react on CMD_ABORT: around 1 msec */ #define RF_TURN_OFF_WAIT_TIMEOUT (RTIMER_SECOND >> 10) +/* How long to wait for the RF to finish TX of a packet or an ACK */ +#define TX_FINISH_WAIT_TIMEOUT (RTIMER_SECOND >> 7) + #define LIMITED_BUSYWAIT(cond, timeout) do { \ rtimer_clock_t end_time = RTIMER_NOW() + timeout; \ while(cond) { \ @@ -697,7 +700,7 @@ rx_off(void) } /* Wait for ongoing ACK TX to finish */ - while(transmitting()); + LIMITED_BUSYWAIT(transmitting(), TX_FINISH_WAIT_TIMEOUT); /* Send a CMD_ABORT command to RF Core */ if(rf_core_send_cmd(CMDR_DIR_CMD(CMD_ABORT), &cmd_status) != RF_CORE_CMD_OK) { @@ -1140,7 +1143,7 @@ channel_clear(void) * * We could probably even simply return that the channel is clear */ - while(transmitting()); + LIMITED_BUSYWAIT(transmitting(), TX_FINISH_WAIT_TIMEOUT); } else { was_off = 1; if(on() != RF_CORE_CMD_OK) { @@ -1297,7 +1300,7 @@ off(void) return RF_CORE_CMD_OK; } - while(transmitting()); + LIMITED_BUSYWAIT(transmitting(), TX_FINISH_WAIT_TIMEOUT); /* stopping the rx explicitly results in lower sleep-mode power usage */ rx_off(); diff --git a/arch/cpu/cc26xx-cc13xx/rf-core/rf-ble.c b/arch/cpu/cc26xx-cc13xx/rf-core/rf-ble.c index 3faf75d25..e5a38cac7 100644 --- a/arch/cpu/cc26xx-cc13xx/rf-core/rf-ble.c +++ b/arch/cpu/cc26xx-cc13xx/rf-core/rf-ble.c @@ -1,5 +1,6 @@ /* * Copyright (c) 2015, Texas Instruments Incorporated - http://www.ti.com/ + * Copyright (c) 2017, University of Bristol - http://www.bristol.ac.uk/ * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -71,7 +72,7 @@ #define BLE_ADV_TYPE_DEVINFO 0x01 #define BLE_ADV_TYPE_NAME 0x09 #define BLE_ADV_TYPE_MANUFACTURER 0xFF -#define BLE_ADV_NAME_BUF_LEN 32 +#define BLE_ADV_NAME_BUF_LEN BLE_ADV_MAX_SIZE #define BLE_ADV_PAYLOAD_BUF_LEN 64 #define BLE_UUID_SIZE 16 /*---------------------------------------------------------------------------*/ @@ -82,8 +83,6 @@ static uint8_t payload[BLE_ADV_PAYLOAD_BUF_LEN]; static int p = 0; static int i; /*---------------------------------------------------------------------------*/ -static uint16_t tx_power = 0x9330; -/*---------------------------------------------------------------------------*/ /* BLE beacond config */ static struct ble_beacond_config { clock_time_t interval; @@ -108,6 +107,38 @@ static uint32_t ble_overrides[] = { 0xFFFFFFFF, /* End of override list */ }; /*---------------------------------------------------------------------------*/ +/* TX Power dBm lookup table - values from SmartRF Studio */ +typedef struct output_config { + radio_value_t dbm; + uint16_t tx_power; /* Value for the CMD_RADIO_SETUP.txPower field */ +} output_config_t; + +static const output_config_t output_power[] = { + { 5, 0x9330 }, + { 4, 0x9324 }, + { 3, 0x5a1c }, + { 2, 0x4e18 }, + { 1, 0x4214 }, + { 0, 0x3161 }, + { -3, 0x2558 }, + { -6, 0x1d52 }, + { -9, 0x194e }, + { -12, 0x144b }, + { -15, 0x0ccb }, + { -18, 0x0cc9 }, + { -21, 0x0cc7 }, +}; + +#define OUTPUT_CONFIG_COUNT (sizeof(output_power) / sizeof(output_config_t)) + +/* Max and Min Output Power in dBm */ +#define OUTPUT_POWER_MIN (output_power[OUTPUT_CONFIG_COUNT - 1].dbm) +#define OUTPUT_POWER_MAX (output_power[0].dbm) +#define OUTPUT_POWER_UNKNOWN 0xFFFF + +/* Default TX Power - position in output_power[] */ +static const output_config_t *tx_power_current = &output_power[0]; +/*---------------------------------------------------------------------------*/ PROCESS(rf_ble_beacon_process, "CC13xx / CC26xx RF BLE Beacon Process"); /*---------------------------------------------------------------------------*/ static int @@ -132,7 +163,7 @@ send_ble_adv_nc(int channel, uint8_t *adv_payload, int adv_payload_len) cmd.channel = channel; /* Set up BLE Advertisement parameters */ - params->pDeviceAddress = (uint16_t *)&linkaddr_node_addr.u8[LINKADDR_SIZE - 2]; + params->pDeviceAddress = (uint16_t *)BLE_ADDRESS_PTR; params->endTrigger.triggerType = TRIG_NEVER; params->endTime = TRIG_NEVER; @@ -157,6 +188,33 @@ send_ble_adv_nc(int channel, uint8_t *adv_payload, int adv_payload_len) return RF_CORE_CMD_OK; } /*---------------------------------------------------------------------------*/ +/* Returns the current TX power in dBm */ +radio_value_t +rf_ble_get_tx_power(void) +{ + return tx_power_current->dbm; +} +/*---------------------------------------------------------------------------*/ +/* + * Set TX power to 'at least' power dBm + * This works with a lookup table. If the value of 'power' does not exist in + * the lookup table, TXPOWER will be set to the immediately higher available + * value + */ +void +rf_ble_set_tx_power(radio_value_t power) +{ + int i; + + /* First, find the correct setting and save it */ + for(i = OUTPUT_CONFIG_COUNT - 1; i >= 0; --i) { + if(power <= output_power[i].dbm) { + tx_power_current = &output_power[i]; + break; + } + } +} +/*---------------------------------------------------------------------------*/ void rf_ble_beacond_config(clock_time_t interval, const char *name) { @@ -211,7 +269,6 @@ rf_ble_beacond_stop() { process_exit(&rf_ble_beacon_process); } -/*---------------------------------------------------------------------------*/ static uint8_t rf_radio_setup() { @@ -223,7 +280,7 @@ rf_radio_setup() /* Create radio setup command */ rf_core_init_radio_op((rfc_radioOp_t *)&cmd, sizeof(cmd), CMD_RADIO_SETUP); - cmd.txPower = tx_power; + cmd.txPower = tx_power_current->tx_power; cmd.pRegOverride = ble_overrides; cmd.config.frontEndMode = RF_CORE_RADIO_SETUP_FRONT_END_MODE; cmd.config.biasMode = RF_CORE_RADIO_SETUP_BIAS_MODE; @@ -246,13 +303,114 @@ rf_radio_setup() return RF_CORE_CMD_OK; } /*---------------------------------------------------------------------------*/ -PROCESS_THREAD(rf_ble_beacon_process, ev, data) +/*---------------------------------------------------------------------------*/ +void +rf_ble_beacon_single(uint8_t channel, uint8_t *data, uint8_t len) { - uint8_t was_on; - int j; uint32_t cmd_status; bool interrupts_disabled; + uint8_t j, channel_selected; + uint8_t was_on; + /* Adhere to the maximum BLE advertisement payload size */ + if(len > BLE_ADV_NAME_BUF_LEN) { + len = BLE_ADV_NAME_BUF_LEN; + } + + /* + * Under ContikiMAC, some IEEE-related operations will be called from an + * interrupt context. We need those to see that we are in BLE mode. + */ + interrupts_disabled = ti_lib_int_master_disable(); + ble_mode_on = RF_BLE_ACTIVE; + if(!interrupts_disabled) { + ti_lib_int_master_enable(); + } + + /* + * First, determine our state: + * + * If we are running CSMA, we are likely in IEEE RX mode. We need to + * abort the IEEE BG Op before entering BLE mode. + * If we are ContikiMAC, we are likely off, in which case we need to + * boot the CPE before entering BLE mode + */ + was_on = rf_core_is_accessible(); + + if(was_on) { + /* + * We were on: If we are in the process of receiving a frame, abort the + * BLE beacon burst. Otherwise, terminate the primary radio Op so we + * can switch to BLE mode + */ + if(NETSTACK_RADIO.receiving_packet()) { + PRINTF("rf_ble_beacon_single: We were receiving\n"); + + /* Abort this pass */ + return; + } + + rf_core_primary_mode_abort(); + } else { + + oscillators_request_hf_xosc(); + + /* We were off: Boot the CPE */ + if(rf_core_boot() != RF_CORE_CMD_OK) { + /* Abort this pass */ + PRINTF("rf_ble_beacon_single: rf_core_boot() failed\n"); + return; + } + + oscillators_switch_to_hf_xosc(); + + /* Enter BLE mode */ + if(rf_radio_setup() != RF_CORE_CMD_OK) { + /* Continue so we can at least try to restore our previous state */ + PRINTF("rf_ble_beacon_single: Error entering BLE mode\n"); + } else { + + for(j = 0; j < 3; j++) { + channel_selected = (channel >> j) & 0x01; + if(channel_selected == 1) { + if(send_ble_adv_nc(37 + j, data, len) != RF_CORE_CMD_OK) { + /* Continue... */ + PRINTF("rf_ble_beacon_single: Channel=%d, " + "Error advertising\n", 37 + j); + } + } + } + } + + /* Send a CMD_STOP command to RF Core */ + if(rf_core_send_cmd(CMDR_DIR_CMD(CMD_STOP), &cmd_status) != RF_CORE_CMD_OK) { + /* Continue... */ + PRINTF("rf_ble_beacon_single: status=0x%08lx\n", cmd_status); + } + + if(was_on) { + /* We were on, go back to previous primary mode */ + rf_core_primary_mode_restore(); + } else { + /* We were off. Shut back off */ + rf_core_power_down(); + + /* Switch HF clock source to the RCOSC to preserve power */ + oscillators_switch_to_hf_rc(); + } + + interrupts_disabled = ti_lib_int_master_disable(); + + ble_mode_on = RF_BLE_IDLE; + + if(!interrupts_disabled) { + ti_lib_int_master_enable(); + } + } +} +/*---------------------------------------------------------------------------*/ +PROCESS_THREAD(rf_ble_beacon_process, ev, data) +{ PROCESS_BEGIN(); while(1) { @@ -278,115 +436,21 @@ PROCESS_THREAD(rf_ble_beacon_process, ev, data) strlen(beacond_config.adv_name)); p += strlen(beacond_config.adv_name); + /* + * Send BLE_ADV_MESSAGES beacon bursts. Each burst on all three + * channels, with a BLE_ADV_DUTY_CYCLE interval between bursts + */ for(i = 0; i < BLE_ADV_MESSAGES; i++) { - /* - * Under ContikiMAC, some IEEE-related operations will be called from an - * interrupt context. We need those to see that we are in BLE mode. - */ - interrupts_disabled = ti_lib_int_master_disable(); - ble_mode_on = RF_BLE_ACTIVE; - if(!interrupts_disabled) { - ti_lib_int_master_enable(); - } - /* - * Send BLE_ADV_MESSAGES beacon bursts. Each burst on all three - * channels, with a BLE_ADV_DUTY_CYCLE interval between bursts - * - * First, determine our state: - * - * If we are running CSMA, we are likely in IEEE RX mode. We need to - * abort the IEEE BG Op before entering BLE mode. - * If we are ContikiMAC, we are likely off, in which case we need to - * boot the CPE before entering BLE mode - */ - was_on = rf_core_is_accessible(); + rf_ble_beacon_single(BLE_ADV_CHANNEL_ALL, payload, p); - if(was_on) { - /* - * We were on: If we are in the process of receiving a frame, abort the - * BLE beacon burst. Otherwise, terminate the primary radio Op so we - * can switch to BLE mode - */ - if(NETSTACK_RADIO.receiving_packet()) { - PRINTF("rf_ble_beacon_process: We were receiving\n"); - - /* Abort this pass */ - break; - } - - rf_core_primary_mode_abort(); - } else { - /* Request the HF XOSC to source the HF clock. */ - oscillators_request_hf_xosc(); - - /* We were off: Boot the CPE */ - if(rf_core_boot() != RF_CORE_CMD_OK) { - PRINTF("rf_ble_beacon_process: rf_core_boot() failed\n"); - - /* Abort this pass */ - break; - } - - /* Trigger a switch to the XOSC, so that we can use the FS */ - oscillators_switch_to_hf_xosc(); - } - - /* Enter BLE mode */ - if(rf_radio_setup() != RF_CORE_CMD_OK) { - PRINTF("cc26xx_rf_ble_beacon_process: Error entering BLE mode\n"); - /* Continue so we can at least try to restore our previous state */ - } else { - /* Send advertising packets on all 3 advertising channels */ - for(j = 37; j <= 39; j++) { - if(send_ble_adv_nc(j, payload, p) != RF_CORE_CMD_OK) { - PRINTF("cc26xx_rf_ble_beacon_process: Channel=%d, " - "Error advertising\n", j); - /* Break the loop, but don't return just yet */ - break; - } - } - } - - /* Send a CMD_STOP command to RF Core */ - if(rf_core_send_cmd(CMDR_DIR_CMD(CMD_STOP), &cmd_status) != RF_CORE_CMD_OK) { - PRINTF("cc26xx_rf_ble_beacon_process: status=0x%08lx\n", cmd_status); - /* Continue... */ - } - - if(was_on) { - /* We were on, go back to previous primary mode */ - rf_core_primary_mode_restore(); - } else { - /* We were off. Shut back off */ - rf_core_power_down(); - - /* Switch HF clock source to the RCOSC to preserve power */ - oscillators_switch_to_hf_rc(); - } etimer_set(&ble_adv_et, BLE_ADV_DUTY_CYCLE); - interrupts_disabled = ti_lib_int_master_disable(); - - ble_mode_on = RF_BLE_IDLE; - - if(!interrupts_disabled) { - ti_lib_int_master_enable(); - } - /* Wait unless this is the last burst */ if(i < BLE_ADV_MESSAGES - 1) { PROCESS_WAIT_EVENT_UNTIL(etimer_expired(&ble_adv_et)); } } - - interrupts_disabled = ti_lib_int_master_disable(); - - ble_mode_on = RF_BLE_IDLE; - - if(!interrupts_disabled) { - ti_lib_int_master_enable(); - } } PROCESS_END(); } diff --git a/arch/cpu/cc26xx-cc13xx/rf-core/rf-ble.h b/arch/cpu/cc26xx-cc13xx/rf-core/rf-ble.h index 6d91dc13d..761ca88d6 100644 --- a/arch/cpu/cc26xx-cc13xx/rf-core/rf-ble.h +++ b/arch/cpu/cc26xx-cc13xx/rf-core/rf-ble.h @@ -1,5 +1,6 @@ /* * Copyright (c) 2015, Texas Instruments Incorporated - http://www.ti.com/ + * Copyright (c) 2017, University of Bristol - http://www.bristol.ac.uk/ * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -45,6 +46,7 @@ /*---------------------------------------------------------------------------*/ #include "contiki.h" #include "rf-core/rf-core.h" +#include "radio.h" #include /*---------------------------------------------------------------------------*/ @@ -57,6 +59,23 @@ #define RF_BLE_IDLE 0 #define RF_BLE_ACTIVE 1 /*---------------------------------------------------------------------------*/ +/* Memory address of BLE MAC address. Can be overwritten by the user by defining BLE_ADDRESS_PTR. */ +#ifndef BLE_ADDRESS_PTR +#define BLE_ADDRESS_PTR (0x500012E8) +#endif +/*---------------------------------------------------------------------------*/ +/* BLE Advertisement channels. Not to be changed by the user. */ +#define BLE_ADV_CHANNEL_MASK 0x07 + +#define BLE_ADV_CHANNEL_37 0x01 +#define BLE_ADV_CHANNEL_38 0x02 +#define BLE_ADV_CHANNEL_39 0x04 + +#define BLE_ADV_CHANNEL_ALL (BLE_ADV_CHANNEL_37 | BLE_ADV_CHANNEL_38 | BLE_ADV_CHANNEL_39) +/*---------------------------------------------------------------------------*/ +/* Maximum BLE advertisement size. Not to be changed by the user. */ +#define BLE_ADV_MAX_SIZE 31 +/*---------------------------------------------------------------------------*/ /** * \brief Set the device name to use with the BLE advertisement/beacon daemon * \param interval The interval (ticks) between two consecutive beacon bursts @@ -89,6 +108,37 @@ void rf_ble_beacond_stop(void); * \retval 0 The BLE daemon is not active, or disabled */ uint8_t rf_ble_is_active(void); + +/** + * \brief Set TX power for BLE advertisements + * \param power The 'at least' TX power in dBm, values avove 5 dBm will be ignored + * + * Set TX power to 'at least' power dBm. + * This works with a lookup table. If the value of 'power' does not exist in + * the lookup table, TXPOWER will be set to the immediately higher available + * value + */ +void rf_ble_set_tx_power(radio_value_t power); + +/** + * \brief Get TX power for BLE advertisements + * \return The TX power for BLE advertisements + */ +radio_value_t rf_ble_get_tx_power(void); + +/** + * \brief Transmit a single BLE advertisement in one or more advertisement channels + * \param channel Bitmask of advertisement channels to be used: use + * BLE_ADV_CHANNEL_37 for channel 37, BLE_ADV_CHANNEL_38 for channel 38, + * BLE_ADV_CHANNEL_39 for channel 39, or any 'or' combination of those + * \param data A pointer to the advertisement data buffer + * \param len The length of the advertisement data. If more than BLE_ADV_MAX_SIZE, + * the first BLE_ADV_MAX_SIZE bytes will be used. + * + * Transmits a given advertisement payload once in one or any arbitrary combination + * of advertisement channels. + */ +void rf_ble_beacon_single(uint8_t channel, uint8_t *data, uint8_t len); /*---------------------------------------------------------------------------*/ #endif /* RF_BLE_H_ */ /*---------------------------------------------------------------------------*/ diff --git a/arch/platform/jn516x/lib/slip.c b/arch/platform/jn516x/lib/slip.c index 8e66c5f66..a5ce4c16d 100644 --- a/arch/platform/jn516x/lib/slip.c +++ b/arch/platform/jn516x/lib/slip.c @@ -167,7 +167,7 @@ slip_write_char(uint8_t c) slip_arch_writeb(c); } /*---------------------------------------------------------------------------*/ -uint8_t +void slip_write(const void *_ptr, int len) { const uint8_t *ptr = _ptr; @@ -181,14 +181,12 @@ slip_write(const void *_ptr, int len) slip_write_char(c); } slip_arch_writeb(SLIP_END); - - return len; } /*---------------------------------------------------------------------------*/ /* slip_send: forward (IPv4) packets with {UIP_FW_NETIF(..., slip_send)} * was used in slip-bridge.c */ -uint8_t +void slip_send(void) { uint16_t i; @@ -203,8 +201,6 @@ slip_send(void) slip_write_char(c); } slip_arch_writeb(SLIP_END); - - return UIP_FW_OK; } /*---------------------------------------------------------------------------*/ static void diff --git a/arch/platform/srf06-cc26xx/contiki-conf.h b/arch/platform/srf06-cc26xx/contiki-conf.h index 3c7430c6c..fbe9c5059 100644 --- a/arch/platform/srf06-cc26xx/contiki-conf.h +++ b/arch/platform/srf06-cc26xx/contiki-conf.h @@ -177,6 +177,19 @@ #endif /** @} */ /*---------------------------------------------------------------------------*/ +/** + * \name JTAG interface configuration + * + * Enable/Disable the JTAG DAP and TAP interfaces on the chip. + * Setting this to 0 will disable access to the debug interface + * to secure deployed images. + * @{ + */ +#ifndef CCXXWARE_CONF_JTAG_INTERFACE_ENABLE +#define CCXXWARE_CONF_JTAG_INTERFACE_ENABLE 1 +#endif +/** @} */ +/*---------------------------------------------------------------------------*/ /** * \name ROM Bootloader configuration * diff --git a/examples/slip-radio/project-conf.h b/examples/slip-radio/project-conf.h index 89e135a42..2f05bec5e 100644 --- a/examples/slip-radio/project-conf.h +++ b/examples/slip-radio/project-conf.h @@ -37,7 +37,7 @@ /*---------------------------------------------------------------------------*/ #define UIP_CONF_ROUTER 0 -#define CMD_CONF_OUTPUT slip_radio_cmd_output +#define CMD_CONF_OUTPUT slip_write /* Default CMD handlers if the target did not specify them */ #ifndef CMD_CONF_HANDLERS diff --git a/examples/slip-radio/slip-net.c b/examples/slip-radio/slip-net.c index 1a787c85c..e1efbf4cf 100644 --- a/examples/slip-radio/slip-net.c +++ b/examples/slip-radio/slip-net.c @@ -49,27 +49,6 @@ slipnet_init(void) { } /*---------------------------------------------------------------------------*/ -void -slip_send_packet(const uint8_t *ptr, int len) -{ - uint16_t i; - uint8_t c; - - slip_arch_writeb(SLIP_END); - for(i = 0; i < len; ++i) { - c = *ptr++; - if(c == SLIP_END) { - slip_arch_writeb(SLIP_ESC); - c = SLIP_ESC_END; - } else if(c == SLIP_ESC) { - slip_arch_writeb(SLIP_ESC); - c = SLIP_ESC_ESC; - } - slip_arch_writeb(c); - } - slip_arch_writeb(SLIP_END); -} -/*---------------------------------------------------------------------------*/ static void slipnet_input(void) { @@ -94,7 +73,7 @@ slipnet_input(void) } LOG_DBG_("\n"); - slip_send_packet(uip_buf, uip_len); + slip_write(uip_buf, uip_len); } /*---------------------------------------------------------------------------*/ static uint8_t diff --git a/examples/slip-radio/slip-radio.c b/examples/slip-radio/slip-radio.c index 720bc9694..53a0324bc 100644 --- a/examples/slip-radio/slip-radio.c +++ b/examples/slip-radio/slip-radio.c @@ -56,8 +56,6 @@ extern const struct slip_radio_sensors SLIP_RADIO_CONF_SENSORS; #endif -void slip_send_packet(const uint8_t *ptr, int len); - /* max 16 packets at the same time??? */ uint8_t packet_ids[16]; int packet_pos; @@ -187,12 +185,6 @@ slip_radio_cmd_handler(const uint8_t *data, int len) return 0; } /*---------------------------------------------------------------------------*/ -void -slip_radio_cmd_output(const uint8_t *data, int data_len) -{ - slip_send_packet(data, data_len); -} -/*---------------------------------------------------------------------------*/ static void slip_input_callback(void) { diff --git a/os/dev/slip.c b/os/dev/slip.c index b27dca332..3cfe9ea07 100644 --- a/os/dev/slip.c +++ b/os/dev/slip.c @@ -26,48 +26,41 @@ * 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. - * - * This file is part of the Contiki operating system. - * */ - +/*---------------------------------------------------------------------------*/ +#include "contiki.h" +#include "net/ipv6/uip.h" +#include "dev/slip.h" #include #include - -#include "contiki.h" - -#include "net/ipv6/uip.h" -#define BUF ((struct uip_tcpip_hdr *)&uip_buf[UIP_LLH_LEN]) - -#include "dev/slip.h" - +/*---------------------------------------------------------------------------*/ #define SLIP_END 0300 #define SLIP_ESC 0333 #define SLIP_ESC_END 0334 #define SLIP_ESC_ESC 0335 - +/*---------------------------------------------------------------------------*/ PROCESS(slip_process, "SLIP driver"); - -uint8_t slip_active; - -#if 1 -#define SLIP_STATISTICS(statement) -#else -uint16_t slip_rubbish, slip_twopackets, slip_overflow, slip_ip_drop; +/*---------------------------------------------------------------------------*/ +static uint8_t slip_active; +/*---------------------------------------------------------------------------*/ +#if SLIP_CONF_WITH_STATS +static uint16_t slip_rubbish, slip_twopackets, slip_overflow, slip_ip_drop; #define SLIP_STATISTICS(statement) statement +#else +#define SLIP_STATISTICS(statement) #endif - +/*---------------------------------------------------------------------------*/ /* Must be at least one byte larger than UIP_BUFSIZE! */ #define RX_BUFSIZE (UIP_BUFSIZE - UIP_LLH_LEN + 16) - +/*---------------------------------------------------------------------------*/ enum { - STATE_TWOPACKETS = 0, /* We have 2 packets and drop incoming data. */ + STATE_TWOPACKETS = 0, /* We have 2 packets and drop incoming data. */ STATE_OK = 1, STATE_ESC = 2, STATE_RUBBISH = 3, }; - +/*---------------------------------------------------------------------------*/ /* * Variables begin and end manage the buffer space in a cyclic * fashion. The first used byte is at begin and end is one byte past @@ -78,13 +71,12 @@ enum { * [pkt_end, end). If more bytes arrive in state STATE_TWOPACKETS * they are discarded. */ - static uint8_t state = STATE_TWOPACKETS; static uint16_t begin, next_free; static uint8_t rxbuf[RX_BUFSIZE]; -static uint16_t pkt_end; /* SLIP_END tracker. */ +static uint16_t pkt_end; /* SLIP_END tracker. */ -static void (* input_callback)(void) = NULL; +static void (*input_callback)(void) = NULL; /*---------------------------------------------------------------------------*/ void slip_set_input_callback(void (*c)(void)) @@ -92,36 +84,13 @@ slip_set_input_callback(void (*c)(void)) input_callback = c; } /*---------------------------------------------------------------------------*/ -/* slip_send: forward (IPv4) packets with {UIP_FW_NETIF(..., slip_send)} - * was used in slip-bridge.c - */ -uint8_t +void slip_send(void) { - uint16_t i; - uint8_t *ptr; - uint8_t c; - - slip_arch_writeb(SLIP_END); - - ptr = &uip_buf[UIP_LLH_LEN]; - for(i = 0; i < uip_len; ++i) { - c = *ptr++; - if(c == SLIP_END) { - slip_arch_writeb(SLIP_ESC); - c = SLIP_ESC_END; - } else if(c == SLIP_ESC) { - slip_arch_writeb(SLIP_ESC); - c = SLIP_ESC_ESC; - } - slip_arch_writeb(c); - } - slip_arch_writeb(SLIP_END); - - return UIP_FW_OK; + slip_write(&uip_buf[UIP_LLH_LEN], uip_len); } /*---------------------------------------------------------------------------*/ -uint8_t +void slip_write(const void *_ptr, int len) { const uint8_t *ptr = _ptr; @@ -141,9 +110,8 @@ slip_write(const void *_ptr, int len) } slip_arch_writeb(c); } - slip_arch_writeb(SLIP_END); - return len; + slip_arch_writeb(SLIP_END); } /*---------------------------------------------------------------------------*/ static void @@ -153,56 +121,9 @@ rxbuf_init(void) state = STATE_OK; } /*---------------------------------------------------------------------------*/ -/* Upper half does the polling. */ static uint16_t slip_poll_handler(uint8_t *outbuf, uint16_t blen) { -#ifdef SLIP_CONF_MICROSOFT_CHAT - /* This is a hack and won't work across buffer edge! */ - if(rxbuf[begin] == 'C') { - int i; - if(begin < next_free && (next_free - begin) >= 6 - && memcmp(&rxbuf[begin], "CLIENT", 6) == 0) { - state = STATE_TWOPACKETS; /* Interrupts do nothing. */ - memset(&rxbuf[begin], 0x0, 6); - - rxbuf_init(); - - for(i = 0; i < 13; i++) { - slip_arch_writeb("CLIENTSERVER\300"[i]); - } - return 0; - } - } -#endif /* SLIP_CONF_MICROSOFT_CHAT */ - -#ifdef SLIP_CONF_ANSWER_MAC_REQUEST - else if(rxbuf[begin] == '?') { - /* Used by tapslip6 to request mac for auto configure */ - int i, j; - char* hexchar = "0123456789abcdef"; - if(begin < next_free && (next_free - begin) >= 2 - && rxbuf[begin + 1] == 'M') { - state = STATE_TWOPACKETS; /* Interrupts do nothing. */ - rxbuf[begin] = 0; - rxbuf[begin + 1] = 0; - - rxbuf_init(); - - linkaddr_t addr = get_mac_addr(); - /* this is just a test so far... just to see if it works */ - slip_arch_writeb('!'); - slip_arch_writeb('M'); - for(j = 0; j < 8; j++) { - slip_arch_writeb(hexchar[addr.u8[j] >> 4]); - slip_arch_writeb(hexchar[addr.u8[j] & 15]); - } - slip_arch_writeb(SLIP_END); - return 0; - } - } -#endif /* SLIP_CONF_ANSWER_MAC_REQUEST */ - /* * Interrupt can not change begin but may change pkt_end. * If pkt_end != begin it will not change again. @@ -221,7 +142,7 @@ slip_poll_handler(uint8_t *outbuf, uint16_t blen) len = 0; break; } - if (esc) { + if(esc) { if(rxbuf[i] == SLIP_ESC_ESC) { outbuf[len] = SLIP_ESC; len++; @@ -245,7 +166,7 @@ slip_poll_handler(uint8_t *outbuf, uint16_t blen) len = 0; break; } - if (esc) { + if(esc) { if(rxbuf[i] == SLIP_ESC_ESC) { outbuf[len] = SLIP_ESC; len++; @@ -266,7 +187,7 @@ slip_poll_handler(uint8_t *outbuf, uint16_t blen) len = 0; break; } - if (esc) { + if(esc) { if(rxbuf[i] == SLIP_ESC_ESC) { outbuf[len] = SLIP_ESC; len++; @@ -332,17 +253,13 @@ PROCESS_THREAD(slip_process, ev, data) /* Move packet from rxbuf to buffer provided by uIP. */ uip_len = slip_poll_handler(&uip_buf[UIP_LLH_LEN], - UIP_BUFSIZE - UIP_LLH_LEN); + UIP_BUFSIZE - UIP_LLH_LEN); if(uip_len > 0) { if(input_callback) { input_callback(); } -#ifdef SLIP_CONF_TCPIP_INPUT - SLIP_CONF_TCPIP_INPUT(); -#else tcpip_input(); -#endif } } @@ -364,7 +281,7 @@ slip_input_byte(unsigned char c) if(c != SLIP_ESC_END && c != SLIP_ESC_ESC) { state = STATE_RUBBISH; SLIP_STATISTICS(slip_rubbish++); - next_free = pkt_end; /* remove rubbish */ + next_free = pkt_end; /* remove rubbish */ return 0; } state = STATE_OK; @@ -389,22 +306,14 @@ slip_input_byte(unsigned char c) } rxbuf[cur_end] = c; -#ifdef SLIP_CONF_MICROSOFT_CHAT - /* There could be a separate poll routine for this. */ - if(c == 'T' && rxbuf[begin] == 'C') { - process_poll(&slip_process); - return 1; - } -#endif /* SLIP_CONF_MICROSOFT_CHAT */ - if(c == SLIP_END) { /* * We have a new packet, possibly of zero length. * * There may already be one packet buffered. */ - if(cur_end != pkt_end) { /* Non zero length. */ - if(begin == pkt_end) { /* None buffered. */ + if(cur_end != pkt_end) { /* Non zero length. */ + if(begin == pkt_end) { /* None buffered. */ pkt_end = cur_end; } else { SLIP_STATISTICS(slip_twopackets++); diff --git a/os/dev/slip.h b/os/dev/slip.h index 759de1a46..bb0ca3baf 100644 --- a/os/dev/slip.h +++ b/os/dev/slip.h @@ -41,7 +41,7 @@ PROCESS_NAME(slip_process); /** * Send an IP packet from the uIP buffer with SLIP. */ -uint8_t slip_send(void); +void slip_send(void); /** * Input a SLIP byte. @@ -62,13 +62,10 @@ uint8_t slip_send(void); */ int slip_input_byte(unsigned char c); -uint8_t slip_write(const void *ptr, int len); - -/* Did we receive any bytes lately? */ -extern uint8_t slip_active; - -/* Statistics. */ -extern uint16_t slip_rubbish, slip_twopackets, slip_overflow, slip_ip_drop; +/** + * Send using SLIP len bytes starting from the location pointed to by ptr + */ +void slip_write(const void *ptr, int len); /** * Set a function to be called when there is activity on the SLIP