Initial commit

This commit is contained in:
Thomas Klaehn
2019-10-09 13:45:38 +02:00
commit 2461dbfb92
117 changed files with 68364 additions and 0 deletions

229
common/button_if.c Normal file
View File

@@ -0,0 +1,229 @@
//*****************************************************************************
// button_if.c
//
// CC3200 Launchpad button interface APIs
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#include <stdlib.h>
#include "hw_types.h"
#include "hw_ints.h"
#include "rom.h"
#include "rom_map.h"
#include "gpio.h"
#include "interrupt.h"
#include "pin.h"
#include "hw_memmap.h"
#ifdef SL_PLATFORM_MULTI_THREADED /* If OS-based application */
#include "osi.h"
#endif
#include "button_if.h"
P_INT_HANDLER g_S2InterruptHdl;
P_INT_HANDLER g_S3InterruptHdl;
//*****************************************************************************
//
//! GPIO Interrupt Handler for S3 button
//!
//! \param None
//!
//! \return None
//
//*****************************************************************************
void GPIOs3IntHandler()
{
unsigned long ulPinState = GPIOIntStatus(GPIOA1_BASE,1);
if(ulPinState & GPIO_PIN_5)
{
Button_IF_DisableInterrupt(SW3);
g_S3InterruptHdl();
}
}
//*****************************************************************************
//
//! GPIO Interrupt Handler for S2 button
//!
//! \param None
//!
//! \return None
//
//*****************************************************************************
void GPIOs2IntHandler()
{
unsigned long ulPinState = GPIOIntStatus(GPIOA2_BASE,1);
if(ulPinState & GPIO_PIN_6)
{
Button_IF_DisableInterrupt(SW2);
g_S2InterruptHdl();
}
}
//*****************************************************************************
//
//! \brief Initialize Push Button GPIO
//!
//! \param[in] S2InterruptHdl GPIO Interrupt Handler for SW2 LP button
//! \param[in] S3InterruptHdl GPIO Interrupt Handler for SW3 LP button
//!
//! \return none
//!
//! \brief Initializes Push Button Ports and Pins
//
//*****************************************************************************
void Button_IF_Init(P_INT_HANDLER S2InterruptHdl,P_INT_HANDLER S3InterruptHdl )
{
if(S3InterruptHdl != NULL)
{
//
// Set Interrupt Type for GPIO
//
MAP_GPIOIntTypeSet(GPIOA1_BASE,GPIO_PIN_5,GPIO_FALLING_EDGE);
g_S3InterruptHdl = S3InterruptHdl;
//
// Register Interrupt handler
//
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
osi_InterruptRegister(INT_GPIOA1,(P_OSI_INTR_ENTRY)GPIOs3IntHandler, \
INT_PRIORITY_LVL_1);
#else
MAP_IntPrioritySet(INT_GPIOA1, INT_PRIORITY_LVL_1);
MAP_GPIOIntRegister(GPIOA1_BASE, GPIOs3IntHandler);
#endif
//
// Enable Interrupt
//
MAP_GPIOIntClear(GPIOA1_BASE,GPIO_PIN_5);
MAP_GPIOIntEnable(GPIOA1_BASE,GPIO_INT_PIN_5);
}
if(S2InterruptHdl != NULL)
{
//
// Set Interrupt Type for GPIO
//
MAP_GPIOIntTypeSet(GPIOA2_BASE,GPIO_PIN_6,GPIO_FALLING_EDGE);
g_S2InterruptHdl = S2InterruptHdl;
//
// Register Interrupt handler
//
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
osi_InterruptRegister(INT_GPIOA2,(P_OSI_INTR_ENTRY)GPIOs2IntHandler, \
INT_PRIORITY_LVL_1);
#else
MAP_IntPrioritySet(INT_GPIOA2, INT_PRIORITY_LVL_1);
MAP_GPIOIntRegister(GPIOA2_BASE, GPIOs2IntHandler);
#endif
//
// Enable Interrupt
//
MAP_GPIOIntClear(GPIOA2_BASE,GPIO_PIN_6);
MAP_GPIOIntEnable(GPIOA2_BASE,GPIO_INT_PIN_6);
}
}
//*****************************************************************************
//
//! \brief Enables Push Button GPIO Interrupt
//!
//! \param[in] ucSwitch Push Button Swich Enum - SW2,SW3
//!
//! \return none
//!
//
//*****************************************************************************
void Button_IF_EnableInterrupt(unsigned char ucSwitch)
{
if(ucSwitch & SW2)
{
//Enable GPIO Interrupt
MAP_GPIOIntClear(GPIOA2_BASE,GPIO_PIN_6);
MAP_IntPendClear(INT_GPIOA2);
MAP_IntEnable(INT_GPIOA2);
MAP_GPIOIntEnable(GPIOA2_BASE,GPIO_PIN_6);
}
if(ucSwitch & SW3)
{
//Enable GPIO Interrupt
MAP_GPIOIntClear(GPIOA1_BASE,GPIO_PIN_5);
MAP_IntPendClear(INT_GPIOA1);
MAP_IntEnable(INT_GPIOA1);
MAP_GPIOIntEnable(GPIOA1_BASE,GPIO_PIN_5);
}
}
//*****************************************************************************
//
//! \brief Disables Push Button GPIO Interrupt
//!
//! \param[in] ucSwitch Push Button Swich Enum - SW2,SW3
//!
//! \return none
//!
//
//*****************************************************************************
void Button_IF_DisableInterrupt(unsigned char ucSwitch)
{
if(ucSwitch & SW2)
{
//Clear and Disable GPIO Interrupt
MAP_GPIOIntDisable(GPIOA2_BASE,GPIO_PIN_6);
MAP_GPIOIntClear(GPIOA2_BASE,GPIO_PIN_6);
MAP_IntDisable(INT_GPIOA2);
}
if(ucSwitch & SW3)
{
//Clear and Disable GPIO Interrupt
MAP_GPIOIntDisable(GPIOA1_BASE,GPIO_PIN_5);
MAP_GPIOIntClear(GPIOA1_BASE,GPIO_PIN_5);
MAP_IntDisable(INT_GPIOA1);
}
}

79
common/button_if.h Normal file
View File

@@ -0,0 +1,79 @@
//*****************************************************************************
// button_if.h
//
// CC3200 Launchpad button interface function prototypes
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#ifndef __BUTTONIF_H__
#define __BUTTONIF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
typedef enum
{
NO_SW,
SW1 = 0x1, /* SW1/Reset Button */
SW2 = 0x2, /* SW2/GP22/Pin15 */
SW3 = 0x4 /* SW3/GP13/Pin4 */
}eSwNum;
typedef void (*P_INT_HANDLER)(void);
void GPIOs2IntHandler();
void GPIOs3IntHandler();
void Button_IF_Init(P_INT_HANDLER S2InterruptHdl,P_INT_HANDLER S1InterruptHdl );
void Button_IF_EnableInterrupt(unsigned char ucSwitch);
void Button_IF_DisableInterrupt(unsigned char ucSwitch);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __GPIOIF_H__

165
common/common.h Normal file
View File

@@ -0,0 +1,165 @@
//*****************************************************************************
// common.h
//
// Contains the common macro/enum definitions used by different networking apps
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#ifndef __COMMON__H__
#define __COMMON__H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//
// Values for below macros shall be modified as per access-point(AP) properties
// SimpleLink device will connect to following AP when application is executed
//
#define SSID_NAME "cc3200demo" /* AP SSID */
#define SECURITY_TYPE SL_SEC_TYPE_OPEN/* Security type (OPEN or WEP or WPA*/
#define SECURITY_KEY "" /* Password of the secured AP */
#define SSID_LEN_MAX 32
#define BSSID_LEN_MAX 6
#ifdef NOTERM
#define UART_PRINT(x,...)
#define DBG_PRINT(x,...)
#define ERR_PRINT(x)
#else
#define UART_PRINT Report
#define DBG_PRINT Report
#define ERR_PRINT(x) Report("Error [%d] at line [%d] in function [%s] \n\r",x,__LINE__,__FUNCTION__)
#endif
// Loop forever, user can change it as per application's requirement
#define LOOP_FOREVER() \
{\
while(1); \
}
// check the error code and handle it
#define ASSERT_ON_ERROR(error_code)\
{\
if(error_code < 0) \
{\
ERR_PRINT(error_code);\
return error_code;\
}\
}
#define SPAWN_TASK_PRIORITY 9
#define SL_STOP_TIMEOUT 200
#define UNUSED(x) ((x) = (x))
#define SUCCESS 0
#define FAILURE -1
// Status bits - These are used to set/reset the corresponding bits in
// given variable
typedef enum{
STATUS_BIT_NWP_INIT = 0, // If this bit is set: Network Processor is
// powered up
STATUS_BIT_CONNECTION, // If this bit is set: the device is connected to
// the AP or client is connected to device (AP)
STATUS_BIT_IP_LEASED, // If this bit is set: the device has leased IP to
// any connected client
STATUS_BIT_IP_AQUIRED, // If this bit is set: the device has acquired an IP
STATUS_BIT_SMARTCONFIG_START, // If this bit is set: the SmartConfiguration
// process is started from SmartConfig app
STATUS_BIT_P2P_DEV_FOUND, // If this bit is set: the device (P2P mode)
// found any p2p-device in scan
STATUS_BIT_P2P_REQ_RECEIVED, // If this bit is set: the device (P2P mode)
// found any p2p-negotiation request
STATUS_BIT_CONNECTION_FAILED, // If this bit is set: the device(P2P mode)
// connection to client(or reverse way) is failed
STATUS_BIT_PING_DONE // If this bit is set: the device has completed
// the ping operation
}e_StatusBits;
#define CLR_STATUS_BIT_ALL(status_variable) (status_variable = 0)
#define SET_STATUS_BIT(status_variable, bit) status_variable |= (1<<(bit))
#define CLR_STATUS_BIT(status_variable, bit) status_variable &= ~(1<<(bit))
#define CLR_STATUS_BIT_ALL(status_variable) (status_variable = 0)
#define GET_STATUS_BIT(status_variable, bit) (0 != (status_variable & (1<<(bit))))
#define IS_NW_PROCSR_ON(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_NWP_INIT)
#define IS_CONNECTED(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_CONNECTION)
#define IS_IP_LEASED(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_IP_LEASED)
#define IS_IP_ACQUIRED(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_IP_AQUIRED)
#define IS_SMART_CFG_START(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_SMARTCONFIG_START)
#define IS_P2P_DEV_FOUND(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_P2P_DEV_FOUND)
#define IS_P2P_REQ_RCVD(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_P2P_REQ_RECEIVED)
#define IS_CONNECT_FAILED(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_CONNECTION_FAILED)
#define IS_PING_DONE(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_PING_DONE)
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif //__COMMON__H__

474
common/gpio_if.c Normal file
View File

@@ -0,0 +1,474 @@
//*****************************************************************************
// gpio_if.c
//
// GPIO interface APIs, this common interface file helps to configure,
// set/toggle only 3 GPIO pins which are connected to 3 LEDs of CC32xx Launchpad
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
// Standard includes
#include <stdio.h>
// Driverlib includes
#include "hw_types.h"
#include "hw_ints.h"
#include "hw_memmap.h"
#include "hw_apps_rcm.h"
#include "interrupt.h"
#include "pin.h"
#include "gpio.h"
#include "prcm.h"
#include "rom.h"
#include "rom_map.h"
// OS includes
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
#include <stdlib.h>
#include "osi.h"
#endif
// Common interface include
#include "gpio_if.h"
//****************************************************************************
// GLOBAL VARIABLES
//****************************************************************************
static unsigned long ulReg[]=
{
GPIOA0_BASE,
GPIOA1_BASE,
GPIOA2_BASE,
GPIOA3_BASE,
GPIOA4_BASE
};
//*****************************************************************************
// Variables to store TIMER Port,Pin values
//*****************************************************************************
unsigned int g_uiLED1Port = 0,g_uiLED2Port = 0,g_uiLED3Port = 0;
unsigned char g_ucLED1Pin,g_ucLED2Pin,g_ucLED3Pin;
#define GPIO_LED1 9
#define GPIO_LED2 10
#define GPIO_LED3 11
//****************************************************************************
// LOCAL FUNCTION DEFINITIONS
//****************************************************************************
static unsigned char
GetPeripheralIntNum(unsigned int uiGPIOPort)
{
switch(uiGPIOPort)
{
case GPIOA0_BASE:
return INT_GPIOA0;
case GPIOA1_BASE:
return INT_GPIOA1;
case GPIOA2_BASE:
return INT_GPIOA2;
case GPIOA3_BASE:
return INT_GPIOA3;
default:
return INT_GPIOA0;
}
}
//*****************************************************************************
//
//! GPIO Enable & Configuration
//!
//! \param ucPins is the bit-pack representation of 3 LEDs
//! LSB:GP09-GP10-GP11:MSB
//!
//! \return None
//
//*****************************************************************************
void
GPIO_IF_LedConfigure(unsigned char ucPins)
{
if(ucPins & LED1)
{
GPIO_IF_GetPortNPin(GPIO_LED1,
&g_uiLED1Port,
&g_ucLED1Pin);
}
if(ucPins & LED2)
{
GPIO_IF_GetPortNPin(GPIO_LED2,
&g_uiLED2Port,
&g_ucLED2Pin);
}
if(ucPins & LED3)
{
GPIO_IF_GetPortNPin(GPIO_LED3,
&g_uiLED3Port,
&g_ucLED3Pin);
}
}
//*****************************************************************************
//
//! Turn LED On
//!
//! \param ledNum is the LED Number
//!
//! \return none
//!
//! \brief Turns a specific LED Off
//
//*****************************************************************************
void
GPIO_IF_LedOn(char ledNum)
{
switch(ledNum)
{
case MCU_ON_IND:
case MCU_EXECUTE_SUCCESS_IND:
case MCU_GREEN_LED_GPIO:
{
/* Switch ON GREEN LED */
GPIO_IF_Set(GPIO_LED3, g_uiLED3Port, g_ucLED3Pin, 1);
break;
}
case MCU_SENDING_DATA_IND:
case MCU_EXECUTE_FAIL_IND:
case MCU_ORANGE_LED_GPIO:
{
/* Switch ON ORANGE LED */
GPIO_IF_Set(GPIO_LED2, g_uiLED2Port, g_ucLED2Pin, 1);
break;
}
case MCU_ASSOCIATED_IND:
case MCU_IP_ALLOC_IND:
case MCU_SERVER_INIT_IND:
case MCU_CLIENT_CONNECTED_IND:
case MCU_RED_LED_GPIO:
{
/* Switch ON RED LED */
GPIO_IF_Set(GPIO_LED1, g_uiLED1Port, g_ucLED1Pin, 1);
break;
}
case MCU_ALL_LED_IND:
{
/* Switch ON ALL LEDs LED */
GPIO_IF_Set(GPIO_LED3, g_uiLED3Port, g_ucLED3Pin, 1);
GPIO_IF_Set(GPIO_LED2, g_uiLED2Port, g_ucLED2Pin, 1);
GPIO_IF_Set(GPIO_LED1, g_uiLED1Port, g_ucLED1Pin, 1);
break;
}
default:
break;
}
}
//*****************************************************************************
//
//! Turn LED Off
//!
//! \param ledNum is the LED Number
//!
//! \return none
//!
//! \brief Turns a specific LED Off
//
//*****************************************************************************
void
GPIO_IF_LedOff(char ledNum)
{
switch(ledNum)
{
case MCU_ON_IND:
case MCU_EXECUTE_SUCCESS_IND:
case MCU_GREEN_LED_GPIO:
{
/* Switch OFF GREEN LED */
GPIO_IF_Set(GPIO_LED3, g_uiLED3Port, g_ucLED3Pin, 0);
break;
}
case MCU_SENDING_DATA_IND:
case MCU_EXECUTE_FAIL_IND:
case MCU_ORANGE_LED_GPIO:
{
/* Switch OFF ORANGE LED */
GPIO_IF_Set(GPIO_LED2, g_uiLED2Port, g_ucLED2Pin, 0);
break;
}
case MCU_ASSOCIATED_IND:
case MCU_IP_ALLOC_IND:
case MCU_SERVER_INIT_IND:
case MCU_CLIENT_CONNECTED_IND:
case MCU_RED_LED_GPIO:
{
/* Switch OFF RED LED */
GPIO_IF_Set(GPIO_LED1, g_uiLED1Port, g_ucLED1Pin, 0);
break;
}
case MCU_ALL_LED_IND:
{
/* Switch OFF ALL LEDs LED */
GPIO_IF_Set(GPIO_LED3, g_uiLED3Port, g_ucLED3Pin, 0);
GPIO_IF_Set(GPIO_LED2, g_uiLED2Port, g_ucLED2Pin, 0);
GPIO_IF_Set(GPIO_LED1, g_uiLED1Port, g_ucLED1Pin, 0);
break;
}
default:
break;
}
}
//*****************************************************************************
//
//! \brief This function returns LED current Status
//!
//! \param[in] ucGPIONum is the GPIO to which the LED is connected
//! MCU_GREEN_LED_GPIO\MCU_ORANGE_LED_GPIO\MCU_RED_LED_GPIO
//!
//!
//! \return 1: LED ON, 0: LED OFF
//
//*****************************************************************************
unsigned char
GPIO_IF_LedStatus(unsigned char ucGPIONum)
{
unsigned char ucLEDStatus;
switch(ucGPIONum)
{
case MCU_GREEN_LED_GPIO:
{
ucLEDStatus = GPIO_IF_Get(ucGPIONum, g_uiLED3Port, g_ucLED3Pin);
break;
}
case MCU_ORANGE_LED_GPIO:
{
ucLEDStatus = GPIO_IF_Get(ucGPIONum, g_uiLED2Port, g_ucLED2Pin);
break;
}
case MCU_RED_LED_GPIO:
{
ucLEDStatus = GPIO_IF_Get(ucGPIONum, g_uiLED1Port, g_ucLED1Pin);
break;
}
default:
ucLEDStatus = 0;
}
return ucLEDStatus;
}
//*****************************************************************************
//
//! Toggle the Led state
//!
//! \param ledNum is the LED Number
//!
//! \return none
//!
//! \brief Toggles a board LED
//
//*****************************************************************************
void GPIO_IF_LedToggle(unsigned char ucLedNum)
{
unsigned char ucLEDStatus = GPIO_IF_LedStatus(ucLedNum);
if(ucLEDStatus == 1)
{
GPIO_IF_LedOff(ucLedNum);
}
else
{
GPIO_IF_LedOn(ucLedNum);
}
}
//****************************************************************************
//
//! Get the port and pin of a given GPIO
//!
//! \param ucPin is the pin to be set-up as a GPIO (0:39)
//! \param puiGPIOPort is the pointer to store GPIO port address return value
//! \param pucGPIOPin is the pointer to store GPIO pin return value
//!
//! This function
//! 1. Return the GPIO port address and pin for a given external pin number
//!
//! \return None.
//
//****************************************************************************
void
GPIO_IF_GetPortNPin(unsigned char ucPin,
unsigned int *puiGPIOPort,
unsigned char *pucGPIOPin)
{
//
// Get the GPIO pin from the external Pin number
//
*pucGPIOPin = 1 << (ucPin % 8);
//
// Get the GPIO port from the external Pin number
//
*puiGPIOPort = (ucPin / 8);
*puiGPIOPort = ulReg[*puiGPIOPort];
}
//****************************************************************************
//
//! Configures the GPIO selected as input to generate interrupt on activity
//!
//! \param uiGPIOPort is the GPIO port address
//! \param ucGPIOPin is the GPIO pin of the specified port
//! \param uiIntType is the type of the interrupt (refer gpio.h)
//! \param pfnIntHandler is the interrupt handler to register
//!
//! This function
//! 1. Sets GPIO interrupt type
//! 2. Registers Interrupt handler
//! 3. Enables Interrupt
//!
//! \return None
//
//****************************************************************************
void
GPIO_IF_ConfigureNIntEnable(unsigned int uiGPIOPort,
unsigned char ucGPIOPin,
unsigned int uiIntType,
void (*pfnIntHandler)(void))
{
//
// Set GPIO interrupt type
//
MAP_GPIOIntTypeSet(uiGPIOPort,ucGPIOPin,uiIntType);
//
// Register Interrupt handler
//
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
osi_InterruptRegister(GetPeripheralIntNum(uiGPIOPort),
pfnIntHandler, INT_PRIORITY_LVL_1);
#else
MAP_IntPrioritySet(GetPeripheralIntNum(uiGPIOPort), INT_PRIORITY_LVL_1);
MAP_GPIOIntRegister(uiGPIOPort,pfnIntHandler);
#endif
//
// Enable Interrupt
//
MAP_GPIOIntClear(uiGPIOPort,ucGPIOPin);
MAP_GPIOIntEnable(uiGPIOPort,ucGPIOPin);
}
//****************************************************************************
//
//! Set a value to the specified GPIO pin
//!
//! \param ucPin is the GPIO pin to be set (0:39)
//! \param uiGPIOPort is the GPIO port address
//! \param ucGPIOPin is the GPIO pin of the specified port
//! \param ucGPIOValue is the value to be set
//!
//! This function
//! 1. Sets a value to the specified GPIO pin
//!
//! \return None.
//
//****************************************************************************
void
GPIO_IF_Set(unsigned char ucPin,
unsigned int uiGPIOPort,
unsigned char ucGPIOPin,
unsigned char ucGPIOValue)
{
//
// Set the corresponding bit in the bitmask
//
ucGPIOValue = ucGPIOValue << (ucPin % 8);
//
// Invoke the API to set the value
//
MAP_GPIOPinWrite(uiGPIOPort,ucGPIOPin,ucGPIOValue);
}
//****************************************************************************
//
//! Set a value to the specified GPIO pin
//!
//! \param ucPin is the GPIO pin to be set (0:39)
//! \param uiGPIOPort is the GPIO port address
//! \param ucGPIOPin is the GPIO pin of the specified port
//!
//! This function
//! 1. Gets a value of the specified GPIO pin
//!
//! \return value of the GPIO pin
//
//****************************************************************************
unsigned char
GPIO_IF_Get(unsigned char ucPin,
unsigned int uiGPIOPort,
unsigned char ucGPIOPin)
{
unsigned char ucGPIOValue;
long lGPIOStatus;
//
// Invoke the API to Get the value
//
lGPIOStatus = MAP_GPIOPinRead(uiGPIOPort,ucGPIOPin);
//
// Set the corresponding bit in the bitmask
//
ucGPIOValue = lGPIOStatus >> (ucPin % 8);
return ucGPIOValue;
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

115
common/gpio_if.h Normal file
View File

@@ -0,0 +1,115 @@
//*****************************************************************************
// gpio_if.h
//
// Defines and Macros for the GPIO interface.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#ifndef __GPIOIF_H__
#define __GPIOIF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
typedef enum
{
NO_LED,
LED1 = 0x1, /* RED LED D7/GP9/Pin64 */
LED2 = 0x2, /* ORANGE LED D6/GP10/Pin1 */
LED3 = 0x4 /* GREEN LED D5/GP11/Pin2 */
} ledEnum;
typedef enum
{
NO_LED_IND = NO_LED,
MCU_SENDING_DATA_IND = LED1,
MCU_ASSOCIATED_IND, /* Device associated to an AP */
MCU_IP_ALLOC_IND, /* Device acquired an IP */
MCU_SERVER_INIT_IND, /* Device connected to remote server */
MCU_CLIENT_CONNECTED_IND, /* Any client connects to device */
MCU_ON_IND, /* Device SLHost invoked successfully */
MCU_EXECUTE_SUCCESS_IND, /* Task executed sucessfully */
MCU_EXECUTE_FAIL_IND, /* Task execution failed */
MCU_RED_LED_GPIO, /* GP09 for LED RED as per LP 3.0 */
MCU_ORANGE_LED_GPIO,/* GP10 for LED ORANGE as per LP 3.0 */
MCU_GREEN_LED_GPIO, /* GP11 for LED GREEN as per LP 3.0 */
MCU_ALL_LED_IND
} ledNames;
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void GPIO_IF_GetPortNPin(unsigned char ucPin,
unsigned int *puiGPIOPort,
unsigned char *pucGPIOPin);
extern void GPIO_IF_ConfigureNIntEnable(unsigned int uiGPIOPort,
unsigned char ucGPIOPin,
unsigned int uiIntType,
void (*pfnIntHandler)(void));
extern void GPIO_IF_Set(unsigned char ucPin,
unsigned int uiGPIOPort,
unsigned char ucGPIOPin,
unsigned char ucGPIOValue);
extern unsigned char GPIO_IF_Get(unsigned char ucPin,
unsigned int uiGPIOPort,
unsigned char ucGPIOPin);
extern void GPIO_IF_LedConfigure(unsigned char ucPins);
extern void GPIO_IF_LedOn(char ledNum);
extern void GPIO_IF_LedOff(char ledNum);
extern unsigned char GPIO_IF_LedStatus(unsigned char ucGPIONum);
extern void GPIO_IF_LedToggle(unsigned char ucLedNum);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __GPIOIF_H__

434
common/i2c_if.c Normal file
View File

@@ -0,0 +1,434 @@
//*****************************************************************************
// i2c_if.c
//
// I2C interface APIs. Operates in a polled mode.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
// Standard includes
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
// Driverlib includes
#include "hw_types.h"
#include "hw_memmap.h"
#include "hw_ints.h"
#include "hw_i2c.h"
#include "i2c.h"
#include "pin.h"
#include "rom.h"
#include "rom_map.h"
#include "prcm.h"
// Common interface include
#include "i2c_if.h"
//*****************************************************************************
// MACRO DEFINITIONS
//*****************************************************************************
#define I2C_BASE I2CA0_BASE
#define SYS_CLK 80000000
#define FAILURE -1
#define SUCCESS 0
#define RETERR_IF_TRUE(condition) {if(condition) return FAILURE;}
#define RET_IF_ERR(Func) {int iRetVal = (Func); \
if (SUCCESS != iRetVal) \
return iRetVal;}
//****************************************************************************
// LOCAL FUNCTION DEFINITIONS
//****************************************************************************
static int I2CTransact(unsigned long ulCmd);
//****************************************************************************
//
//! Invokes the transaction over I2C
//!
//! \param ulCmd is the command to be executed over I2C
//!
//! This function works in a polling mode,
//! 1. Initiates the transfer of the command.
//! 2. Waits for the I2C transaction completion
//! 3. Check for any error in transaction
//! 4. Clears the master interrupt
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
static int
I2CTransact(unsigned long ulCmd)
{
//
// Clear all interrupts
//
MAP_I2CMasterIntClearEx(I2C_BASE,MAP_I2CMasterIntStatusEx(I2C_BASE,false));
//
// Set the time-out. Not to be used with breakpoints.
//
MAP_I2CMasterTimeoutSet(I2C_BASE, I2C_TIMEOUT_VAL);
//
// Initiate the transfer.
//
MAP_I2CMasterControl(I2C_BASE, ulCmd);
//
// Wait until the current byte has been transferred.
// Poll on the raw interrupt status.
//
while((MAP_I2CMasterIntStatusEx(I2C_BASE, false)
& (I2C_MASTER_INT_DATA | !I2C_MASTER_INT_TIMEOUT)) == 0)
{
if (MAP_I2CMasterIntStatusEx(I2C_BASE, false) & I2C_MASTER_INT_TIMEOUT) return -1;
}
//
// Check for any errors in transfer
//
if(MAP_I2CMasterErr(I2C_BASE) != I2C_MASTER_ERR_NONE)
{
switch(ulCmd)
{
case I2C_MASTER_CMD_BURST_SEND_START:
case I2C_MASTER_CMD_BURST_SEND_CONT:
case I2C_MASTER_CMD_BURST_SEND_STOP:
MAP_I2CMasterControl(I2C_BASE,
I2C_MASTER_CMD_BURST_SEND_ERROR_STOP);
break;
case I2C_MASTER_CMD_BURST_RECEIVE_START:
case I2C_MASTER_CMD_BURST_RECEIVE_CONT:
case I2C_MASTER_CMD_BURST_RECEIVE_FINISH:
MAP_I2CMasterControl(I2C_BASE,
I2C_MASTER_CMD_BURST_RECEIVE_ERROR_STOP);
break;
default:
break;
}
return FAILURE;
}
return SUCCESS;
}
//****************************************************************************
//
//! Invokes the I2C driver APIs to write to the specified address
//!
//! \param ucDevAddr is the 7-bit I2C slave address
//! \param pucData is the pointer to the data to be written
//! \param ucLen is the length of data to be written
//! \param ucStop determines if the transaction is followed by stop bit
//!
//! This function works in a polling mode,
//! 1. Writes the device register address to be written to.
//! 2. In a loop, writes all the bytes over I2C
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
int
I2C_IF_Write(unsigned char ucDevAddr,
unsigned char *pucData,
unsigned char ucLen,
unsigned char ucStop)
{
RETERR_IF_TRUE(pucData == NULL);
RETERR_IF_TRUE(ucLen == 0);
//
// Set I2C codec slave address
//
MAP_I2CMasterSlaveAddrSet(I2C_BASE, ucDevAddr, false);
//
// Write the first byte to the controller.
//
MAP_I2CMasterDataPut(I2C_BASE, *pucData);
//
// Initiate the transfer.
//
RET_IF_ERR(I2CTransact(I2C_MASTER_CMD_BURST_SEND_START));
//
// Decrement the count and increment the data pointer
// to facilitate the next transfer
//
ucLen--;
pucData++;
//
// Loop until the completion of transfer or error
//
while(ucLen)
{
//
// Write the next byte of data
//
MAP_I2CMasterDataPut(I2C_BASE, *pucData);
//
// Transact over I2C to send byte
//
RET_IF_ERR(I2CTransact(I2C_MASTER_CMD_BURST_SEND_CONT));
//
// Decrement the count and increment the data pointer
// to facilitate the next transfer
//
ucLen--;
pucData++;
}
//
// If stop bit is to be sent, send it.
//
if(ucStop == true)
{
RET_IF_ERR(I2CTransact(I2C_MASTER_CMD_BURST_SEND_STOP));
}
return SUCCESS;
}
//****************************************************************************
//
//! Invokes the I2C driver APIs to read from the device. This assumes the
//! device local address to read from is set using the I2CWrite API.
//!
//! \param ucDevAddr is the 7-bit I2C slave address
//! \param pucData is the pointer to the read data to be placed
//! \param ucLen is the length of data to be read
//!
//! This function works in a polling mode,
//! 1. Writes the device register address to be written to.
//! 2. In a loop, reads all the bytes over I2C
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
int
I2C_IF_Read(unsigned char ucDevAddr,
unsigned char *pucData,
unsigned char ucLen)
{
unsigned long ulCmdID;
RETERR_IF_TRUE(pucData == NULL);
RETERR_IF_TRUE(ucLen == 0);
//
// Set I2C codec slave address
//
MAP_I2CMasterSlaveAddrSet(I2C_BASE, ucDevAddr, true);
//
// Check if its a single receive or burst receive
//
if(ucLen == 1)
{
//
// Configure for a single receive
//
ulCmdID = I2C_MASTER_CMD_SINGLE_RECEIVE;
}
else
{
//
// Initiate a burst receive sequence
//
ulCmdID = I2C_MASTER_CMD_BURST_RECEIVE_START;
}
//
// Initiate the transfer.
//
RET_IF_ERR(I2CTransact(ulCmdID));
//
// Decrement the count and increment the data pointer
// to facilitate the next transfer
//
ucLen--;
//
// Loop until the completion of reception or error
//
while(ucLen)
{
//
// Receive the byte over I2C
//
*pucData = MAP_I2CMasterDataGet(I2C_BASE);
//
// Decrement the count and increment the data pointer
// to facilitate the next transfer
//
ucLen--;
pucData++;
if(ucLen)
{
//
// Continue the reception
//
RET_IF_ERR(I2CTransact(I2C_MASTER_CMD_BURST_RECEIVE_CONT));
}
else
{
//
// Complete the last reception
//
RET_IF_ERR(I2CTransact(I2C_MASTER_CMD_BURST_RECEIVE_FINISH));
}
}
//
// Receive the byte over I2C
//
*pucData = MAP_I2CMasterDataGet(I2C_BASE);
return SUCCESS;
}
//****************************************************************************
//
//! Invokes the I2C driver APIs to read from a specified address the device.
//! This assumes the device local address to be of 8-bit. For other
//! combinations use I2CWrite followed by I2CRead.
//!
//! \param ucDevAddr is the 7-bit I2C slave address
//! \param pucWrDataBuf is the pointer to the data to be written (reg addr)
//! \param ucWrLen is the length of data to be written
//! \param pucRdDataBuf is the pointer to the read data to be placed
//! \param ucRdLen is the length of data to be read
//!
//! This function works in a polling mode,
//! 1. Writes the data over I2C (device register address to be read from).
//! 2. In a loop, reads all the bytes over I2C
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
int
I2C_IF_ReadFrom(unsigned char ucDevAddr,
unsigned char *pucWrDataBuf,
unsigned char ucWrLen,
unsigned char *pucRdDataBuf,
unsigned char ucRdLen)
{
//
// Write the register address to be read from.
// Stop bit implicitly assumed to be 0.
//
RET_IF_ERR(I2C_IF_Write(ucDevAddr,pucWrDataBuf,ucWrLen,0));
//
// Read the specified length of data
//
RET_IF_ERR(I2C_IF_Read(ucDevAddr, pucRdDataBuf, ucRdLen));
return SUCCESS;
}
//****************************************************************************
//
//! Enables and configures the I2C peripheral
//!
//! \param ulMode is the mode configuration of I2C
//! The parameter \e ulMode is one of the following
//! - \b I2C_MASTER_MODE_STD for 100 Kbps standard mode.
//! - \b I2C_MASTER_MODE_FST for 400 Kbps fast mode.
//!
//! This function works in a polling mode,
//! 1. Powers ON the I2C peripheral.
//! 2. Configures the I2C peripheral
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
int
I2C_IF_Open(unsigned long ulMode)
{
//
// Enable I2C Peripheral
//
//MAP_HwSemaphoreLock(HWSEM_I2C, HWSEM_WAIT_FOR_EVER);
MAP_PRCMPeripheralClkEnable(PRCM_I2CA0, PRCM_RUN_MODE_CLK);
MAP_PRCMPeripheralReset(PRCM_I2CA0);
MAP_I2CMasterEnable(I2CA0_BASE);
// Clear all interrupts.
MAP_I2CMasterIntClearEx(I2CA0_BASE, MAP_I2CMasterIntStatusEx(I2CA0_BASE, false));
// Enable interrupts.
MAP_I2CMasterIntEnableEx(I2CA0_BASE,
I2C_MASTER_INT_TIMEOUT | // timeout
I2C_MASTER_INT_DATA // data transaction complete
);
//
// Configure I2C module in the specified mode
//
switch(ulMode)
{
case I2C_MASTER_MODE_STD: /* 100000 */
MAP_I2CMasterInitExpClk(I2C_BASE,SYS_CLK,false);
break;
case I2C_MASTER_MODE_FST: /* 400000 */
MAP_I2CMasterInitExpClk(I2C_BASE,SYS_CLK,true);
break;
default:
MAP_I2CMasterInitExpClk(I2C_BASE,SYS_CLK,true);
break;
}
//
// Disables the multi-master mode
//
//MAP_I2CMasterDisable(I2C_BASE);
return SUCCESS;
}
//****************************************************************************
//
//! Disables the I2C peripheral
//!
//! \param None
//!
//! This function works in a polling mode,
//! 1. Powers OFF the I2C peripheral.
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
int
I2C_IF_Close()
{
//
// Power OFF the I2C peripheral
//
MAP_PRCMPeripheralClkDisable(PRCM_I2CA0, PRCM_RUN_MODE_CLK);
return SUCCESS;
}

99
common/i2c_if.h Normal file
View File

@@ -0,0 +1,99 @@
//*****************************************************************************
// i2c_if.h
//
// Defines and Macros for the I2C interface.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#ifndef __I2C_IF_H__
#define __I2C_IF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
#define I2C_MRIS_CLKTOUT 0x2
//*****************************************************************************
//
// I2C transaction time-out value.
// Set to value 0x7D. (@100KHz it is 20ms, @400Khz it is 5 ms)
//
//*****************************************************************************
#define I2C_TIMEOUT_VAL 0x7D
//*****************************************************************************
//
// Values that can be passed to I2COpen as the ulMode parameter.
//
//*****************************************************************************
#define I2C_MASTER_MODE_STD 0
#define I2C_MASTER_MODE_FST 1
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern int I2C_IF_Open(unsigned long ulMode);
extern int I2C_IF_Close();
extern int I2C_IF_Write(unsigned char ucDevAddr,
unsigned char *pucData,
unsigned char ucLen,
unsigned char ucStop);
extern int I2C_IF_Read(unsigned char ucDevAddr,
unsigned char *pucData,
unsigned char ucLen);
extern int I2C_IF_ReadFrom(unsigned char ucDevAddr,
unsigned char *pucWrDataBuf,
unsigned char ucWrLen,
unsigned char *pucRdDataBuf,
unsigned char ucRdLen);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __I2C_IF_H__

255
common/i2s_if.c Normal file
View File

@@ -0,0 +1,255 @@
//*****************************************************************************
// i2s_if.c
//
// I2S interface APIs.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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 microphone
//! @{
//
//*****************************************************************************
/* Standard includes. */
#include <stdio.h>
/* Hardware & driverlib library includes. */
#include "hw_types.h"
#include "hw_mcasp.h"
#include "hw_ints.h"
#include "hw_memmap.h"
#include "debug.h"
#include "prcm.h"
#include "rom.h"
#include "rom_map.h"
#include "udma.h"
#include "interrupt.h"
#include "prcm.h"
#include "uart.h"
#include "pin.h"
#include "i2s.h"
// common interface includes
#include "common.h"
/* Demo app includes. */
#include "i2s_if.h"
#include "gpio_if.h"
//*****************************************************************************
//
//! Returns the pointer to transfer Audio samples to be rendered
//!
//! \param None
//!
//! This function
//! 1. Returns the pointer to the data buffer
//!
//! \return None.
//
//*****************************************************************************
unsigned int* AudioRendererGetDMADataPtr()
{
return (unsigned int *)(I2S_TX_DMA_PORT);
}
//*****************************************************************************
//
//! Returns the pointer to transfer Audio samples to be captured
//!
//! \param None
//!
//! This function
//! 1. Returns the pointer to the data buffer
//!
//! \return None.
//
//*****************************************************************************
unsigned int* AudioCapturerGetDMADataPtr()
{
return (unsigned int *)(I2S_RX_DMA_PORT);
}
//*****************************************************************************
//
//! Initialize the audio capture or render
//!
//! \param None
//!
//! This function initializes
//! 1. Initializes the McASP module
//!
//! \return None.
//
//*****************************************************************************
void AudioInit()
{
//
// Initialising the McASP
//
MAP_PRCMPeripheralClkEnable(PRCM_I2S,PRCM_RUN_MODE_CLK);
}
//*****************************************************************************
//
//! Setup the Audio capturer callback routine and the interval of callback.
//! On the invocation the callback is expected to fill the AFIFO with enough
//! number of samples for one callback interval.
//!
//! \param pfnAppCbHndlr is the callback handler that is invoked when
//! \e ucCallbackEvtSamples space is available in the audio FIFO
//! \param ucCallbackEvtSamples is used to configure the callback interval
//!
//! This function initializes
//! 1. Initializes the interrupt callback routine
//! 2. Sets up the AFIFO to interrupt at the configured interval
//!
//! \return 0 - Success
//! -1 - Failure
//
//*****************************************************************************
long AudioSetupDMAMode(void (*pfnAppCbHndlr)(void),
unsigned long ulCallbackEvtSamples,
unsigned char RxTx)
{
MAP_I2SIntEnable(I2S_BASE,I2S_INT_XDATA);
#ifdef USE_TIRTOS
long lRetVal = -1;
lRetVal = osi_InterruptRegister(INT_I2S, pfnAppCbHndlr, INT_PRIORITY_LVL_1);
ASSERT_ON_ERROR(lRetVal);
#else
MAP_I2SIntRegister(I2S_BASE,pfnAppCbHndlr);
#endif
if(RxTx == I2S_MODE_RX_TX)
{
MAP_I2SRxFIFOEnable(I2S_BASE,8,1);
}
if(RxTx & I2S_MODE_TX)
{
MAP_I2STxFIFOEnable(I2S_BASE,8,1);
}
return SUCCESS;
}
//*****************************************************************************
//
//! Initialize the AudioCaptureRendererConfigure
//!
//! \param[in] bitsPerSample - Number of bits per sample
//! \param[in] bitRate - Bit rate
//! \param[in] noOfChannels - Number of channels
//! \param[in] RxTx - Play or record or both
//! \param[in] dma - 1 for dma and 0 for non-dma mode
//!
//!
//! \return None.
//
//*****************************************************************************
void AudioCaptureRendererConfigure(unsigned char bitsPerSample,
unsigned short bitRate,
unsigned char noOfChannels,
unsigned char RxTx,
unsigned char dma)
{
unsigned long bitClk;
bitClk = bitsPerSample * bitRate * noOfChannels;
if(dma)
{
if(bitsPerSample == 16)
{
MAP_PRCMI2SClockFreqSet(512000);
MAP_I2SConfigSetExpClk(I2S_BASE,512000,bitClk,I2S_SLOT_SIZE_16|
I2S_PORT_DMA);
}
}
if(RxTx == I2S_MODE_RX_TX)
{
MAP_I2SSerializerConfig(I2S_BASE,I2S_DATA_LINE_1,I2S_SER_MODE_RX,
I2S_INACT_LOW_LEVEL);
}
if(RxTx & I2S_MODE_TX)
{
MAP_I2SSerializerConfig(I2S_BASE,I2S_DATA_LINE_0,I2S_SER_MODE_TX,
I2S_INACT_LOW_LEVEL);
}
}
//*****************************************************************************
//
//! Initialize the Audio_Start
//!
//! \param[in] RxTx - Flag for play or record or both
//!
//! This function initializes
//! 1. Enable the McASP module for TX and RX
//!
//! \return None.
//
//*****************************************************************************
void Audio_Start(unsigned char RxTx)
{
if(RxTx == I2S_MODE_RX_TX)
{
MAP_I2SEnable(I2S_BASE,I2S_MODE_TX_RX_SYNC);
}
else if(RxTx & I2S_MODE_TX)
{
MAP_I2SEnable(I2S_BASE,I2S_MODE_TX_ONLY);
}
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

141
common/i2s_if.h Normal file
View File

@@ -0,0 +1,141 @@
//*****************************************************************************
// mcasp_if.h
//
// MCASP interface APIs.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
//*****************************************************************************
//
// mcasp_if.h - Defines and prototypes for MultiChannel Audio Serial Port.
//
//*****************************************************************************
#ifndef __MCASP_IF_H__
#define __MCASP_IF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
#define WFIFO_NUMDMA_WORDS 1
#define MCASP_DMA_PORT_ADDR 0x4401E200
//
// Update the sampling freq, channels, sample length appropriately
//
typedef enum {
SAMPLING_FREQ_8_KHZ = 8000,
SAMPLING_FREQ_11_X_KHZ = 11025,
SAMPLING_FREQ_16_KHZ = 16000,
SAMPLING_FREQ_22_X_KHZ = 22050,
SAMPLING_FREQ_32_KHZ = 32000,
SAMPLING_FREQ_44_1_KHZ = 44100,
SAMPLING_FREQ_48_KHZ = 48000
} tESamplFreq;
typedef enum {
CH_MONO = 1,
CH_STEREO = 2
} tENumChannels;
typedef enum {
BIT_8_PCM = 8,
BIT_16_PCM = 16,
BIT_24_PCM = 24,
BIT_32_PCM = 32
} tESampleLen;
#define I2S_MODE_RX 0x01
#define I2S_MODE_TX 0x02
#define I2S_MODE_RX_TX 0x03
//
// Audio Renderer Interface APIs
//
extern void AudioRendererInit();
extern void AudioCapturerInit();
extern void AudioInit();
extern void McASPInit();
extern void AudioRendererSetupCPUMode(void (*pfnAppCbHndlr)(void));
extern void AudioRendererSetupDMAMode(void (*pfnAppCbHndlr)(void),
unsigned long ulCallbackEvtSamples);
extern void AudioCapturerSetupCPUMode(void (*pfnAppCbHndlr)(void));
extern long AudioCapturerSetupDMAMode(void (*pfnAppCbHndlr)(void),
unsigned long ulCallbackEvtSamples);
extern long AudioSetupDMAMode(void (*pfnAppCbHndlr)(void),
unsigned long ulCallbackEvtSamples,
unsigned char RxTx);
extern unsigned int* AudioRendererGetDMADataPtr();
extern unsigned int* AudioCapturerGetDMADataPtr();
extern void AudioCapturerConfigure(int iSamplingFrequency,
short sNumOfChannels,
short sBitsPerSample);
extern void AudioRendererConfigure(int iSamplingFrequency,
short sNumOfChannels,
short sBitsPerSample);
extern void AudioRendererStart();
extern void AudioCapturerStart();
extern void AudioRendererStop();
extern void AudioRendererDeInit();
extern unsigned int BitClockConfigure(int iSamplingFrequency,
short sNumOfChannels,
short sBitsPerSample);
extern void AudioCaptureRendererConfigure(unsigned char bitsPerSample,
unsigned short bitRate,
unsigned char noOfChannels,
unsigned char RxTx,
unsigned char dma);
extern void Audio_Start(unsigned char RxTx);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __MCASP_IF_H__

108
common/network_common.c Normal file
View File

@@ -0,0 +1,108 @@
//*****************************************************************************
// network_common.c
//
// Networking common callback for CC3200 device
//
// Copyright (C) 2016 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#include <stdlib.h>
// Simplelink includes
#include "simplelink.h"
//*****************************************************************************
// SimpleLink Asynchronous Event Handlers -- Start
//*****************************************************************************
//*****************************************************************************
//
//! \brief This function serves as first level handler for HTTP GET/POST tokens
//! It runs under driver context and performs only operation that can run
//! from this context. For operations that can't is sets an indication of
//! received token and preempts the provisioning context.
//!
//! \param pSlHttpServerEvent Pointer indicating http server event
//! \param pSlHttpServerResponse Pointer indicating http server response
//!
//! \return None
//!
//*****************************************************************************
_SlEventPropogationStatus_e sl_Provisioning_HttpServerEventHdl(
SlHttpServerEvent_t *apSlHttpServerEvent,
SlHttpServerResponse_t *apSlHttpServerResponse)
{
// Unused in this application
return EVENT_PROPAGATION_CONTINUE;
}
//*****************************************************************************
//
//! \brief This function serves as first level network application events handler.
//! It runs under driver context and performs only operation that can run
//! from this context. For operations that can't is sets an indication of
//! received token and preempts the provisioning context.
//!
//! \param apEventInfo Pointer to the net app event information
//!
//! \return None
//!
//*****************************************************************************
_SlEventPropogationStatus_e sl_Provisioning_NetAppEventHdl(SlNetAppEvent_t *apNetAppEvent)
{
// Unused in this application
return EVENT_PROPAGATION_CONTINUE;
}
//*****************************************************************************
//
//! \brief This function serves as first level WLAN events handler.
//! It runs under driver context and performs only operation that can run
//! from this context. For operations that can't is sets an indication of
//! received token and preempts the provisioning context.
//!
//! \param apEventInfo Pointer to the WLAN event information
//!
//! \return None
//!
//*****************************************************************************
_SlEventPropogationStatus_e sl_Provisioning_WlanEventHdl(SlWlanEvent_t *apEventInfo)
{
// Unused in this application
return EVENT_PROPAGATION_CONTINUE;
}
//*****************************************************************************
// SimpleLink Asynchronous Event Handlers -- End
//*****************************************************************************

1273
common/network_if.c Normal file

File diff suppressed because it is too large Load Diff

83
common/network_if.h Normal file
View File

@@ -0,0 +1,83 @@
//*****************************************************************************
// network_if.h
//
// Networking interface macro and function prototypes for CC3200 device
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#ifndef __NETWORK_IF__H__
#define __NETWORK_IF__H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern long Network_IF_InitDriver(unsigned int uiMode);
extern long Network_IF_DeInitDriver(void);
extern long Network_IF_ConnectAP(char * pcSsid, SlSecParams_t SecurityParams);
extern long Network_IF_DisconnectFromAP();
extern long Network_IF_IpConfigGet(unsigned long *aucIP, unsigned long *aucSubnetMask,
unsigned long *aucDefaultGateway, unsigned long *aucDNSServer);
extern long Network_IF_GetHostIP( char* pcHostName,unsigned long * pDestinationIP);
extern unsigned long Network_IF_CurrentMCUState();
extern void Network_IF_UnsetMCUMachineState(char stat);
extern void Network_IF_SetMCUMachineState(char stat);
extern void Network_IF_ResetMCUStateMachine();
extern unsigned short itoa(short cNum, char *cString);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif

264
common/startup_ccs.c Normal file
View File

@@ -0,0 +1,264 @@
//*****************************************************************************
// startup_ccs.c
//
// Startup code for use with TI's Code Composer Studio.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#ifndef USE_TIRTOS /* if project uses TI-RTOS then no need to include startup file */
//*****************************************************************************
//
// Forward declaration of the default fault handlers.
//
//*****************************************************************************
void ResetISR(void);
static void NmiSR(void);
static void FaultISR(void);
static void IntDefaultHandler(void);
static void BusFaultHandler(void);
//*****************************************************************************
//
// External declaration for the reset handler that is to be called when the
// processor is started
//
//*****************************************************************************
extern void _c_int00(void);
#ifdef USE_FREERTOS
extern void vPortSVCHandler(void);
extern void xPortPendSVHandler(void);
extern void xPortSysTickHandler(void);
#endif
//*****************************************************************************
//
// Linker variable that marks the top of the stack.
//
//*****************************************************************************
extern unsigned long __STACK_END;
//*****************************************************************************
// The vector table. Note that the proper constructs must be placed on this to
// ensure that it ends up at physical address 0x0000.0000 or at the start of
// the program if located at a start address other than 0.
//
//*****************************************************************************
#pragma DATA_SECTION(g_pfnVectors, ".intvecs")
void (* const g_pfnVectors[256])(void) =
{
(void (*)(void))((unsigned long)&__STACK_END),
// The initial stack pointer
ResetISR, // The reset handler
NmiSR, // The NMI handler
FaultISR, // The hard fault handler
IntDefaultHandler, // The MPU fault handler
BusFaultHandler, // The bus fault handler
IntDefaultHandler, // The usage fault handler
0, // Reserved
0, // Reserved
0, // Reserved
0, // Reserved
#ifdef USE_FREERTOS
vPortSVCHandler, // SVCall handler
#else
IntDefaultHandler, // SVCall handler
#endif
IntDefaultHandler, // Debug monitor handler
0, // Reserved
#ifdef USE_FREERTOS
xPortPendSVHandler, // The PendSV handler
xPortSysTickHandler, // The SysTick handler
#else
IntDefaultHandler, // The PendSV handler
IntDefaultHandler, // The SysTick handler
#endif
IntDefaultHandler, // GPIO Port A0
IntDefaultHandler, // GPIO Port A1
IntDefaultHandler, // GPIO Port A2
IntDefaultHandler, // GPIO Port A3
0, // Reserved
IntDefaultHandler, // UART0 Rx and Tx
IntDefaultHandler, // UART1 Rx and Tx
0, // Reserved
IntDefaultHandler, // I2C0 Master and Slave
0,0,0,0,0, // Reserved
IntDefaultHandler, // ADC Channel 0
IntDefaultHandler, // ADC Channel 1
IntDefaultHandler, // ADC Channel 2
IntDefaultHandler, // ADC Channel 3
IntDefaultHandler, // Watchdog Timer
IntDefaultHandler, // Timer 0 subtimer A
IntDefaultHandler, // Timer 0 subtimer B
IntDefaultHandler, // Timer 1 subtimer A
IntDefaultHandler, // Timer 1 subtimer B
IntDefaultHandler, // Timer 2 subtimer A
IntDefaultHandler, // Timer 2 subtimer B
0,0,0,0, // Reserved
IntDefaultHandler, // Flash
0,0,0,0,0, // Reserved
IntDefaultHandler, // Timer 3 subtimer A
IntDefaultHandler, // Timer 3 subtimer B
0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // uDMA Software Transfer
IntDefaultHandler, // uDMA Error
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // SHA
0,0, // Reserved
IntDefaultHandler, // AES
0, // Reserved
IntDefaultHandler, // DES
0,0,0,0,0, // Reserved
IntDefaultHandler, // SDHost
0, // Reserved
IntDefaultHandler, // I2S
0, // Reserved
IntDefaultHandler, // Camera
0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // NWP to APPS Interrupt
IntDefaultHandler, // Power, Reset and Clock module
0,0, // Reserved
IntDefaultHandler, // Shared SPI
IntDefaultHandler, // Generic SPI
IntDefaultHandler, // Link SPI
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0 // Reserved
};
//*****************************************************************************
//
// 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 entry() routine is called. Any fancy
// actions (such as making decisions based on the reset cause register, and
// resetting the bits in that register) are left solely in the hands of the
// application.
//
//*****************************************************************************
void
ResetISR(void)
{
//
// Jump to the CCS C initialization routine.
//
__asm(" .global _c_int00\n"
" b.w _c_int00");
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives a NMI. This
// simply enters an infinite loop, preserving the system state for examination
// by a debugger.
//
//*****************************************************************************
static void
NmiSR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives a fault
// interrupt. This simply enters an infinite loop, preserving the system state
// for examination by a debugger.
//
//*****************************************************************************
static void
FaultISR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// 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.
//
//*****************************************************************************
static void
BusFaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// 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.
//
//*****************************************************************************
static void
IntDefaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}
#endif

269
common/startup_ewarm.c Normal file
View File

@@ -0,0 +1,269 @@
//*****************************************************************************
// startup_ewarm.c
//
// Startup code for use with IAR IDE.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#include "hw_types.h"
#include "hw_ints.h"
#include "interrupt.h"
//*****************************************************************************
//
// Forward declaration of the default fault handlers.
//
//*****************************************************************************
void ResetISR(void);
static void NmiSR(void);
static void FaultISR(void);
static void IntDefaultHandler(void);
static void BusFaultHandler(void);
#ifdef USE_FREERTOS
extern void vPortSVCHandler(void);
extern void xPortPendSVHandler(void);
extern void xPortSysTickHandler(void);
#endif
//*****************************************************************************
//
// The entry point for the application startup code.
//
//*****************************************************************************
extern void __iar_program_start(void);
//*****************************************************************************
//
// Reserve space for the system stack.
//
//*****************************************************************************
static unsigned long pulStack[1024] @ ".noinit";
//*****************************************************************************
//
// The vector table. Note that the proper constructs must be placed on this to
// ensure that it ends up at physical address 0x0000.0000.
//
//*****************************************************************************
__root const uVectorEntry __vector_table[256] @ ".intvec" =
{
{ .ulPtr = (unsigned long)pulStack + sizeof(pulStack) },
// The initial stack pointer
ResetISR, // The reset handler
NmiSR, // The NMI handler
FaultISR, // The hard fault handler
IntDefaultHandler, // The MPU fault handler
BusFaultHandler, // The bus fault handler
IntDefaultHandler, // The usage fault handler
0, // Reserved
0, // Reserved
0, // Reserved
0, // Reserved
#ifdef USE_FREERTOS
vPortSVCHandler, // SVCall handler
#else
IntDefaultHandler, // SVCall handler
#endif
IntDefaultHandler, // Debug monitor handler
0, // Reserved
#ifdef USE_FREERTOS
xPortPendSVHandler, // The PendSV handler
xPortSysTickHandler, // The SysTick handler
#else
IntDefaultHandler, // The PendSV handler
IntDefaultHandler, // The SysTick handler
#endif
IntDefaultHandler, // GPIO Port A0
IntDefaultHandler, // GPIO Port A1
IntDefaultHandler, // GPIO Port A2
IntDefaultHandler, // GPIO Port A3
0, // Reserved
IntDefaultHandler, // UART0 Rx and Tx
IntDefaultHandler, // UART1 Rx and Tx
0, // Reserved
IntDefaultHandler, // I2C0 Master and Slave
0,0,0,0,0, // Reserved
IntDefaultHandler, // ADC Channel 0
IntDefaultHandler, // ADC Channel 1
IntDefaultHandler, // ADC Channel 2
IntDefaultHandler, // ADC Channel 3
IntDefaultHandler, // Watchdog Timer
IntDefaultHandler, // Timer 0 subtimer A
IntDefaultHandler, // Timer 0 subtimer B
IntDefaultHandler, // Timer 1 subtimer A
IntDefaultHandler, // Timer 1 subtimer B
IntDefaultHandler, // Timer 2 subtimer A
IntDefaultHandler, // Timer 2 subtimer B
0,0,0,0, // Reserved
IntDefaultHandler, // Flash
0,0,0,0,0, // Reserved
IntDefaultHandler, // Timer 3 subtimer A
IntDefaultHandler, // Timer 3 subtimer B
0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // uDMA Software Transfer
IntDefaultHandler, // uDMA Error
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // SHA
0,0, // Reserved
IntDefaultHandler, // AES
0, // Reserved
IntDefaultHandler, // DES
0,0,0,0,0, // Reserved
IntDefaultHandler, // SDHost
0, // Reserved
IntDefaultHandler, // I2S
0, // Reserved
IntDefaultHandler, // Camera
0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // NWP to APPS Interrupt
IntDefaultHandler, // Power, Reset and Clock module
0,0, // Reserved
IntDefaultHandler, // Shared SPI
IntDefaultHandler, // Generic SPI
IntDefaultHandler, // Link SPI
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0 // Reserved
};
//*****************************************************************************
//
//! 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 entry() routine is called. Any fancy
//! actions (such as making decisions based on the reset cause register, and
//! resetting the bits in that register) are left solely in the hands of the
//! application.
//
//*****************************************************************************
void
ResetISR(void)
{
//
// Call the application's entry point.
//
__iar_program_start();
}
//*****************************************************************************
//
//! This is the code that gets called when the processor receives a NMI. This
//! simply enters an infinite loop, preserving the system state for examination
//! by a debugger.
//
//*****************************************************************************
static void
NmiSR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
//! This is the code that gets called when the processor receives a fault
//! interrupt. This simply enters an infinite loop, preserving the system state
//! for examination by a debugger.
//
//*****************************************************************************
static void
FaultISR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
//! 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.
//
//*****************************************************************************
static void
BusFaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
//! 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.
//
//*****************************************************************************
static void
IntDefaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}

361
common/startup_gcc.c Normal file
View File

@@ -0,0 +1,361 @@
//*****************************************************************************
// startup_gcc.c
//
// Startup code for use with GCC.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#include <stdint.h>
#include "hw_nvic.h"
#include "hw_types.h"
//*****************************************************************************
//
// Heap block pointers defined by linker script
//
//*****************************************************************************
static char *heap_end = 0;
extern unsigned long _heap;
extern unsigned long _eheap;
//*****************************************************************************
//
// Forward declaration of the default fault handlers.
//
//*****************************************************************************
void ResetISR(void);
static void NmiSR(void);
static void FaultISR(void);
static void IntDefaultHandler(void);
static void BusFaultHandler(void);
//*****************************************************************************
//
// External declaration for the reset handler that is to be called when the
// processor is started
//
//*****************************************************************************
extern void _c_int00(void);
extern void vPortSVCHandler(void);
extern void xPortPendSVHandler(void);
extern void xPortSysTickHandler(void);
//*****************************************************************************
//
// The entry point for the application.
//
//*****************************************************************************
extern int main(void);
//*****************************************************************************
//
// Reserve space for the system stack.
//
//*****************************************************************************
static uint32_t pui32Stack[1024];
//*****************************************************************************
//
// The vector table. Note that the proper constructs must be placed on this to
// ensure that it ends up at physical address 0x0000.0000.
//
//*****************************************************************************
__attribute__ ((section(".intvecs")))
void (* const g_pfnVectors[256])(void) =
{
(void (*)(void))((uint32_t)pui32Stack + sizeof(pui32Stack)),
// The initial stack pointer
ResetISR, // The reset handler
NmiSR, // The NMI handler
FaultISR, // The hard fault handler
IntDefaultHandler, // The MPU fault handler
BusFaultHandler, // The bus fault handler
IntDefaultHandler, // The usage fault handler
0, // Reserved
0, // Reserved
0, // Reserved
0, // Reserved
#ifdef USE_FREERTOS
vPortSVCHandler, // SVCall handler
#else
IntDefaultHandler, // SVCall handler
#endif
IntDefaultHandler, // Debug monitor handler
0, // Reserved
#ifdef USE_FREERTOS
xPortPendSVHandler, // The PendSV handler
xPortSysTickHandler, // The SysTick handler
#else
IntDefaultHandler, // The PendSV handler
IntDefaultHandler, // The SysTick handler
#endif
IntDefaultHandler, // GPIO Port A0
IntDefaultHandler, // GPIO Port A1
IntDefaultHandler, // GPIO Port A2
IntDefaultHandler, // GPIO Port A3
0, // Reserved
IntDefaultHandler, // UART0 Rx and Tx
IntDefaultHandler, // UART1 Rx and Tx
0, // Reserved
IntDefaultHandler, // I2C0 Master and Slave
0,0,0,0,0, // Reserved
IntDefaultHandler, // ADC Channel 0
IntDefaultHandler, // ADC Channel 1
IntDefaultHandler, // ADC Channel 2
IntDefaultHandler, // ADC Channel 3
IntDefaultHandler, // Watchdog Timer
IntDefaultHandler, // Timer 0 subtimer A
IntDefaultHandler, // Timer 0 subtimer B
IntDefaultHandler, // Timer 1 subtimer A
IntDefaultHandler, // Timer 1 subtimer B
IntDefaultHandler, // Timer 2 subtimer A
IntDefaultHandler, // Timer 2 subtimer B
0,0,0,0, // Reserved
IntDefaultHandler, // Flash
0,0,0,0,0, // Reserved
IntDefaultHandler, // Timer 3 subtimer A
IntDefaultHandler, // Timer 3 subtimer B
0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // uDMA Software Transfer
IntDefaultHandler, // uDMA Error
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // SHA
0,0, // Reserved
IntDefaultHandler, // AES
0, // Reserved
IntDefaultHandler, // DES
0,0,0,0,0, // Reserved
IntDefaultHandler, // SDHost
0, // Reserved
IntDefaultHandler, // I2S
0, // Reserved
IntDefaultHandler, // Camera
0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // NWP to APPS Interrupt
IntDefaultHandler, // Power, Reset and Clock module
0,0, // Reserved
IntDefaultHandler, // Shared SPI
IntDefaultHandler, // Generic SPI
IntDefaultHandler, // Link SPI
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0 // Reserved
};
//*****************************************************************************
//
// The following are constructs created by the linker, indicating where the
// the "data" and "bss" segments reside in memory. The initializers for the
// for the "data" segment resides immediately following the "text" segment.
//
//*****************************************************************************
extern uint32_t _etext;
extern uint32_t _data;
extern uint32_t _edata;
extern uint32_t _bss;
extern uint32_t _ebss;
extern uint32_t __init_data;
//*****************************************************************************
//
// 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 entry() routine is called. Any fancy
// actions (such as making decisions based on the reset cause register, and
// resetting the bits in that register) are left solely in the hands of the
// application.
//
//*****************************************************************************
void
ResetISR(void)
{
uint32_t *pui32Src, *pui32Dest;
//
// Copy the data segment initializers
//
pui32Src = &__init_data;
for(pui32Dest = &_data; pui32Dest < &_edata; )
{
*pui32Dest++ = *pui32Src++;
}
//
// Zero fill the bss segment.
//
__asm(" ldr r0, =_bss\n"
" ldr r1, =_ebss\n"
" mov r2, #0\n"
" .thumb_func\n"
"zero_loop:\n"
" cmp r0, r1\n"
" it lt\n"
" strlt r2, [r0], #4\n"
" blt zero_loop");
//
// Call the application's entry point.
//
main();
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives a NMI. This
// simply enters an infinite loop, preserving the system state for examination
// by a debugger.
//
//*****************************************************************************
static void
NmiSR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives a fault
// interrupt. This simply enters an infinite loop, preserving the system state
// for examination by a debugger.
//
//*****************************************************************************
static void
FaultISR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// 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.
//
//*****************************************************************************
static void
BusFaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// 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.
//
//*****************************************************************************
static void
IntDefaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// This function is used by dynamic memory allocation API(s) in newlib
// library
//
//*****************************************************************************
void * _sbrk(unsigned int incr)
{
char *prev_heap_end;
//
// Check if this function is calld for the
// first time and the heap end pointer
//
if (heap_end == 0)
{
heap_end = (char *)&_heap;
}
//
// Check if we have enough heap memory available
//
prev_heap_end = heap_end;
if (heap_end + incr > (char *)&_eheap)
{
//
// Return error
//
return 0;
}
//
// Set the new heap end pointer
//
heap_end += incr;
//
// Return the pointer to the newly allocated memory
//
return prev_heap_end;
}

330
common/timer_if.c Normal file
View File

@@ -0,0 +1,330 @@
//*****************************************************************************
// timer_if.c
//
// timer interface file: contains different interface functions for timer APIs
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
// Driverlib includes
#include "hw_types.h"
#include "hw_memmap.h"
#include "hw_ints.h"
#include "debug.h"
#include "interrupt.h"
#include "timer.h"
#include "rom.h"
#include "rom_map.h"
#include "prcm.h"
// TI-RTOS includes
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
#include <stdlib.h>
#include "osi.h"
#endif
#include "timer_if.h"
static unsigned char
GetPeripheralIntNum(unsigned long ulBase, unsigned long ulTimer)
{
if(ulTimer == TIMER_A)
{
switch(ulBase)
{
case TIMERA0_BASE:
return INT_TIMERA0A;
case TIMERA1_BASE:
return INT_TIMERA1A;
case TIMERA2_BASE:
return INT_TIMERA2A;
case TIMERA3_BASE:
return INT_TIMERA3A;
default:
return INT_TIMERA0A;
}
}
else if(ulTimer == TIMER_B)
{
switch(ulBase)
{
case TIMERA0_BASE:
return INT_TIMERA0B;
case TIMERA1_BASE:
return INT_TIMERA1B;
case TIMERA2_BASE:
return INT_TIMERA2B;
case TIMERA3_BASE:
return INT_TIMERA3B;
default:
return INT_TIMERA0B;
}
}
else
{
return INT_TIMERA0A;
}
}
//*****************************************************************************
//
//! Initializing the Timer
//!
//! \param ePeripheral is the peripheral which need to be initialized.
//! \param ulBase is the base address for the timer.
//! \param ulConfig is the configuration for the timer.
//! \param ulTimer selects amoung the TIMER_A or TIMER_B or TIMER_BOTH.
//! \param ulValue is the timer prescale value which must be between 0 and
//! 255 (inclusive) for 16/32-bit timers and between 0 and 65535 (inclusive)
//! for 32/64-bit timers.
//! This function
//! 1. Enables and reset the peripheral for the timer.
//! 2. Configures and set the prescale value for the timer.
//!
//! \return none
//
//*****************************************************************************
void Timer_IF_Init( unsigned long ePeripheral, unsigned long ulBase, unsigned
long ulConfig, unsigned long ulTimer, unsigned long ulValue)
{
//
// Initialize GPT A0 (in 32 bit mode) as periodic down counter.
//
MAP_PRCMPeripheralClkEnable(ePeripheral, PRCM_RUN_MODE_CLK);
MAP_PRCMPeripheralReset(ePeripheral);
MAP_TimerConfigure(ulBase,ulConfig);
MAP_TimerPrescaleSet(ulBase,ulTimer,ulValue);
}
//*****************************************************************************
//
//! setting up the timer
//!
//! \param ulBase is the base address for the timer.
//! \param ulTimer selects between the TIMER_A or TIMER_B or TIMER_BOTH.
//! \param TimerBaseIntHandler is the pointer to the function that handles the
//! interrupt for the Timer
//!
//! This function
//! 1. Register the function handler for the timer interrupt.
//! 2. enables the timer interrupt.
//!
//! \return none
//
//*****************************************************************************
void Timer_IF_IntSetup(unsigned long ulBase, unsigned long ulTimer,
void (*TimerBaseIntHandler)(void))
{
//
// Setup the interrupts for the timer timeouts.
//
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
if(ulTimer == TIMER_BOTH)
{
osi_InterruptRegister(GetPeripheralIntNum(ulBase, TIMER_A),
TimerBaseIntHandler, INT_PRIORITY_LVL_1);
osi_InterruptRegister(GetPeripheralIntNum(ulBase, TIMER_B),
TimerBaseIntHandler, INT_PRIORITY_LVL_1);
}
else
{
osi_InterruptRegister(GetPeripheralIntNum(ulBase, ulTimer),
TimerBaseIntHandler, INT_PRIORITY_LVL_1);
}
#else
MAP_IntPrioritySet(GetPeripheralIntNum(ulBase, ulTimer), INT_PRIORITY_LVL_1);
MAP_TimerIntRegister(ulBase, ulTimer, TimerBaseIntHandler);
#endif
if(ulTimer == TIMER_BOTH)
{
MAP_TimerIntEnable(ulBase, TIMER_TIMA_TIMEOUT|TIMER_TIMB_TIMEOUT);
}
else
{
MAP_TimerIntEnable(ulBase, ((ulTimer == TIMER_A) ? TIMER_TIMA_TIMEOUT :
TIMER_TIMB_TIMEOUT));
}
}
//*****************************************************************************
//
//! clears the timer interrupt
//!
//! \param ulBase is the base address for the timer.
//!
//! This function
//! 1. clears the interrupt with given base.
//!
//! \return none
//
//*****************************************************************************
void Timer_IF_InterruptClear(unsigned long ulBase)
{
unsigned long ulInts;
ulInts = MAP_TimerIntStatus(ulBase, true);
//
// Clear the timer interrupt.
//
MAP_TimerIntClear(ulBase, ulInts);
}
//*****************************************************************************
//
//! starts the timer
//!
//! \param ulBase is the base address for the timer.
//! \param ulTimer selects amoung the TIMER_A or TIMER_B or TIMER_BOTH.
//! \param ulValue is the time delay in mSec after that run out,
//! timer gives an interrupt.
//!
//! This function
//! 1. Load the Timer with the specified value.
//! 2. enables the timer.
//!
//! \return none
//!
//! \Note- HW Timer runs on 80MHz clock
//
//*****************************************************************************
void Timer_IF_Start(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue)
{
MAP_TimerLoadSet(ulBase,ulTimer,MILLISECONDS_TO_TICKS(ulValue));
//
// Enable the GPT
//
MAP_TimerEnable(ulBase,ulTimer);
}
//*****************************************************************************
//
//! disable the timer
//!
//! \param ulBase is the base address for the timer.
//! \param ulTimer selects amoung the TIMER_A or TIMER_B or TIMER_BOTH.
//!
//! This function
//! 1. disables the interupt.
//!
//! \return none
//
//*****************************************************************************
void Timer_IF_Stop(unsigned long ulBase, unsigned long ulTimer)
{
//
// Disable the GPT
//
MAP_TimerDisable(ulBase,ulTimer);
}
//*****************************************************************************
//
//! De-Initialize the timer
//!
//! \param uiGPTBaseAddr
//! \param ulTimer
//!
//! This function
//! 1. disable the timer interrupts
//! 2. unregister the timer interrupt
//!
//! \return None.
//
//*****************************************************************************
void Timer_IF_DeInit(unsigned long ulBase,unsigned long ulTimer)
{
//
// Disable the timer interrupt
//
MAP_TimerIntDisable(ulBase,TIMER_TIMA_TIMEOUT|TIMER_TIMB_TIMEOUT);
//
// Unregister the timer interrupt
//
MAP_TimerIntUnregister(ulBase,ulTimer);
}
//*****************************************************************************
//
//! starts the timer
//!
//! \param ulBase is the base address for the timer.
//! \param ulTimer selects between the TIMER A and TIMER B.
//! \param ulValue is timer reload value (mSec) after which the timer will run out and gives an interrupt.
//!
//! This function
//! 1. Reload the Timer with the specified value.
//!
//! \return none
//
//*****************************************************************************
void Timer_IF_ReLoad(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue)
{
MAP_TimerLoadSet(ulBase,ulTimer,MILLISECONDS_TO_TICKS(ulValue));
}
//*****************************************************************************
//
//! starts the timer
//!
//! \param ulBase is the base address for the timer.
//! \param ulTimer selects amoung the TIMER_A or TIMER_B or TIMER_BOTH.
//!
//! This function
//! 1. returns the timer value.
//!
//! \return Timer Value.
//
//*****************************************************************************
unsigned int Timer_IF_GetCount(unsigned long ulBase, unsigned long ulTimer)
{
unsigned long ulCounter;
ulCounter = MAP_TimerValueGet(ulBase, ulTimer);
return 0xFFFFFFFF - ulCounter;
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

81
common/timer_if.h Normal file
View File

@@ -0,0 +1,81 @@
//*****************************************************************************
// timer_if.h
//
// timer interface header file: Prototypes and Macros for timer APIs
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#ifndef __TIMER_IF_H__
#define __TIMER_IF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
/****************************************************************************/
/* MACROS */
/****************************************************************************/
#define SYS_CLK 80000000
#define MILLISECONDS_TO_TICKS(ms) ((SYS_CLK/1000) * (ms))
#define PERIODIC_TEST_LOOPS 5
extern void Timer_IF_Init( unsigned long ePeripheralc, unsigned long ulBase,
unsigned long ulConfig, unsigned long ulTimer, unsigned long ulValue);
extern void Timer_IF_IntSetup(unsigned long ulBase, unsigned long ulTimer,
void (*TimerBaseIntHandler)(void));
extern void Timer_IF_InterruptClear(unsigned long ulBase);
extern void Timer_IF_Start(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue);
extern void Timer_IF_Stop(unsigned long ulBase, unsigned long ulTimer);
extern void Timer_IF_ReLoad(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue);
extern unsigned int Timer_IF_GetCount(unsigned long ulBase, unsigned long ulTimer);
void Timer_IF_DeInit(unsigned long ulBase,unsigned long ulTimer);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __TIMER_IF_H__

337
common/uart_if.c Normal file
View File

@@ -0,0 +1,337 @@
//*****************************************************************************
// uart_if.c
//
// uart interface file: Prototypes and Macros for UARTLogger
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
// Standard includes
#include <stdarg.h>
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
// Driverlib includes
#include "hw_types.h"
#include "hw_memmap.h"
#include "prcm.h"
#include "pin.h"
#include "uart.h"
#include "rom.h"
#include "rom_map.h"
#if defined(USE_FREERTOS) || defined(USE_TI_RTOS)
#include "osi.h"
#endif
#include "uart_if.h"
#define IS_SPACE(x) (x == 32 ? 1 : 0)
//*****************************************************************************
// Global variable indicating command is present
//*****************************************************************************
static unsigned long __Errorlog;
//*****************************************************************************
// Global variable indicating input length
//*****************************************************************************
unsigned int ilen=1;
//*****************************************************************************
//
//! Initialization
//!
//! This function
//! 1. Configures the UART to be used.
//!
//! \return none
//
//*****************************************************************************
void
InitTerm()
{
#ifndef NOTERM
MAP_UARTConfigSetExpClk(CONSOLE,MAP_PRCMPeripheralClockGet(CONSOLE_PERIPH),
UART_BAUD_RATE, (UART_CONFIG_WLEN_8 | UART_CONFIG_STOP_ONE |
UART_CONFIG_PAR_NONE));
#endif
__Errorlog = 0;
}
//*****************************************************************************
//
//! Outputs a character string to the console
//!
//! \param str is the pointer to the string to be printed
//!
//! This function
//! 1. prints the input string character by character on to the console.
//!
//! \return none
//
//*****************************************************************************
void
Message(const char *str)
{
#ifndef NOTERM
if(str != NULL)
{
while(*str!='\0')
{
MAP_UARTCharPut(CONSOLE,*str++);
}
}
#endif
}
//*****************************************************************************
//
//! Clear the console window
//!
//! This function
//! 1. clears the console window.
//!
//! \return none
//
//*****************************************************************************
void
ClearTerm()
{
Message("\33[2J\r");
}
//*****************************************************************************
//
//! Error Function
//!
//! \param
//!
//! \return none
//!
//*****************************************************************************
void
Error(char *pcFormat, ...)
{
#ifndef NOTERM
char cBuf[256];
va_list list;
va_start(list,pcFormat);
vsnprintf(cBuf,256,pcFormat,list);
Message(cBuf);
#endif
__Errorlog++;
}
//*****************************************************************************
//
//! Get the Command string from UART
//!
//! \param pucBuffer is the command store to which command will be populated
//! \param ucBufLen is the length of buffer store available
//!
//! \return Length of the bytes received. -1 if buffer length exceeded.
//!
//*****************************************************************************
int
GetCmd(char *pcBuffer, unsigned int uiBufLen)
{
char cChar;
int iLen = 0;
//
// Wait to receive a character over UART
//
while(MAP_UARTCharsAvail(CONSOLE) == false)
{
#if defined(USE_FREERTOS) || defined(USE_TI_RTOS)
osi_Sleep(1);
#endif
}
cChar = MAP_UARTCharGetNonBlocking(CONSOLE);
//
// Echo the received character
//
MAP_UARTCharPut(CONSOLE, cChar);
iLen = 0;
//
// Checking the end of Command
//
while((cChar != '\r') && (cChar !='\n') )
{
//
// Handling overflow of buffer
//
if(iLen >= uiBufLen)
{
return -1;
}
//
// Copying Data from UART into a buffer
//
if(cChar != '\b')
{
*(pcBuffer + iLen) = cChar;
iLen++;
}
else
{
//
// Deleting last character when you hit backspace
//
if(iLen)
{
iLen--;
}
}
//
// Wait to receive a character over UART
//
while(MAP_UARTCharsAvail(CONSOLE) == false)
{
#if defined(USE_FREERTOS) || defined(USE_TI_RTOS)
osi_Sleep(1);
#endif
}
cChar = MAP_UARTCharGetNonBlocking(CONSOLE);
//
// Echo the received character
//
MAP_UARTCharPut(CONSOLE, cChar);
}
*(pcBuffer + iLen) = '\0';
Report("\n\r");
return iLen;
}
//*****************************************************************************
//
//! Trim the spaces from left and right end of given string
//!
//! \param Input string on which trimming happens
//!
//! \return length of trimmed string
//
//*****************************************************************************
int TrimSpace(char * pcInput)
{
size_t size;
char *endStr, *strData = pcInput;
char index = 0;
size = strlen(strData);
if (!size)
return 0;
endStr = strData + size - 1;
while (endStr >= strData && IS_SPACE(*endStr))
endStr--;
*(endStr + 1) = '\0';
while (*strData && IS_SPACE(*strData))
{
strData++;
index++;
}
memmove(pcInput,strData,strlen(strData)+1);
return strlen(pcInput);
}
//*****************************************************************************
//
//! prints the formatted string on to the console
//!
//! \param format is a pointer to the character string specifying the format in
//! the following arguments need to be interpreted.
//! \param [variable number of] arguments according to the format in the first
//! parameters
//! This function
//! 1. prints the formatted error statement.
//!
//! \return count of characters printed
//
//*****************************************************************************
int Report(const char *pcFormat, ...)
{
int iRet = 0;
#ifndef NOTERM
char *pcBuff, *pcTemp;
int iSize = 256;
va_list list;
pcBuff = (char*)malloc(iSize);
if(pcBuff == NULL)
{
return -1;
}
while(1)
{
va_start(list,pcFormat);
iRet = vsnprintf(pcBuff,iSize,pcFormat,list);
va_end(list);
if(iRet > -1 && iRet < iSize)
{
break;
}
else
{
iSize*=2;
if((pcTemp=realloc(pcBuff,iSize))==NULL)
{
Message("Could not reallocate memory\n\r");
iRet = -1;
break;
}
else
{
pcBuff=pcTemp;
}
}
}
Message(pcBuff);
free(pcBuff);
#endif
return iRet;
}

94
common/uart_if.h Normal file
View File

@@ -0,0 +1,94 @@
//*****************************************************************************
// uart_if.h
//
// uart interface header file: Prototypes and Macros for UARTLogger
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#ifndef __uart_if_H__
#define __uart_if_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
/****************************************************************************/
/* MACROS */
/****************************************************************************/
#define UART_BAUD_RATE 115200
#define SYSCLK 80000000
#define CONSOLE UARTA0_BASE
#define CONSOLE_PERIPH PRCM_UARTA0
//
// Define the size of UART IF buffer for RX
//
#define UART_IF_BUFFER 64
//
// Define the UART IF buffer
//
extern unsigned char g_ucUARTBuffer[];
/****************************************************************************/
/* FUNCTION PROTOTYPES */
/****************************************************************************/
extern void DispatcherUARTConfigure(void);
extern void DispatcherUartSendPacket(unsigned char *inBuff, unsigned short usLength);
extern int GetCmd(char *pcBuffer, unsigned int uiBufLen);
extern void InitTerm(void);
extern void ClearTerm(void);
extern void Message(const char *format);
extern void Error(char *format,...);
extern int TrimSpace(char * pcInput);
extern int Report(const char *format, ...);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif

370
common/udma_if.c Normal file
View File

@@ -0,0 +1,370 @@
//*****************************************************************************
// udma_if.c
//
// uDMA interface file
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#include <stdio.h>
#include <string.h>
// Driverlib includes
#include "hw_ints.h"
#include "hw_memmap.h"
#include "hw_uart.h"
#include "hw_types.h"
#include "hw_udma.h"
#include "rom.h"
#include "rom_map.h"
#include "gpio.h"
#include "udma.h"
#include "interrupt.h"
#include "prcm.h"
#include "uart.h"
// TI-RTOS includes
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
#include <stdlib.h>
#include "osi.h"
#endif
#include "udma_if.h"
#define MAX_NUM_CH 64 //32*2 entries
#define CTL_TBL_SIZE 64 //32*2 entries
#define UDMA_CH5_BITID (1<<5)
//*****************************************************************************
// GLOBAL VARIABLES -- Start
//*****************************************************************************
volatile unsigned char iDone;
tAppCallbackHndl gfpAppCallbackHndl[MAX_NUM_CH];
#if defined(gcc)
tDMAControlTable gpCtlTbl[CTL_TBL_SIZE] __attribute__(( aligned(1024)));
#endif
#if defined(ccs)
#pragma DATA_ALIGN(gpCtlTbl, 1024)
tDMAControlTable gpCtlTbl[CTL_TBL_SIZE];
#endif
#if defined(ewarm)
#pragma data_alignment=1024
tDMAControlTable gpCtlTbl[CTL_TBL_SIZE];
#endif
//*****************************************************************************
// GLOBAL VARIABLES -- End
//*****************************************************************************
//*****************************************************************************
//
//! DMA software interrupt handler
//!
//! \param None
//!
//! This function
//! 1. Invoked when DMA operation is complete
//!
//! \return None.
//
//*****************************************************************************
void
DmaSwIntHandler(void)
{
unsigned long uiIntStatus;
iDone = 1;
uiIntStatus = MAP_uDMAIntStatus();
MAP_uDMAIntClear(uiIntStatus);
}
//*****************************************************************************
//
//! DMA error interrupt handler
//!
//! \param None
//!
//! This function
//! 1. Invoked when DMA operation is in error
//!
//! \return None.
//
//*****************************************************************************
void
DmaErrorIntHandler(void)
{
MAP_uDMAIntClear(MAP_uDMAIntStatus());
}
//*****************************************************************************
//
//! Initialize the DMA controller
//!
//! \param None
//!
//! This function initializes
//! 1. Initializes the McASP module
//!
//! \return None.
//
//*****************************************************************************
void UDMAInit()
{
unsigned int uiLoopCnt;
//
// Enable McASP at the PRCM module
//
MAP_PRCMPeripheralClkEnable(PRCM_UDMA,PRCM_RUN_MODE_CLK);
MAP_PRCMPeripheralReset(PRCM_UDMA);
//
// Register interrupt handlers
//
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
osi_InterruptRegister(INT_UDMA, DmaSwIntHandler, INT_PRIORITY_LVL_1);
osi_InterruptRegister(INT_UDMAERR, DmaErrorIntHandler, INT_PRIORITY_LVL_1);
#else
MAP_IntPrioritySet(INT_UDMA, INT_PRIORITY_LVL_1);
MAP_uDMAIntRegister(UDMA_INT_SW, DmaSwIntHandler);
MAP_IntPrioritySet(INT_UDMAERR, INT_PRIORITY_LVL_1);
MAP_uDMAIntRegister(UDMA_INT_ERR, DmaErrorIntHandler);
#endif
//
// Enable uDMA using master enable
//
MAP_uDMAEnable();
//
// Set Control Table
//
memset(gpCtlTbl,0,sizeof(tDMAControlTable)*CTL_TBL_SIZE);
MAP_uDMAControlBaseSet(gpCtlTbl);
//
// Reset App Callbacks
//
for(uiLoopCnt = 0; uiLoopCnt < MAX_NUM_CH; uiLoopCnt++)
{
gfpAppCallbackHndl[uiLoopCnt] = NULL;
}
}
//*****************************************************************************
//
//! Configures the uDMA channel
//!
//! \param uiChannel is the DMA channel to be selected
//! \param pfpAppCb is the application callback to be invoked on transfer
//!
//! This function
//! 1. Configures the uDMA channel
//!
//! \return None.
//
//*****************************************************************************
void UDMAChannelSelect(unsigned int uiChannel, tAppCallbackHndl pfpAppCb)
{
if((uiChannel & 0xFF) >= MAX_NUM_CH)
{
return;
}
MAP_uDMAChannelAssign(uiChannel);
MAP_uDMAChannelAttributeDisable(uiChannel,UDMA_ATTR_ALTSELECT);
gfpAppCallbackHndl[(uiChannel & 0xFF)] = pfpAppCb;
}
//*****************************************************************************
//
//! Sets up the Auto Memory transfer
//!
//! \param ulChannel. DMA Channel to be used
//! \param pvSrcBuf. Pointer to the source buffer
//! \param pvDstBuf. Pointer to the destination buffer
//! \param size. Items to be transfered(should not exceed 1024).
//!
//! This function
//! 1. Configures the uDMA channel
//!
//! \return None.
//
//*****************************************************************************
void UDMASetupAutoMemTransfer(unsigned long ulChannel, void *pvSrcBuf,
void *pvDstBuf, unsigned long size)
{
UDMASetupTransfer(ulChannel, UDMA_MODE_AUTO, size,
UDMA_SIZE_8, UDMA_ARB_8, pvSrcBuf,
UDMA_SRC_INC_8, pvDstBuf, UDMA_DST_INC_8);
}
//*****************************************************************************
//
//! Sets up the Ping Pong mode of transfer
//!
//! \param ulChannel. DMA Channel to be used
//! \param pvSrcBuf1.Pointer to the Source Buffer for Primary Control Structure
//! \param pvDstBuf1.Pointer to the Destination Buffer for Primary Structure
//! \param pvSrcBuf2.Pointer to the Source Buffer for alternate Control Structure
//! \param pvDstBuf2. Pointer to the Destination Buffer for alternate Structure
//! \param size. Total size to be transferred(should not exceed 1024).
//!
//! This function
//! 1. Configures the uDMA channel
//!
//! \return None.
//
//*****************************************************************************
void UDMASetupPingPongTransfer(unsigned long ulChannel, void *pvSrcBuf1,
void *pvDstBuf1, void *pvSrcBuf2,
void *pvDstBuf2, unsigned long size)
{
UDMASetupTransfer(ulChannel, UDMA_MODE_PINGPONG, size, UDMA_SIZE_8,
UDMA_ARB_8, pvSrcBuf1, UDMA_SRC_INC_8,
pvDstBuf1, UDMA_DST_INC_8);
UDMASetupTransfer(ulChannel|UDMA_ALT_SELECT, UDMA_MODE_PINGPONG, size,
UDMA_SIZE_8, UDMA_ARB_8, pvSrcBuf2, UDMA_SRC_INC_8,
pvDstBuf2, UDMA_DST_INC_8);
}
//*****************************************************************************
//
//! Start the DMA SW transfer
//!
//! \param None
//!
//! This function
//! 1. Starts the SW controlled uDMA transfer
//!
//! \return None.
//
//*****************************************************************************
void UDMAStartTransfer(unsigned long ulChannel)
{
//
// Request for channel transfer
//
MAP_uDMAChannelRequest(ulChannel);
}
//*****************************************************************************
//
//! Stop the DMA transfer
//!
//! \param None
//!
//! This function
//! 1. Stops the uDMA transfer on specified channel
//!
//! \return None.
//
//*****************************************************************************
void UDMAStopTransfer(unsigned long ulChannel)
{
//
// Disable the channel
//
MAP_uDMAChannelDisable(ulChannel);
}
//*****************************************************************************
//
//! De-Initialize the DMA controller
//!
//! \param None
//!
//! This function
//! 1. De-Initializes the uDMA module
//!
//! \return None.
//
//*****************************************************************************
void UDMADeInit()
{
//
// UnRegister interrupt handlers
//
MAP_uDMAIntUnregister(UDMA_INT_SW);
MAP_uDMAIntUnregister(UDMA_INT_ERR);
//
// Disable the uDMA
//
MAP_uDMADisable();
}
//*****************************************************************************
//
//! Does the actual Memory transfer
//!
//! \param ulChannel. DMA Channel to be used
//! \param ulMode. DMA Mode to be used
//! \param ulItemCount. Items to be transfered in DMA Transfer(should not exceed 1024)
//! \param ulArbSize. Arbitration Size to be set
//! \param pvSrcBuf. Pointer to the source Buffer
//! \param ulSrcInc. Source Increment
//! \param pvDstBuf. Pointer to the Destination Buffer
//! \param ulDstInc. Destination Increment
//!
//! This function
//! 1. Sets up the uDMA registers to perform the actual transfer
//!
//! \return None.
//
//*****************************************************************************
void UDMASetupTransfer(unsigned long ulChannel, unsigned long ulMode,
unsigned long ulItemCount, unsigned long ulItemSize,
unsigned long ulArbSize, void *pvSrcBuf,
unsigned long ulSrcInc, void *pvDstBuf,
unsigned long ulDstInc)
{
MAP_uDMAChannelControlSet(ulChannel, ulItemSize | ulSrcInc | ulDstInc | ulArbSize);
MAP_uDMAChannelAttributeEnable(ulChannel,UDMA_ATTR_USEBURST);
MAP_uDMAChannelTransferSet(ulChannel, ulMode, pvSrcBuf, pvDstBuf, ulItemCount);
MAP_uDMAChannelEnable(ulChannel);
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

95
common/udma_if.h Normal file
View File

@@ -0,0 +1,95 @@
//*****************************************************************************
// udma_if.h
//
// uDMA interface MACRO and function prototypes
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#ifndef __UDMA_IF_H__
#define __UDMA_IF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
#define PRINT_DBG printf
typedef void (*tAppCallbackHndl)(void);
#define MAX_NUM_CH 64 //32*2 entries
#define CTL_TBL_SIZE 64 //32*2 entries
#define UDMA_CH5_BITID (1<<5)
//
// UDMA Interface APIs
//
void UDMAInit();
void UDMAChannelSelect(unsigned int uiChannel, tAppCallbackHndl pfpAppCb);
void UDMASetupAutoMemTransfer(
unsigned long ulChannel,
void *pvSrcBuf,
void *pvDstBuf,
unsigned long size);
void UDMASetupPingPongTransfer(
unsigned long ulChannel,
void *pvSrcBuf1,
void *pvDstBuf1,
void *pvSrcBuf2,
void *pvDstBuf2,
unsigned long size);
void UDMAStartTransfer(unsigned long ulChannel);
void UDMAStopTransfer(unsigned long ulChannel);
void UDMADeInit();
void UDMASetupTransfer(unsigned long ulChannel, unsigned long ulMode,
unsigned long ulItemCount, unsigned long ulItemSize,
unsigned long ulArbSize, void *pvSrcBuf,
unsigned long ulSrcInc, void *pvDstBuf, unsigned long ulDstInc);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __UDMA_IF_H__

212
common/utils_if.c Normal file
View File

@@ -0,0 +1,212 @@
//*****************************************************************************
// utils_if.c
//
// Contains utility routines.
//
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#include <stdint.h>
#include <stdbool.h>
#include "hw_types.h"
#include "hw_memmap.h"
#include "rom.h"
#include "rom_map.h"
#include "hwspinlock.h"
#include "prcm.h"
#include "spi.h"
//*****************************************************************************
//
//! \addtogroup utils_if_api
//! @{
//
//*****************************************************************************
//*****************************************************************************
// Defines.
//*****************************************************************************
#define INSTR_READ_STATUS 0x05
#define INSTR_DEEP_POWER_DOWN 0xB9
#define STATUS_BUSY 0x01
#define MAX_SEMAPHORE_TAKE_TRIES (4000000)
//****************************************************************************
//
//! Put SPI flash into Deep Power Down mode
//!
//! Note:SPI flash is a shared resource between MCU and Network processing
//! units. This routine should only be exercised after all the network
//! processing has been stopped. To stop network processing use sl_stop API
//! \param None
//!
//! \return Status, 0:Pass, -1:Fail
//
//****************************************************************************
int Utils_SpiFlashDeepPowerDown(void)
{
unsigned long ulStatus=0;
//
// Acquire SSPI HwSpinlock.
//
if (0 != MAP_HwSpinLockTryAcquire(HWSPINLOCK_SSPI, MAX_SEMAPHORE_TAKE_TRIES))
{
return -1;
}
//
// Enable clock for SSPI module
//
MAP_PRCMPeripheralClkEnable(PRCM_SSPI, PRCM_RUN_MODE_CLK);
//
// Reset SSPI at PRCM level and wait for reset to complete
//
MAP_PRCMPeripheralReset(PRCM_SSPI);
while(MAP_PRCMPeripheralStatusGet(PRCM_SSPI)== false)
{
}
//
// Reset SSPI at module level
//
MAP_SPIReset(SSPI_BASE);
//
// Configure SSPI module
//
MAP_SPIConfigSetExpClk(SSPI_BASE,PRCMPeripheralClockGet(PRCM_SSPI),
20000000,SPI_MODE_MASTER,SPI_SUB_MODE_0,
(SPI_SW_CTRL_CS |
SPI_4PIN_MODE |
SPI_TURBO_OFF |
SPI_CS_ACTIVELOW |
SPI_WL_8));
//
// Enable SSPI module
//
MAP_SPIEnable(SSPI_BASE);
//
// Enable chip select for the spi flash.
//
MAP_SPICSEnable(SSPI_BASE);
//
// Wait for spi flash.
//
do
{
//
// Send the status register read instruction and read back a dummy byte.
//
MAP_SPIDataPut(SSPI_BASE,INSTR_READ_STATUS);
MAP_SPIDataGet(SSPI_BASE,&ulStatus);
//
// Write a dummy byte then read back the actual status.
//
MAP_SPIDataPut(SSPI_BASE,0xFF);
MAP_SPIDataGet(SSPI_BASE,&ulStatus);
}
while((ulStatus & 0xFF )== STATUS_BUSY);
//
// Disable chip select for the spi flash.
//
MAP_SPICSDisable(SSPI_BASE);
//
// Start another CS enable sequence for Power down command.
//
MAP_SPICSEnable(SSPI_BASE);
//
// Send Deep Power Down command to spi flash
//
MAP_SPIDataPut(SSPI_BASE,INSTR_DEEP_POWER_DOWN);
//
// Disable chip select for the spi flash.
//
MAP_SPICSDisable(SSPI_BASE);
//
// Release SSPI HwSpinlock.
//
MAP_HwSpinLockRelease(HWSPINLOCK_SSPI);
//
// Return as Pass.
//
return 0;
}
//****************************************************************************
//
//! Used to trigger a hibernate cycle for the SOC
//!
//! Note:This routine should only be exercised after all the network
//! processing has been stopped. To stop network processing use sl_stop API
//! \param None
//!
//! \return None
//
//****************************************************************************
void Utils_TriggerHibCycle(void)
{
//
// Configure the HIB module RTC wake time
//
MAP_PRCMHibernateIntervalSet(330);
//
// Enable the HIB RTC
//
MAP_PRCMHibernateWakeupSourceEnable(PRCM_HIB_SLOW_CLK_CTR);
//
// Enter HIBernate mode
//
MAP_PRCMHibernateEnter();
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

70
common/utils_if.h Normal file
View File

@@ -0,0 +1,70 @@
//*****************************************************************************
// utils_if.h
//
// Utils interface MACRO and function prototypes
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#ifndef __UTILS_IF_H__
#define __UTILS_IF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//
// Utils Interface APIs
//
int Utils_SpiFlashDeepPowerDown(void);
void Utils_TriggerHibCycle(void);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __UTILS_IF_H__

145
common/wdt_if.c Normal file
View File

@@ -0,0 +1,145 @@
//*****************************************************************************
// wdt_if.c
//
// watchdog timer interface APIs
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#include <stdio.h>
#include "hw_types.h"
#include "hw_ints.h"
#include "hw_memmap.h"
#include "prcm.h"
#include "wdt.h"
#include "rom.h"
#include "rom_map.h"
#include "interrupt.h"
#include "wdt_if.h"
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
#include "osi.h"
#endif
/****************************************************************************/
/* FUNCTION DEFINITIONS */
/****************************************************************************/
//****************************************************************************
//
//! Initialize the watchdog timer
//!
//! \param fpAppWDTCB is the WDT interrupt handler to be registered
//! \param uiReloadVal is the reload value to be set to the WDT
//!
//! This function
//! 1. Initializes the WDT
//!
//! \return None.
//
//****************************************************************************
void WDT_IF_Init(fAPPWDTDevCallbk fpAppWDTCB,
unsigned int uiReloadVal)
{
//
// Enable the peripherals used by this example.
//
MAP_PRCMPeripheralClkEnable(PRCM_WDT, PRCM_RUN_MODE_CLK);
//
// Unlock to be able to configure the registers
//
MAP_WatchdogUnlock(WDT_BASE);
if(fpAppWDTCB != NULL)
{
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
osi_InterruptRegister(INT_WDT, fpAppWDTCB, INT_PRIORITY_LVL_1);
#else
MAP_IntPrioritySet(INT_WDT, INT_PRIORITY_LVL_1);
MAP_WatchdogIntRegister(WDT_BASE,fpAppWDTCB);
#endif
}
//
// Set the watchdog timer reload value
//
MAP_WatchdogReloadSet(WDT_BASE,uiReloadVal);
//
// Start the timer. Once the timer is started, it cannot be disable.
//
MAP_WatchdogEnable(WDT_BASE);
}
//****************************************************************************
//
//! DeInitialize the watchdog timer
//!
//! \param None
//!
//! This function
//! 1. DeInitializes the WDT
//!
//! \return None.
//
//****************************************************************************
void WDT_IF_DeInit()
{
//
// Unlock to be able to configure the registers
//
MAP_WatchdogUnlock(WDT_BASE);
//
// Disable stalling of the watchdog timer during debug events
//
MAP_WatchdogStallDisable(WDT_BASE);
//
// Clear the interrupt
//
MAP_WatchdogIntClear(WDT_BASE);
//
// Unregister the interrupt
//
MAP_WatchdogIntUnregister(WDT_BASE);
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

79
common/wdt_if.h Normal file
View File

@@ -0,0 +1,79 @@
//*****************************************************************************
// wdt_if.h
//
// Defines and Macros for the WDT interface.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated 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
// OWNER 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.
//
//*****************************************************************************
#ifndef __WDTIF_H__
#define __WDTIF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// Typedef that can be passed to InitializeGPTOneShot as the fAPPDevCallbk
// parameter.
//
//*****************************************************************************
typedef void (*fAPPWDTDevCallbk)();
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void WDT_IF_Init(fAPPWDTDevCallbk fpAppWDTCB,
unsigned int uiReloadVal);
extern void WDT_IF_DeInit();
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __WDTIF_H__