Merge pull request #685 from g-oikonomou/contrib/cc26xx/remove-lib-rom
Improve usage of CCxxwares and CC2640R2 SDK
This commit is contained in:
commit
f101e473a9
@ -2,6 +2,6 @@ TI_XXWARE_PATH = lib/cc13xxware
|
||||
|
||||
CONTIKI_CPU_SOURCEFILES += smartrf-settings.c prop-mode.c prop-mode-tx-power.c
|
||||
|
||||
CFLAGS += -DCPU_FAMILY_CC13XX=1
|
||||
CFLAGS += -DCPU_FAMILY_CC13X0=1 -DCPU_FAMILY_CC13XX=1
|
||||
|
||||
include $(CONTIKI_CPU)/Makefile.cc26xx-cc13xx
|
||||
|
@ -1,3 +1,5 @@
|
||||
TI_XXWARE_PATH = lib/cc2640r2-sdk
|
||||
|
||||
CFLAGS += -DCPU_FAMILY_CC26X0R2=1 -DCPU_FAMILY_CC26XXR2=1
|
||||
|
||||
include $(CONTIKI_CPU)/Makefile.cc26xx-cc13xx
|
||||
|
@ -1,3 +1,5 @@
|
||||
TI_XXWARE_PATH = lib/cc26xxware
|
||||
|
||||
CFLAGS += -DCPU_FAMILY_CC26X0=1 -DCPU_FAMILY_CC26XX=1
|
||||
|
||||
include $(CONTIKI_CPU)/Makefile.cc26xx-cc13xx
|
||||
|
@ -64,11 +64,11 @@
|
||||
* project has specified otherwise. Depending on the final mode, determine a
|
||||
* default channel (again, if unspecified) and configure RDC params
|
||||
*/
|
||||
#if CPU_FAMILY_CC13XX
|
||||
#if CPU_FAMILY_CC13X0
|
||||
#ifndef CC13XX_CONF_PROP_MODE
|
||||
#define CC13XX_CONF_PROP_MODE 1
|
||||
#endif /* CC13XX_CONF_PROP_MODE */
|
||||
#endif /* CPU_FAMILY_CC13XX */
|
||||
#endif /* CPU_FAMILY_CC13X0 */
|
||||
|
||||
#if CC13XX_CONF_PROP_MODE
|
||||
#ifndef NETSTACK_CONF_RADIO
|
||||
|
@ -39,7 +39,6 @@
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#include "contiki.h"
|
||||
#include "ti-lib.h"
|
||||
#include "ti-lib-rom.h"
|
||||
#include "dev/gpio-hal.h"
|
||||
|
||||
#include <stdint.h>
|
||||
@ -53,11 +52,7 @@ gpio_hal_arch_pin_cfg_set(gpio_hal_pin_t pin, gpio_hal_pin_cfg_t cfg)
|
||||
gpio_hal_pin_cfg_t tmp;
|
||||
|
||||
/* Clear settings that we are about to change, keep everything else */
|
||||
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
|
||||
config = ti_lib_ioc_port_configure_get(pin);
|
||||
#else
|
||||
config = ti_lib_rom_ioc_port_configure_get(pin);
|
||||
#endif
|
||||
config &= ~CONFIG_MASK;
|
||||
|
||||
tmp = cfg & GPIO_HAL_PIN_CFG_EDGE_BOTH;
|
||||
@ -87,7 +82,7 @@ gpio_hal_arch_pin_cfg_set(gpio_hal_pin_t pin, gpio_hal_pin_cfg_t cfg)
|
||||
config |= IOC_INT_ENABLE;
|
||||
}
|
||||
|
||||
ti_lib_rom_ioc_port_configure_set(pin, IOC_PORT_GPIO, config);
|
||||
ti_lib_ioc_port_configure_set(pin, IOC_PORT_GPIO, config);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
gpio_hal_pin_cfg_t
|
||||
@ -98,11 +93,7 @@ gpio_hal_arch_pin_cfg_get(gpio_hal_pin_t pin)
|
||||
uint32_t config;
|
||||
|
||||
cfg = 0;
|
||||
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
|
||||
config = ti_lib_ioc_port_configure_get(pin);
|
||||
#else
|
||||
config = ti_lib_rom_ioc_port_configure_get(pin);
|
||||
#endif
|
||||
|
||||
/* Pull */
|
||||
tmp = config & IOC_IOPULL_M;
|
||||
|
@ -49,7 +49,6 @@
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#include "contiki.h"
|
||||
#include "ti-lib.h"
|
||||
#include "ti-lib-rom.h"
|
||||
|
||||
#include <stdint.h>
|
||||
/*---------------------------------------------------------------------------*/
|
||||
@ -57,15 +56,10 @@
|
||||
|
||||
#define gpio_hal_arch_interrupt_enable(p) interrupt_enable(p)
|
||||
|
||||
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
|
||||
#define gpio_hal_arch_interrupt_disable(p) ti_lib_ioc_int_disable(p)
|
||||
#define gpio_hal_arch_pin_set_input(p) ti_lib_ioc_pin_type_gpio_input(p)
|
||||
#define gpio_hal_arch_pin_set_output(p) ti_lib_ioc_pin_type_gpio_output(p)
|
||||
#else
|
||||
#define gpio_hal_arch_interrupt_disable(p) ti_lib_rom_ioc_int_disable(p)
|
||||
#define gpio_hal_arch_pin_set_input(p) ti_lib_rom_ioc_pin_type_gpio_input(p)
|
||||
#define gpio_hal_arch_pin_set_output(p) ti_lib_rom_ioc_pin_type_gpio_output(p)
|
||||
#endif
|
||||
|
||||
#define gpio_hal_arch_set_pin(p) ti_lib_gpio_set_dio(p)
|
||||
#define gpio_hal_arch_clear_pin(p) ti_lib_gpio_clear_dio(p)
|
||||
#define gpio_hal_arch_toggle_pin(p) ti_lib_gpio_toggle_dio(p)
|
||||
@ -80,11 +74,7 @@ static inline void
|
||||
interrupt_enable(gpio_hal_pin_t pin)
|
||||
{
|
||||
ti_lib_gpio_clear_event_dio(pin);
|
||||
#ifndef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
|
||||
ti_lib_rom_ioc_int_enable(pin);
|
||||
#else
|
||||
ti_lib_ioc_int_enable(pin);
|
||||
#endif
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#endif /* GPIO_HAL_ARCH_H_ */
|
||||
|
@ -99,7 +99,7 @@ soc_rtc_init(void)
|
||||
ti_lib_aon_rtc_channel_enable(AON_RTC_CH1);
|
||||
ti_lib_aon_rtc_enable();
|
||||
|
||||
ti_lib_rom_int_enable(INT_AON_RTC_COMB);
|
||||
ti_lib_int_enable(INT_AON_RTC_COMB);
|
||||
|
||||
/* Re-enable interrupts */
|
||||
if(!interrupts_disabled) {
|
||||
|
@ -71,7 +71,7 @@ static void
|
||||
disable_number_ready_interrupt(void)
|
||||
{
|
||||
ti_lib_trng_int_disable(TRNG_NUMBER_READY);
|
||||
ti_lib_rom_int_disable(INT_TRNG_IRQ);
|
||||
ti_lib_int_disable(INT_TRNG_IRQ);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static void
|
||||
@ -79,14 +79,14 @@ enable_number_ready_interrupt(void)
|
||||
{
|
||||
ti_lib_trng_int_clear(TRNG_NUMBER_READY);
|
||||
ti_lib_trng_int_enable(TRNG_NUMBER_READY);
|
||||
ti_lib_rom_int_enable(INT_TRNG_IRQ);
|
||||
ti_lib_int_enable(INT_TRNG_IRQ);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static bool
|
||||
accessible(void)
|
||||
{
|
||||
/* First, check the PD */
|
||||
if(ti_lib_rom_prcm_power_domain_status(PRCM_DOMAIN_PERIPH)
|
||||
if(ti_lib_prcm_power_domain_status(PRCM_DOMAIN_PERIPH)
|
||||
!= PRCM_DOMAIN_POWER_ON) {
|
||||
return false;
|
||||
}
|
||||
@ -104,12 +104,12 @@ static void
|
||||
power_up(void)
|
||||
{
|
||||
/* First, make sure the PERIPH PD is on */
|
||||
ti_lib_rom_prcm_power_domain_on(PRCM_DOMAIN_PERIPH);
|
||||
while((ti_lib_rom_prcm_power_domain_status(PRCM_DOMAIN_PERIPH)
|
||||
ti_lib_prcm_power_domain_on(PRCM_DOMAIN_PERIPH);
|
||||
while((ti_lib_prcm_power_domain_status(PRCM_DOMAIN_PERIPH)
|
||||
!= PRCM_DOMAIN_POWER_ON));
|
||||
|
||||
/* Enable clock in active mode */
|
||||
ti_lib_rom_prcm_peripheral_run_enable(PRCM_PERIPH_TRNG);
|
||||
ti_lib_prcm_peripheral_run_enable(PRCM_PERIPH_TRNG);
|
||||
ti_lib_prcm_load_set();
|
||||
while(!ti_lib_prcm_load_get());
|
||||
}
|
||||
@ -136,7 +136,7 @@ static uint64_t
|
||||
read_number(void)
|
||||
{
|
||||
uint64_t ran = (uint64_t)HWREG(TRNG_BASE + TRNG_O_OUT1) << 32;
|
||||
ran += ti_lib_rom_trng_number_get(TRNG_LOW_WORD);
|
||||
ran += ti_lib_trng_number_get(TRNG_LOW_WORD);
|
||||
|
||||
return ran;
|
||||
}
|
||||
@ -237,7 +237,7 @@ soc_trng_rand_asynchronous(uint32_t samples, soc_trng_callback_t cb)
|
||||
ti_lib_trng_int_clear(TRNG_NUMBER_READY);
|
||||
|
||||
/* Enable clock in sleep mode and register with LPM */
|
||||
ti_lib_rom_prcm_peripheral_sleep_enable(PRCM_PERIPH_TRNG);
|
||||
ti_lib_prcm_peripheral_sleep_enable(PRCM_PERIPH_TRNG);
|
||||
ti_lib_prcm_load_set();
|
||||
while(!ti_lib_prcm_load_get());
|
||||
|
||||
@ -271,7 +271,7 @@ PROCESS_THREAD(soc_trng_process, ev, data)
|
||||
}
|
||||
|
||||
/* Disable clock in sleep mode */
|
||||
ti_lib_rom_prcm_peripheral_sleep_disable(PRCM_PERIPH_TRNG);
|
||||
ti_lib_prcm_peripheral_sleep_disable(PRCM_PERIPH_TRNG);
|
||||
ti_lib_prcm_load_set();
|
||||
while(!ti_lib_prcm_load_get());
|
||||
|
||||
|
@ -123,7 +123,7 @@ spi_arch_lock_and_open(const spi_device_t *dev)
|
||||
!= PRCM_DOMAIN_POWER_ON)) ;
|
||||
|
||||
/* Enable clock in active mode */
|
||||
ti_lib_rom_prcm_peripheral_run_enable(spi_controller[dev->spi_controller].prcm_periph);
|
||||
ti_lib_prcm_peripheral_run_enable(spi_controller[dev->spi_controller].prcm_periph);
|
||||
ti_lib_prcm_load_set();
|
||||
while(!ti_lib_prcm_load_get()) ;
|
||||
|
||||
@ -131,17 +131,14 @@ spi_arch_lock_and_open(const spi_device_t *dev)
|
||||
ti_lib_ssi_int_disable(spi_controller[dev->spi_controller].ssi_base, SSI_RXOR | SSI_RXFF | SSI_RXTO | SSI_TXFF);
|
||||
ti_lib_ssi_int_clear(spi_controller[dev->spi_controller].ssi_base, SSI_RXOR | SSI_RXTO);
|
||||
|
||||
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
|
||||
ti_lib_ssi_config_set_exp_clk(spi_controller[dev->spi_controller].ssi_base, ti_lib_sys_ctrl_clock_get(),
|
||||
get_mode(dev), SSI_MODE_MASTER, dev->spi_bit_rate, 8);
|
||||
ti_lib_ioc_pin_type_ssi_master(spi_controller[dev->spi_controller].ssi_base, dev->pin_spi_miso,
|
||||
dev->pin_spi_mosi, IOID_UNUSED, dev->pin_spi_sck);
|
||||
#else
|
||||
ti_lib_rom_ssi_config_set_exp_clk(spi_controller[dev->spi_controller].ssi_base, ti_lib_sys_ctrl_clock_get(),
|
||||
get_mode(dev), SSI_MODE_MASTER, dev->spi_bit_rate, 8);
|
||||
ti_lib_rom_ioc_pin_type_ssi_master(spi_controller[dev->spi_controller].ssi_base, dev->pin_spi_miso,
|
||||
dev->pin_spi_mosi, IOID_UNUSED, dev->pin_spi_sck);
|
||||
#endif
|
||||
ti_lib_ssi_config_set_exp_clk(spi_controller[dev->spi_controller].ssi_base,
|
||||
ti_lib_sys_ctrl_clock_get(),
|
||||
get_mode(dev), SSI_MODE_MASTER,
|
||||
dev->spi_bit_rate, 8);
|
||||
ti_lib_ioc_pin_type_ssi_master(spi_controller[dev->spi_controller].ssi_base,
|
||||
dev->pin_spi_miso,
|
||||
dev->pin_spi_mosi, IOID_UNUSED,
|
||||
dev->pin_spi_sck);
|
||||
|
||||
ti_lib_ssi_enable(spi_controller[dev->spi_controller].ssi_base);
|
||||
|
||||
@ -159,7 +156,7 @@ spi_arch_close_and_unlock(const spi_device_t *dev)
|
||||
}
|
||||
|
||||
/* Power down SSI */
|
||||
ti_lib_rom_prcm_peripheral_run_disable(spi_controller[dev->spi_controller].prcm_periph);
|
||||
ti_lib_prcm_peripheral_run_disable(spi_controller[dev->spi_controller].prcm_periph);
|
||||
ti_lib_prcm_load_set();
|
||||
while(!ti_lib_prcm_load_get()) ;
|
||||
|
||||
@ -213,20 +210,12 @@ spi_arch_transfer(const spi_device_t *dev,
|
||||
for(i = 0; i < totlen; i++) {
|
||||
c = i < wlen ? write_buf[i] : 0;
|
||||
ti_lib_ssi_data_put(spi_controller[dev->spi_controller].ssi_base, (uint8_t)c);
|
||||
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
|
||||
ti_lib_ssi_data_get(spi_controller[dev->spi_controller].ssi_base, &c);
|
||||
#else
|
||||
ti_lib_rom_ssi_data_get(spi_controller[dev->spi_controller].ssi_base, &c);
|
||||
#endif
|
||||
if(i < rlen) {
|
||||
inbuf[i] = (uint8_t)c;
|
||||
}
|
||||
}
|
||||
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
|
||||
while(ti_lib_ssi_data_get_non_blocking(spi_controller[dev->spi_controller].ssi_base, &c)) ;
|
||||
#else
|
||||
while(ti_lib_rom_ssi_data_get_non_blocking(spi_controller[dev->spi_controller].ssi_base, &c)) ;
|
||||
#endif
|
||||
return SPI_DEV_STATUS_OK;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
|
@ -162,10 +162,10 @@ lpm_shutdown(uint32_t wakeup_pin, uint32_t io_pull, uint32_t wake_on)
|
||||
ti_lib_aon_wuc_mcu_power_off_config(MCU_VIRT_PWOFF_DISABLE);
|
||||
|
||||
/* Latch the IOs in the padring and enable I/O pad sleep mode */
|
||||
#if !defined(ThisLibraryIsFor_CC26x0R2_HaltIfViolated)
|
||||
ti_lib_pwr_ctrl_io_freeze_enable();
|
||||
ti_lib_aon_ioc_freeze_enable();
|
||||
HWREG(AON_SYSCTL_BASE + AON_SYSCTL_O_SLEEPCTL) = 0;
|
||||
ti_lib_sys_ctrl_aon_sync();
|
||||
|
||||
#endif
|
||||
/* Turn off VIMS cache, CRAM and TRAM - possibly not required */
|
||||
ti_lib_prcm_cache_retention_disable();
|
||||
ti_lib_vims_mode_set(VIMS_BASE, VIMS_MODE_OFF);
|
||||
@ -193,12 +193,7 @@ wake_up(void)
|
||||
ti_lib_sys_ctrl_aon_sync();
|
||||
|
||||
/* Adjust recharge settings */
|
||||
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
|
||||
// May need to change to XOSC_IN_LOW_POWER_MODE
|
||||
ti_lib_sys_ctrl_adjust_recharge_after_power_down(XOSC_IN_HIGH_POWER_MODE);
|
||||
#else
|
||||
ti_lib_sys_ctrl_adjust_recharge_after_power_down();
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Release the request to the uLDO
|
||||
|
@ -399,8 +399,8 @@ rf_core_set_modesel()
|
||||
} else if(chip_type == CHIP_TYPE_CC1350) {
|
||||
HWREG(PRCM_BASE + PRCM_O_RFCMODESEL) = PRCM_RFCMODESEL_CURR_MODE5;
|
||||
rv = RF_CORE_CMD_OK;
|
||||
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
|
||||
} else if (chip_type == CHIP_TYPE_CC2640R2) {
|
||||
#if CPU_FAMILY_CC26X0R2
|
||||
} else if(chip_type == CHIP_TYPE_CC2640R2) {
|
||||
HWREG(PRCM_BASE + PRCM_O_RFCMODESEL) = PRCM_RFCMODESEL_CURR_MODE1;
|
||||
rv = RF_CORE_CMD_OK;
|
||||
#endif
|
||||
|
@ -1,195 +0,0 @@
|
||||
/*
|
||||
* Copyright (c) 2016, Texas Instruments Incorporated - http://www.ti.com/
|
||||
* 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-ti-lib
|
||||
* @{
|
||||
*
|
||||
* \file
|
||||
* Header file with CC13xxware/CC26xxware ROM API.
|
||||
*/
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#ifndef TI_LIB_ROM_H_
|
||||
#define TI_LIB_ROM_H_
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* rom.h */
|
||||
#include "driverlib/rom.h"
|
||||
|
||||
/* AON API */
|
||||
#define ti_lib_rom_aon_event_mcu_wake_up_set ROM_AONEventMcuWakeUpSet
|
||||
#define ti_lib_rom_aon_event_mcu_wake_up_get ROM_AONEventMcuWakeUpGet
|
||||
#define ti_lib_rom_aon_event_aux_wake_up_set ROM_AONEventAuxWakeUpSet
|
||||
#define ti_lib_rom_aon_event_aux_wake_up_get ROM_AONEventAuxWakeUpGet
|
||||
#define ti_lib_rom_aon_event_mcu_set ROM_AONEventMcuSet
|
||||
#define ti_lib_rom_aon_event_mcu_get ROM_AONEventMcuGet
|
||||
|
||||
/* AON_WUC API */
|
||||
#define ti_lib_rom_aon_wuc_aux_reset ROM_AONWUCAuxReset
|
||||
#define ti_lib_rom_aon_wuc_recharge_ctrl_config_set ROM_AONWUCRechargeCtrlConfigSet
|
||||
#define ti_lib_rom_aon_wuc_osc_config ROM_AONWUCOscConfig
|
||||
|
||||
/* AUX_TDC API */
|
||||
#define ti_lib_rom_aux_tdc_config_set ROM_AUXTDCConfigSet
|
||||
#define ti_lib_rom_aux_tdc_measurement_done ROM_AUXTDCMeasurementDone
|
||||
|
||||
/* AUX_WUC API */
|
||||
#define ti_lib_rom_aux_wuc_clock_enable ROM_AUXWUCClockEnable
|
||||
#define ti_lib_rom_aux_wuc_clock_disable ROM_AUXWUCClockDisable
|
||||
#define ti_lib_rom_aux_wuc_clock_status ROM_AUXWUCClockStatus
|
||||
#define ti_lib_rom_aux_wuc_power_ctrl ROM_AUXWUCPowerCtrl
|
||||
|
||||
/* FLASH API */
|
||||
#define ti_lib_rom_flash_power_mode_get ROM_FlashPowerModeGet
|
||||
#define ti_lib_rom_flash_protection_set ROM_FlashProtectionSet
|
||||
#define ti_lib_rom_flash_protection_get ROM_FlashProtectionGet
|
||||
#define ti_lib_rom_flash_protection_save ROM_FlashProtectionSave
|
||||
#define ti_lib_rom_flash_efuse_read_row ROM_FlashEfuseReadRow
|
||||
#define ti_lib_rom_flash_disable_sectors_for_write ROM_FlashDisableSectorsForWrite
|
||||
|
||||
/* I2C API */
|
||||
#define ti_lib_rom_i2c_master_init_exp_clk ROM_I2CMasterInitExpClk
|
||||
#define ti_lib_rom_i2c_master_err ROM_I2CMasterErr
|
||||
|
||||
/* INTERRUPT API */
|
||||
#define ti_lib_rom_int_priority_grouping_set ROM_IntPriorityGroupingSet
|
||||
#define ti_lib_rom_int_priority_grouping_get ROM_IntPriorityGroupingGet
|
||||
#define ti_lib_rom_int_priority_set ROM_IntPrioritySet
|
||||
#define ti_lib_rom_int_priority_get ROM_IntPriorityGet
|
||||
#define ti_lib_rom_int_enable ROM_IntEnable
|
||||
#define ti_lib_rom_int_disable ROM_IntDisable
|
||||
#define ti_lib_rom_int_pend_set ROM_IntPendSet
|
||||
#define ti_lib_rom_int_pend_get ROM_IntPendGet
|
||||
#define ti_lib_rom_int_pend_clear ROM_IntPendClear
|
||||
|
||||
/* IOC API */
|
||||
#define ti_lib_rom_ioc_port_configure_set ROM_IOCPortConfigureSet
|
||||
#if !defined(ThisLibraryIsFor_CC26x0R2_HaltIfViolated)
|
||||
#define ti_lib_rom_ioc_port_configure_get ROM_IOCPortConfigureGet
|
||||
#define ti_lib_rom_ioc_io_shutdown_set ROM_IOCIOShutdownSet
|
||||
#define ti_lib_rom_ioc_io_mode_set ROM_IOCIOModeSet
|
||||
#define ti_lib_rom_ioc_io_int_set ROM_IOCIOIntSet
|
||||
#define ti_lib_rom_ioc_io_port_pull_set ROM_IOCIOPortPullSet
|
||||
#define ti_lib_rom_ioc_io_hyst_set ROM_IOCIOHystSet
|
||||
#define ti_lib_rom_ioc_io_input_set ROM_IOCIOInputSet
|
||||
#define ti_lib_rom_ioc_io_slew_ctrl_set ROM_IOCIOSlewCtrlSet
|
||||
#define ti_lib_rom_ioc_io_drv_strength_set ROM_IOCIODrvStrengthSet
|
||||
#define ti_lib_rom_ioc_io_port_id_set ROM_IOCIOPortIdSet
|
||||
#define ti_lib_rom_ioc_int_enable ROM_IOCIntEnable
|
||||
#define ti_lib_rom_ioc_int_disable ROM_IOCIntDisable
|
||||
#define ti_lib_rom_ioc_pin_type_gpio_input ROM_IOCPinTypeGpioInput
|
||||
#define ti_lib_rom_ioc_pin_type_gpio_output ROM_IOCPinTypeGpioOutput
|
||||
#define ti_lib_rom_ioc_pin_type_uart ROM_IOCPinTypeUart
|
||||
#define ti_lib_rom_ioc_pin_type_ssi_master ROM_IOCPinTypeSsiMaster
|
||||
#define ti_lib_rom_ioc_pin_type_ssi_slave ROM_IOCPinTypeSsiSlave
|
||||
#define ti_lib_rom_ioc_pin_type_i2c ROM_IOCPinTypeI2c
|
||||
#define ti_lib_rom_ioc_pin_type_aux ROM_IOCPinTypeAux
|
||||
#endif
|
||||
|
||||
/* PRCM API */
|
||||
#define ti_lib_rom_prcm_inf_clock_configure_set ROM_PRCMInfClockConfigureSet
|
||||
#define ti_lib_rom_prcm_inf_clock_configure_get ROM_PRCMInfClockConfigureGet
|
||||
#define ti_lib_rom_prcm_audio_clock_config_set ROM_PRCMAudioClockConfigSet
|
||||
#define ti_lib_rom_prcm_power_domain_on ROM_PRCMPowerDomainOn
|
||||
#define ti_lib_rom_prcm_power_domain_off ROM_PRCMPowerDomainOff
|
||||
#define ti_lib_rom_prcm_peripheral_run_enable ROM_PRCMPeripheralRunEnable
|
||||
#define ti_lib_rom_prcm_peripheral_run_disable ROM_PRCMPeripheralRunDisable
|
||||
#define ti_lib_rom_prcm_peripheral_sleep_enable ROM_PRCMPeripheralSleepEnable
|
||||
#define ti_lib_rom_prcm_peripheral_sleep_disable ROM_PRCMPeripheralSleepDisable
|
||||
#define ti_lib_rom_prcm_peripheral_deep_sleep_enable ROM_PRCMPeripheralDeepSleepEnable
|
||||
#define ti_lib_rom_prcm_peripheral_deep_sleep_disable ROM_PRCMPeripheralDeepSleepDisable
|
||||
#define ti_lib_rom_prcm_power_domain_status ROM_PRCMPowerDomainStatus
|
||||
#define ti_lib_rom_prcm_deep_sleep ROM_PRCMDeepSleep
|
||||
|
||||
/* SMPH API */
|
||||
#define ti_lib_rom_smph_acquire ROM_SMPHAcquire
|
||||
|
||||
/* SSI API */
|
||||
#define ti_lib_rom_ssi_config_set_exp_clk ROM_SSIConfigSetExpClk
|
||||
#define ti_lib_rom_ssi_data_put ROM_SSIDataPut
|
||||
#define ti_lib_rom_ssi_data_put_non_blocking ROM_SSIDataPutNonBlocking
|
||||
#define ti_lib_rom_ssi_data_get ROM_SSIDataGet
|
||||
#define ti_lib_rom_ssi_data_get_non_blocking ROM_SSIDataGetNonBlocking
|
||||
|
||||
/* TIMER API */
|
||||
#define ti_lib_rom_timer_configure ROM_TimerConfigure
|
||||
#define ti_lib_rom_timer_level_control ROM_TimerLevelControl
|
||||
#define ti_lib_rom_timer_stall_control ROM_TimerStallControl
|
||||
#define ti_lib_rom_timer_wait_on_trigger_control ROM_TimerWaitOnTriggerControl
|
||||
|
||||
/* TRNG API */
|
||||
#define ti_lib_rom_trng_number_get ROM_TRNGNumberGet
|
||||
|
||||
/* UART API */
|
||||
#define ti_lib_rom_uart_fifo_level_get ROM_UARTFIFOLevelGet
|
||||
#define ti_lib_rom_uart_config_set_exp_clk ROM_UARTConfigSetExpClk
|
||||
#define ti_lib_rom_uart_config_get_exp_clk ROM_UARTConfigGetExpClk
|
||||
#define ti_lib_rom_uart_disable ROM_UARTDisable
|
||||
#define ti_lib_rom_uart_char_get_non_blocking ROM_UARTCharGetNonBlocking
|
||||
#define ti_lib_rom_uart_char_get ROM_UARTCharGet
|
||||
#define ti_lib_rom_uart_char_put_non_blocking ROM_UARTCharPutNonBlocking
|
||||
#define ti_lib_rom_uart_char_put ROM_UARTCharPut
|
||||
|
||||
/* UDMA API */
|
||||
#define ti_lib_rom_udma_channel_attribute_enable ROM_uDMAChannelAttributeEnable
|
||||
#define ti_lib_rom_udma_channel_attribute_disable ROM_uDMAChannelAttributeDisable
|
||||
#define ti_lib_rom_udma_channel_attribute_get ROM_uDMAChannelAttributeGet
|
||||
#define ti_lib_rom_udma_channel_control_set ROM_uDMAChannelControlSet
|
||||
#define ti_lib_rom_udma_channel_transfer_set ROM_uDMAChannelTransferSet
|
||||
#define ti_lib_rom_udma_channel_scatter_gather_set ROM_uDMAChannelScatterGatherSet
|
||||
#define ti_lib_rom_udma_channel_size_get ROM_uDMAChannelSizeGet
|
||||
#define ti_lib_rom_udma_channel_mode_get ROM_uDMAChannelModeGet
|
||||
|
||||
/* VIMS API */
|
||||
#define ti_lib_rom_vims_configure ROM_VIMSConfigure
|
||||
#define ti_lib_rom_vims_mode_set ROM_VIMSModeSet
|
||||
|
||||
/* HAPI */
|
||||
#define ti_lib_hapi_crc32(a, b, c) HapiCrc32(a, b, c)
|
||||
#define ti_lib_hapi_get_flash_size() HapiGetFlashSize()
|
||||
#define ti_lib_hapi_get_chip_id() HapiGetChipId()
|
||||
#define ti_lib_hapi_sector_erase(a) HapiSectorErase(a)
|
||||
#define ti_lib_hapi_program_flash(a, b, c) HapiProgramFlash(a, b, c)
|
||||
#define ti_lib_hapi_reset_device() HapiResetDevice()
|
||||
#define ti_lib_hapi_fletcher32(a, b, c) HapiFletcher32(a, b, c)
|
||||
#define ti_lib_hapi_min_value(a, b) HapiMinValue(a,b)
|
||||
#define ti_lib_hapi_max_value(a, b) HapiMaxValue(a,b)
|
||||
#define ti_lib_hapi_mean_value(a, b) HapiMeanValue(a,b)
|
||||
#define ti_lib_hapi_stand_deviation_value(a, b) HapiStandDeviationValue(a,b)
|
||||
#define ti_lib_hapi_hf_source_safe_switch() HapiHFSourceSafeSwitch()
|
||||
#define ti_lib_hapi_select_comp_a_input(a) HapiSelectCompAInput(a)
|
||||
#define ti_lib_hapi_select_comp_a_ref(a) HapiSelectCompARef(a)
|
||||
#define ti_lib_hapi_select_adc_comp_b_input(a) HapiSelectADCCompBInput(a)
|
||||
#define ti_lib_hapi_select_comp_b_ref(a) HapiSelectCompBRef(a)
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#endif /* TI_LIB_ROM_H_ */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
@ -52,9 +52,6 @@
|
||||
#ifndef TI_LIB_H_
|
||||
#define TI_LIB_H_
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Include ROM API */
|
||||
#include "ti-lib-rom.h"
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* aon_batmon.h */
|
||||
#include "driverlib/aon_batmon.h"
|
||||
|
||||
@ -200,14 +197,16 @@
|
||||
#define ti_lib_chipinfo_get_device_id_hw_rev_code(...) ChipInfo_GetDeviceIdHwRevCode(__VA_ARGS__)
|
||||
#define ti_lib_chipinfo_get_chip_type(...) ChipInfo_GetChipType(__VA_ARGS__)
|
||||
#define ti_lib_chipinfo_get_chip_family(...) ChipInfo_GetChipFamily(__VA_ARGS__)
|
||||
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
|
||||
|
||||
#if CPU_FAMILY_CC26X0R2
|
||||
#define ti_lib_chipinfo_chip_family_is_cc26xx(...) ChipInfo_ChipFamilyIs_CC26x0(__VA_ARGS__)
|
||||
#define ti_lib_chipinfo_chip_family_is_cc13xx(...) ChipInfo_ChipFamilyIs_CC13x0(__VA_ARGS__)
|
||||
#define ti_lib_chipinfo_chip_family_is_cc26x0r2(...) ChipInfo_ChipFamilyIs_CC26x0R2(__VA_ARGS__)
|
||||
#else
|
||||
#define ti_lib_chipinfo_chip_family_is_cc26xx(...) ChipInfo_ChipFamilyIsCC26xx(__VA_ARGS__)
|
||||
#define ti_lib_chipinfo_chip_family_is_cc13xx(...) ChipInfo_ChipFamilyIsCC13xx(__VA_ARGS__)
|
||||
#endif
|
||||
#endif /* CPU_FAMILY_CC26X0R2 */
|
||||
|
||||
#define ti_lib_chipinfo_get_hw_revision(...) ChipInfo_GetHwRevision(__VA_ARGS__)
|
||||
#define ti_lib_chipinfo_hw_revision_is_1_0(...) ChipInfo_HwRevisionIs_1_0(__VA_ARGS__)
|
||||
#define ti_lib_chipinfo_hw_revision_is_gteq_2_0(...) ChipInfo_HwRevisionIs_GTEQ_2_0(__VA_ARGS__)
|
||||
@ -394,10 +393,6 @@
|
||||
#define ti_lib_pwr_ctrl_source_get(...) PowerCtrlSourceGet(__VA_ARGS__)
|
||||
#define ti_lib_pwr_ctrl_reset_source_get(...) PowerCtrlResetSourceGet(__VA_ARGS__)
|
||||
#define ti_lib_pwr_ctrl_reset_source_clear(...) PowerCtrlResetSourceClear(__VA_ARGS__)
|
||||
#if !defined(ThisLibraryIsFor_CC26x0R2_HaltIfViolated)
|
||||
#define ti_lib_pwr_ctrl_io_freeze_enable(...) PowerCtrlIOFreezeEnable(__VA_ARGS__)
|
||||
#define ti_lib_pwr_ctrl_io_freeze_disable(...) PowerCtrlIOFreezeDisable(__VA_ARGS__)
|
||||
#endif
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* rfc.h */
|
||||
#include "driverlib/rfc.h"
|
||||
@ -416,7 +411,14 @@
|
||||
#define ti_lib_sys_ctrl_aon_sync(...) SysCtrlAonSync(__VA_ARGS__)
|
||||
#define ti_lib_sys_ctrl_aon_update(...) SysCtrlAonUpdate(__VA_ARGS__)
|
||||
#define ti_lib_sys_ctrl_set_recharge_before_power_down(...) SysCtrlSetRechargeBeforePowerDown(__VA_ARGS__)
|
||||
#define ti_lib_sys_ctrl_adjust_recharge_after_power_down(...) SysCtrlAdjustRechargeAfterPowerDown(__VA_ARGS__)
|
||||
|
||||
#if CPU_FAMILY_CC26X0R2
|
||||
/* May need to change to XOSC_IN_LOW_POWER_MODE */
|
||||
#define ti_lib_sys_ctrl_adjust_recharge_after_power_down() SysCtrlAdjustRechargeAfterPowerDown(XOSC_IN_HIGH_POWER_MODE)
|
||||
#else
|
||||
#define ti_lib_sys_ctrl_adjust_recharge_after_power_down() SysCtrlAdjustRechargeAfterPowerDown()
|
||||
#endif /* CPU_FAMILY_CC26X0R2 */
|
||||
|
||||
#define ti_lib_sys_ctrl_dcdc_voltage_conditional_control(...) SysCtrl_DCDC_VoltageConditionalControl(__VA_ARGS__)
|
||||
#define ti_lib_sys_ctrl_reset_source_get(...) SysCtrlResetSourceGet(__VA_ARGS__)
|
||||
#define ti_lib_sys_ctrl_system_reset(...) SysCtrlSystemReset(__VA_ARGS__)
|
||||
|
@ -63,9 +63,9 @@ LPM_MODULE(rf_switch_module, NULL, shutdown_handler, NULL, LPM_DOMAIN_NONE);
|
||||
void
|
||||
rf_switch_init()
|
||||
{
|
||||
ti_lib_rom_ioc_pin_type_gpio_output(POWER_PIN);
|
||||
ti_lib_ioc_pin_type_gpio_output(POWER_PIN);
|
||||
ti_lib_gpio_clear_dio(POWER_PIN);
|
||||
ti_lib_rom_ioc_pin_type_gpio_output(SELECT_PIN);
|
||||
ti_lib_ioc_pin_type_gpio_output(SELECT_PIN);
|
||||
ti_lib_gpio_clear_dio(SELECT_PIN);
|
||||
|
||||
lpm_register_module(&rf_switch_module);
|
||||
|
@ -158,11 +158,11 @@ platform_init_stage_one()
|
||||
* latches in the first place. Before doing these things though, we should
|
||||
* allow software to first regain control of pins
|
||||
*/
|
||||
#if !defined(ThisLibraryIsFor_CC26x0R2_HaltIfViolated)
|
||||
ti_lib_pwr_ctrl_io_freeze_disable();
|
||||
ti_lib_aon_ioc_freeze_disable();
|
||||
HWREG(AON_SYSCTL_BASE + AON_SYSCTL_O_SLEEPCTL) = 1;
|
||||
ti_lib_sys_ctrl_aon_sync();
|
||||
|
||||
#endif
|
||||
ti_lib_rom_int_enable(INT_AON_GPIO_EDGE);
|
||||
ti_lib_int_enable(INT_AON_GPIO_EDGE);
|
||||
ti_lib_int_master_enable();
|
||||
|
||||
soc_rtc_init();
|
||||
|
@ -601,11 +601,11 @@ configure(int type, int enable)
|
||||
{
|
||||
switch(type) {
|
||||
case SENSORS_HW_INIT:
|
||||
ti_lib_rom_ioc_pin_type_gpio_input(BOARD_IOID_MPU_INT);
|
||||
ti_lib_ioc_pin_type_gpio_input(BOARD_IOID_MPU_INT);
|
||||
ti_lib_ioc_io_port_pull_set(BOARD_IOID_MPU_INT, IOC_IOPULL_DOWN);
|
||||
ti_lib_ioc_io_hyst_set(BOARD_IOID_MPU_INT, IOC_HYST_ENABLE);
|
||||
|
||||
ti_lib_rom_ioc_pin_type_gpio_output(BOARD_IOID_MPU_POWER);
|
||||
ti_lib_ioc_pin_type_gpio_output(BOARD_IOID_MPU_POWER);
|
||||
ti_lib_ioc_io_drv_strength_set(BOARD_IOID_MPU_POWER, IOC_CURRENT_4MA,
|
||||
IOC_STRENGTH_MAX);
|
||||
ti_lib_gpio_clear_dio(BOARD_IOID_MPU_POWER);
|
||||
|
@ -59,10 +59,10 @@ config(int type, int enable)
|
||||
ti_lib_ioc_pin_type_gpio_output(BOARD_IOID_ALS_PWR);
|
||||
break;
|
||||
case SENSORS_ACTIVE:
|
||||
ti_lib_rom_ioc_pin_type_gpio_output(BOARD_IOID_ALS_PWR);
|
||||
ti_lib_rom_ioc_port_configure_set(BOARD_IOID_ALS_OUT, IOC_PORT_GPIO,
|
||||
ti_lib_ioc_pin_type_gpio_output(BOARD_IOID_ALS_PWR);
|
||||
ti_lib_ioc_port_configure_set(BOARD_IOID_ALS_OUT, IOC_PORT_GPIO,
|
||||
IOC_STD_OUTPUT);
|
||||
ti_lib_rom_ioc_pin_type_gpio_input(BOARD_IOID_ALS_OUT);
|
||||
ti_lib_ioc_pin_type_gpio_input(BOARD_IOID_ALS_OUT);
|
||||
|
||||
if(enable) {
|
||||
ti_lib_gpio_set_dio(BOARD_IOID_ALS_PWR);
|
||||
|
@ -119,7 +119,7 @@
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Default configuration values */
|
||||
#define CC26XX_WEB_DEMO_DEFAULT_ORG_ID "quickstart"
|
||||
#if CPU_FAMILY_CC13XX
|
||||
#if CPU_FAMILY_CC13X0
|
||||
#define CC26XX_WEB_DEMO_DEFAULT_TYPE_ID "cc13xx"
|
||||
#else
|
||||
#define CC26XX_WEB_DEMO_DEFAULT_TYPE_ID "cc26xx"
|
||||
|
Loading…
Reference in New Issue
Block a user