Initial commit

This commit is contained in:
pg 2015-11-28 19:30:17 +01:00
commit be47a7615f
43 changed files with 21388 additions and 0 deletions

BIN
.main.c.swp Normal file

Binary file not shown.

46
README.md Normal file
View File

@ -0,0 +1,46 @@
ble_app_uart-example
==================
This project contains code examples that show nrf51 UART functionality with the app_uart library.
Instructions on how to operate the example is given at the top of the main file in the example.
Requirements
------------
- nRF51 SDK version 6.1.0
- S110 SoftDevice version 7.0.0
- nRF51822 Development Kit version 2.1.0 or later
- python 2.7 (3.x?)
- PyBLEWrapper https://github.com/brettchien/PyBLEWrapper.git
To compile it, clone the repository in the \nrf51822\Board\nrf6310\S110\ folder.
Build and run
-------------
* Compile
```
cd gcc && make
```
* Flashing nrf firmaware on OSX 10.8
```
sudo mount -u -w -o sync /Volumes/MBED
srec_cat /Users/pg/code/blenano/s110_nrf51822_7.3.0_softdevice.hex -intel _build/ble_app_uart_s110_xxaa.hex -intel -o _build/uart.hex -intel --line-length=44
cp -X _build/uart.hex /Volumes/MBED/
sudo rm /Library/Preferences/com.apple.Bluetooth.plist
pkill bluez
```
* Run python script and monitor serial port
```
python python/test.py
```
```python
import sys
import serial
s=serial.Serial("/dev/tty.usbmodem1412")
while True : sys.stdout.write( s.read() )
```

616
app_uart_fifo_mod.c Normal file
View File

@ -0,0 +1,616 @@
/* Copyright (c) 2013 Nordic Semiconductor. All Rights Reserved.
*
* The information contained herein is property of Nordic Semiconductor ASA.
* Terms and conditions of usage are described in detail in NORDIC
* SEMICONDUCTOR STANDARD SOFTWARE LICENSE AGREEMENT.
*
* Licensees are granted free, non-transferable use of the information. NO
* WARRANTY of ANY KIND is provided. This heading must NOT be removed from
* the file.
*
*/
#include "app_uart.h"
#include "app_fifo.h"
#include "nrf.h"
#include "nrf_gpio.h"
#include "app_error.h"
#include "app_util.h"
#include "app_gpiote.h"
#define FIFO_LENGTH(F) (F.write_pos - F.read_pos) /**< Macro to calculate length of a FIFO. */
#define UART_INSTANCE_GPIOTE_BASE 0x00FF /**< Define the base for UART instance ID when flow control is used. The userid from GPIOTE will be used with padded 0xFF at LSB for easy converting the instance id to GPIOTE id. */
#define UART_INSTANCE_ID_INVALID 0x0000 /**< Value 0x0000 is used to indicate an invalid instance id. When 0 is provided as instance id upon initialization, the module will provide a valid id to the caller. */
/** @brief States for the app_uart state machine. */
typedef enum
{
UART_OFF, /**< app_uart state OFF, indicating CTS is low. */
UART_READY, /**< app_uart state ON, indicating CTS is high. */
UART_ON, /**< app_uart state TX, indicating UART is ongoing transmitting data. */
UART_WAIT_CLOSE, /**< app_uart state WAIT CLOSE, indicating that CTS is low, but a byte is currently being transmitted on the line. */
} app_uart_states_t;
/** @brief State transition events for the app_uart state machine. */
typedef enum
{
ON_CTS_HIGH, /**< Event: CTS gone high. */
ON_CTS_LOW, /**< Event: CTS gone low. */
ON_UART_PUT, /**< Event: Application wants to transmit data. */
ON_TX_READY, /**< Event: Data has been transmitted on the uart and line is available. */
ON_UART_CLOSE, /**< Event: The UART module are being stopped. */
} app_uart_state_events_t;
static app_fifo_t m_rx_fifo; /**< RX FIFO buffer for storing data received on the UART until the application fetches them using app_uart_get(). */
static app_fifo_t m_tx_fifo; /**< TX FIFO buffer for storing data to be transmitted on the UART when TXD is ready. Data is put to the buffer on using app_uart_put(). */
static uint8_t m_instance_counter = 1; /**< Instance counter for each caller using the UART module. The GPIOTE user id is mapped directly for callers using HW Flow Control. */
static app_gpiote_user_id_t m_gpiote_uid; /**< GPIOTE id for currently active caller to the UART module. */
static uint32_t m_pin_cts_mask; /**< CTS pin mask for UART module. */
static app_uart_event_handler_t m_event_handler; /**< Event handler function. */
static volatile app_uart_states_t m_current_state = UART_OFF; /**< State of the state machine. */
/**@brief Function for disabling the UART when entering the UART_OFF state.
*/
static void action_uart_deactivate(void)
{
m_current_state = UART_OFF;
NRF_UART0->TASKS_STOPTX = 1;
NRF_UART0->TASKS_STOPRX = 1;
NRF_UART0->ENABLE = (UART_ENABLE_ENABLE_Disabled << UART_ENABLE_ENABLE_Pos);
}
void action_tx_stop()
{
app_uart_evt_t app_uart_event;
// No more bytes in FIFO, terminate transmission.
NRF_UART0->TASKS_STOPTX = 1;
m_current_state = UART_READY;
// Last byte from FIFO transmitted, notify the application.
// Notify that new data is available if this was first byte put in the buffer.
app_uart_event.evt_type = APP_UART_TX_EMPTY;
m_event_handler(&app_uart_event);
}
/**@brief Function for sending the next byte in the TX buffer. Called when (re-)entering the UART_ON state.
* If no more data is available in the TX buffer, the state machine will enter UART_READY state.
*/
static void action_tx_send()
{
uint8_t tx_byte;
if (m_current_state != UART_ON)
{
// Start the UART.
NRF_UART0->TASKS_STARTTX = 1;
}
if (app_fifo_get(&m_tx_fifo, &tx_byte) != NRF_SUCCESS)
{
action_tx_stop();
return;
}
NRF_UART0->INTENCLR = (UART_INTENSET_TXDRDY_Set << UART_INTENSET_TXDRDY_Pos);
NRF_UART0->TXD = tx_byte;
m_current_state = UART_ON;
NRF_UART0->INTENSET = (UART_INTENSET_TXDRDY_Set << UART_INTENSET_TXDRDY_Pos);
}
static void action_tx_ready()
{
// Get next byte from FIFO.
if (FIFO_LENGTH(m_tx_fifo) != 0)
{
action_tx_send();
}
else
{
action_tx_stop();
}
}
/**@brief Function for the handling of the ON_CTS_HIGH event.
*/
static void on_cts_high(void)
{
switch (m_current_state)
{
case UART_READY:
action_uart_deactivate();
break;
case UART_ON:
m_current_state = UART_WAIT_CLOSE;
break;
default:
// Nothing to do.
break;
}
}
/**@brief Function for the handling of the ON_CTS_LOW event.
*/
static void on_cts_low(void)
{
switch (m_current_state)
{
case UART_OFF:
NRF_UART0->ENABLE = (UART_ENABLE_ENABLE_Enabled << UART_ENABLE_ENABLE_Pos);
NRF_UART0->TASKS_STARTRX = 1;
if (FIFO_LENGTH(m_tx_fifo) != 0)
{
action_tx_send();
}
else
{
m_current_state = UART_READY;
}
break;
case UART_WAIT_CLOSE:
m_current_state = UART_ON;
break;
default:
// Nothing to do.
break;
}
}
/**@brief Function for the handling of the ON_TX_READY event.
*/
static void on_tx_ready(void)
{
switch (m_current_state)
{
case UART_WAIT_CLOSE:
action_uart_deactivate();
break;
case UART_ON:
case UART_READY:
action_tx_ready();
break;
default:
// Nothing to do.
break;
}
}
/**@brief Function for the handling of the ON_UART_PUT event when application has put data in the TX buffer.
*/
static void on_uart_put(void)
{
if (m_current_state == UART_READY)
{
action_tx_send();
}
}
/**@brief Function for the handling of the ON_UART_CLOSE event when application is closing the UART module.
*/
static void on_uart_close(void)
{
action_uart_deactivate();
}
/**@brief Function for the state machine main event handler.
*
* @param[in] event Event that has occurred.
*/
static void on_uart_event(app_uart_state_events_t event)
{
switch (event)
{
case ON_CTS_HIGH:
on_cts_high();
break;
case ON_CTS_LOW:
on_cts_low();
break;
case ON_TX_READY:
on_tx_ready();
break;
case ON_UART_PUT:
on_uart_put();
break;
case ON_UART_CLOSE:
on_uart_close();
break;
default:
// All valid events are handled above.
break;
}
}
/**@brief Function for the GPIOTE event handler.
*
* @param[in] event_pins_low_to_high Mask telling which pin(s) generated an event from low->high.
* @param[in] event_pins_high_to_low Mask telling which pin(s) generated an event from high->low.
*/
static void gpiote_uart_event_handler(uint32_t event_pins_low_to_high,
uint32_t event_pins_high_to_low)
{
if ((event_pins_high_to_low & event_pins_low_to_high & m_pin_cts_mask) != 0)
{
// We have an indication from GPIOTE that the CTS pin has toggled high->low and low->high.
// If this occurs, we must read the active pins in the GPIOTE module ourself.
uint32_t active_pins;
uint32_t err_code;
err_code = app_gpiote_pins_state_get(m_gpiote_uid, &active_pins);
if (err_code != NRF_SUCCESS)
{
// Pin reading was not possible, even though an event from GPIOTE was received that the
// CTS pin toggled. If pin double toggled but status cannot be fetched we silently
// return and keep the current UART status as-is.
return;
}
event_pins_low_to_high &= active_pins;
event_pins_high_to_low &= ~active_pins;
}
if ((event_pins_high_to_low & m_pin_cts_mask) != 0)
{
on_uart_event(ON_CTS_LOW);
}
else if ((event_pins_low_to_high & m_pin_cts_mask) != 0)
{
on_uart_event(ON_CTS_HIGH);
}
else
{
// Do nothing, as the CTS pin didn't toggle.
}
}
/**@brief Function for the UART Interrupt handler.
*
* @details UART interrupt handler to process TX Ready when TXD is available, RX Ready when a byte
* is received, or in case of error when receiving a byte.
*/
void UART0_IRQHandler(void)
{
// Handle reception
if (NRF_UART0->EVENTS_RXDRDY != 0)
{
// Clear UART RX event flag
NRF_UART0->EVENTS_RXDRDY = 0;
// Write received byte to FIFO
// Read the RXD hardware register only if the RX FIFO can store it (i.e. not full),
// or the RXD value will be LOST ! When the RX FIFO is full, if HFC (Hardware Flow Control) is used,
// the UART stream will be stopped automatically using the CTS line until a byte has been read from the RX FIFO
// and the RXD register cleared by a read operation.
if(FIFO_LENGTH(m_rx_fifo) <= m_rx_fifo.buf_size_mask)
{
app_fifo_put(&m_rx_fifo, (uint8_t)NRF_UART0->RXD); // Always return NRF_SUCCESS
if (FIFO_LENGTH(m_rx_fifo) == 1)
{
app_uart_evt_t app_uart_event;
app_uart_event.evt_type = APP_UART_DATA_READY;
m_event_handler(&app_uart_event);
}
}
else {
// TODO: send a custom event to indicate that the UART RX FIFO is full ?
// If HFC is used, new data can be sent only after reading the FIFO
// If not, some RX data will be lost !
}
}
// Handle transmission.
if (NRF_UART0->EVENTS_TXDRDY != 0)
{
// Clear UART TX event flag.
NRF_UART0->EVENTS_TXDRDY = 0;
on_uart_event(ON_TX_READY);
}
// Handle errors.
if (NRF_UART0->EVENTS_ERROR != 0)
{
uint32_t error_source;
app_uart_evt_t app_uart_event;
// Clear UART ERROR event flag.
NRF_UART0->EVENTS_ERROR = 0;
// Clear error source.
error_source = NRF_UART0->ERRORSRC;
NRF_UART0->ERRORSRC = error_source;
app_uart_event.evt_type = APP_UART_COMMUNICATION_ERROR;
app_uart_event.data.error_communication = error_source;
m_event_handler(&app_uart_event);
}
}
/**@brief Function for initialization of UART when flow control is disabled.
*/
static void uart_no_flow_control_init(void)
{
NRF_UART0->ENABLE = (UART_ENABLE_ENABLE_Enabled << UART_ENABLE_ENABLE_Pos);
NRF_UART0->EVENTS_RXDRDY = 0;
NRF_UART0->EVENTS_TXDRDY = 0;
NRF_UART0->CONFIG &= ~(UART_CONFIG_HWFC_Enabled << UART_CONFIG_HWFC_Pos);
NRF_UART0->PSELRTS = UART_PIN_DISCONNECTED;
NRF_UART0->PSELCTS = UART_PIN_DISCONNECTED;
NRF_UART0->TASKS_STARTTX = 1;
NRF_UART0->TASKS_STARTRX = 1;
}
/**@brief Function for initialization of UART when standard flow control is enabled.
*/
static void uart_standard_flow_control_init(const app_uart_comm_params_t * p_comm_params)
{
NRF_UART0->ENABLE = (UART_ENABLE_ENABLE_Enabled << UART_ENABLE_ENABLE_Pos);
NRF_UART0->EVENTS_RXDRDY = 0;
NRF_UART0->EVENTS_TXDRDY = 0;
NRF_UART0->CONFIG |= (UART_CONFIG_HWFC_Enabled << UART_CONFIG_HWFC_Pos);
NRF_UART0->PSELCTS = p_comm_params->cts_pin_no;
NRF_UART0->PSELRTS = p_comm_params->rts_pin_no;
NRF_UART0->TASKS_STARTTX = 1;
NRF_UART0->TASKS_STARTRX = 1;
}
uint32_t app_uart_init(const app_uart_comm_params_t * p_comm_params,
app_uart_buffers_t * p_buffers,
app_uart_event_handler_t event_handler,
app_irq_priority_t irq_priority,
uint16_t * p_app_uart_uid)
{
uint32_t err_code;
uint32_t gpiote_high_pins;
uint32_t gpiote_pin_low_high_mask = 0;
uint32_t gpiote_pin_high_low_mask = 0;
m_current_state = UART_OFF;
m_event_handler = event_handler;
if (p_buffers == NULL)
{
return NRF_ERROR_INVALID_PARAM;
}
// Configure buffer RX buffer.
err_code = app_fifo_init(&m_rx_fifo, p_buffers->rx_buf, p_buffers->rx_buf_size);
if (err_code != NRF_SUCCESS)
{
// Propagate error code.
return err_code;
}
// Configure buffer TX buffer.
err_code = app_fifo_init(&m_tx_fifo, p_buffers->tx_buf, p_buffers->tx_buf_size);
if (err_code != NRF_SUCCESS)
{
// Propagate error code.
return err_code;
}
// Configure RX and TX pins.
nrf_gpio_cfg_output(p_comm_params->tx_pin_no);
nrf_gpio_cfg_input(p_comm_params->rx_pin_no, NRF_GPIO_PIN_NOPULL);
NRF_UART0->PSELTXD = p_comm_params->tx_pin_no;
NRF_UART0->PSELRXD = p_comm_params->rx_pin_no;
// Configure baud rate and parity.
NRF_UART0->BAUDRATE = (p_comm_params->baud_rate << UART_BAUDRATE_BAUDRATE_Pos);
if (p_comm_params->use_parity)
{
NRF_UART0->CONFIG = (UART_CONFIG_PARITY_Included << UART_CONFIG_PARITY_Pos);
}
else
{
NRF_UART0->CONFIG = (UART_CONFIG_PARITY_Excluded << UART_CONFIG_PARITY_Pos);
}
if (p_comm_params->flow_control == APP_UART_FLOW_CONTROL_LOW_POWER)
{
// Configure hardware flow control.
nrf_gpio_cfg_output(p_comm_params->rts_pin_no);
NRF_GPIO->OUT = 1 << p_comm_params->rts_pin_no;
NRF_UART0->PSELCTS = UART_PIN_DISCONNECTED;
NRF_UART0->PSELRTS = p_comm_params->rts_pin_no;
NRF_UART0->CONFIG |= (UART_CONFIG_HWFC_Enabled << UART_CONFIG_HWFC_Pos);
// Setup the gpiote to handle pin events on cts-pin.
// For the UART we want to detect both low->high and high->low transitions in order to
// know when to activate/de-activate the TX/RX in the UART.
// Configure pin.
m_pin_cts_mask = (1 << p_comm_params->cts_pin_no);
nrf_gpio_cfg_sense_input(p_comm_params->cts_pin_no, NRF_GPIO_PIN_NOPULL, NRF_GPIO_PIN_SENSE_LOW);
gpiote_pin_low_high_mask = (1 << p_comm_params->cts_pin_no);
gpiote_pin_high_low_mask = (1 << p_comm_params->cts_pin_no);
if (*p_app_uart_uid == UART_INSTANCE_ID_INVALID)
{
err_code = app_gpiote_user_register(&m_gpiote_uid,
gpiote_pin_low_high_mask,
gpiote_pin_high_low_mask,
gpiote_uart_event_handler);
if (err_code != NRF_SUCCESS)
{
return err_code;
}
*p_app_uart_uid = (m_gpiote_uid << 8) | UART_INSTANCE_GPIOTE_BASE;
}
else if (*p_app_uart_uid < UART_INSTANCE_GPIOTE_BASE)
{
return NRF_ERROR_INVALID_PARAM;
}
else
{
m_gpiote_uid = ((*p_app_uart_uid) >> 8) & UART_INSTANCE_GPIOTE_BASE;
}
err_code = app_gpiote_pins_state_get(m_gpiote_uid, &gpiote_high_pins);
if (err_code != NRF_SUCCESS)
{
return err_code;
}
err_code = app_gpiote_user_enable(m_gpiote_uid);
if (err_code != NRF_SUCCESS)
{
return err_code;
}
// UART CTS pin is active when low.
if ((gpiote_high_pins & (1 << p_comm_params->cts_pin_no)) == 0)
{
on_uart_event(ON_CTS_LOW);
}
else
{
on_uart_event(ON_CTS_HIGH);
}
}
else if (p_comm_params->flow_control == APP_UART_FLOW_CONTROL_ENABLED)
{
if (*p_app_uart_uid == UART_INSTANCE_ID_INVALID)
{
*p_app_uart_uid = m_instance_counter++;
}
uart_standard_flow_control_init(p_comm_params);
m_current_state = UART_READY;
}
else
{
if (*p_app_uart_uid == UART_INSTANCE_ID_INVALID)
{
*p_app_uart_uid = m_instance_counter++;
}
uart_no_flow_control_init();
m_current_state = UART_READY;
}
// Enable UART interrupt
NRF_UART0->INTENCLR = 0xffffffffUL;
NRF_UART0->INTENSET = (UART_INTENSET_RXDRDY_Set << UART_INTENSET_RXDRDY_Pos) |
(UART_INTENSET_TXDRDY_Set << UART_INTENSET_TXDRDY_Pos) |
(UART_INTENSET_ERROR_Set << UART_INTENSET_ERROR_Pos);
NVIC_ClearPendingIRQ(UART0_IRQn);
NVIC_SetPriority(UART0_IRQn, irq_priority);
NVIC_EnableIRQ(UART0_IRQn);
return NRF_SUCCESS;
}
uint32_t app_uart_get(uint8_t * p_byte)
{
// Cannot read the RXD byte here. Must be done in the IRQ handler only.
/* NVIC_DisableIRQ(UART0_IRQn);
uint32_t retval = app_fifo_get(&m_rx_fifo, p_byte);
if(rx_fifo_overflow && retval == NRF_SUCCESS)
{
app_fifo_put(&m_rx_fifo, (uint8_t)NRF_UART0->RXD);
}
NVIC_EnableIRQ(UART0_IRQn);
return retval; */
return app_fifo_get(&m_rx_fifo, p_byte);
}
uint32_t app_uart_put(uint8_t byte)
{
uint32_t err_code;
err_code = app_fifo_put(&m_tx_fifo, byte);
if(err_code == NRF_SUCCESS)
on_uart_event(ON_UART_PUT); // Ignore if FIFO is full
return err_code;
}
uint32_t app_uart_flush(void)
{
uint32_t err_code;
err_code = app_fifo_flush(&m_rx_fifo);
if (err_code != NRF_SUCCESS)
{
return err_code;
}
err_code = app_fifo_flush(&m_tx_fifo);
if (err_code != NRF_SUCCESS)
{
return err_code;
}
return NRF_SUCCESS;
}
uint32_t app_uart_get_connection_state(app_uart_connection_state_t * p_conn_state)
{
*p_conn_state = ((m_current_state == UART_OFF) ? APP_UART_DISCONNECTED : APP_UART_CONNECTED);
return NRF_SUCCESS;
}
uint32_t app_uart_close(uint16_t app_uart_uid)
{
uint16_t gpiote_uid;
if (app_uart_uid < UART_INSTANCE_GPIOTE_BASE)
{
on_uart_event(ON_UART_CLOSE);
return NRF_SUCCESS;
}
gpiote_uid = (app_uart_uid >> 8) & UART_INSTANCE_GPIOTE_BASE;
if (gpiote_uid != m_gpiote_uid)
{
return NRF_ERROR_INVALID_PARAM;
}
on_uart_event(ON_UART_CLOSE);
return app_gpiote_user_disable(m_gpiote_uid);
}

512
arm/ble_app_uart.uvopt Normal file
View File

@ -0,0 +1,512 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<ProjectOpt xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_opt.xsd">
<SchemaVersion>1.0</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Extensions>
<cExt>*.c</cExt>
<aExt>*.s*; *.src; *.a*</aExt>
<oExt>*.obj</oExt>
<lExt>*.lib</lExt>
<tExt>*.txt; *.h; *.inc</tExt>
<pExt>*.plm</pExt>
<CppX>*.cpp</CppX>
</Extensions>
<DaveTm>
<dwLowDateTime>0</dwLowDateTime>
<dwHighDateTime>0</dwHighDateTime>
</DaveTm>
<Target>
<TargetName>nrf51822_xxaa_s110 (256K)</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<CLKADS>16000000</CLKADS>
<OPTTT>
<gFlags>1</gFlags>
<BeepAtEnd>1</BeepAtEnd>
<RunSim>0</RunSim>
<RunTarget>1</RunTarget>
</OPTTT>
<OPTHX>
<HexSelection>1</HexSelection>
<FlashByte>65535</FlashByte>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
</OPTHX>
<OPTLEX>
<PageWidth>79</PageWidth>
<PageLength>66</PageLength>
<TabStop>8</TabStop>
<ListingPath>.\_build\</ListingPath>
</OPTLEX>
<ListingPage>
<CreateCListing>1</CreateCListing>
<CreateAListing>1</CreateAListing>
<CreateLListing>1</CreateLListing>
<CreateIListing>0</CreateIListing>
<AsmCond>1</AsmCond>
<AsmSymb>1</AsmSymb>
<AsmXref>0</AsmXref>
<CCond>1</CCond>
<CCode>0</CCode>
<CListInc>0</CListInc>
<CSymb>0</CSymb>
<LinkerCodeListing>0</LinkerCodeListing>
</ListingPage>
<OPTXL>
<LMap>1</LMap>
<LComments>1</LComments>
<LGenerateSymbols>1</LGenerateSymbols>
<LLibSym>1</LLibSym>
<LLines>1</LLines>
<LLocSym>1</LLocSym>
<LPubSym>1</LPubSym>
<LXref>0</LXref>
<LExpSel>0</LExpSel>
</OPTXL>
<OPTFL>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<IsCurrentTarget>1</IsCurrentTarget>
</OPTFL>
<CpuCode>0</CpuCode>
<DebugOpt>
<uSim>0</uSim>
<uTrg>1</uTrg>
<sLdApp>1</sLdApp>
<sGomain>1</sGomain>
<sRbreak>1</sRbreak>
<sRwatch>1</sRwatch>
<sRmem>1</sRmem>
<sRfunc>1</sRfunc>
<sRbox>1</sRbox>
<tLdApp>1</tLdApp>
<tGomain>1</tGomain>
<tRbreak>1</tRbreak>
<tRwatch>1</tRwatch>
<tRmem>1</tRmem>
<tRfunc>0</tRfunc>
<tRbox>1</tRbox>
<tRtrace>0</tRtrace>
<sRSysVw>1</sRSysVw>
<tRSysVw>1</tRSysVw>
<tPdscDbg>1</tPdscDbg>
<sRunDeb>0</sRunDeb>
<sLrtime>0</sLrtime>
<nTsel>6</nTsel>
<sDll></sDll>
<sDllPa></sDllPa>
<sDlgDll></sDlgDll>
<sDlgPa></sDlgPa>
<sIfile></sIfile>
<tDll></tDll>
<tDllPa></tDllPa>
<tDlgDll></tDlgDll>
<tDlgPa></tDlgPa>
<tIfile></tIfile>
<pMon>Segger\JL2CM3.dll</pMon>
</DebugOpt>
<TargetDriverDllRegistry>
<SetRegEntry>
<Number>0</Number>
<Key>DLGTARM</Key>
<Name>(1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>ARMDBGFLAGS</Key>
<Name></Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>DLGUARM</Key>
<Name></Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>UL2CM3</Key>
<Name>UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0nrf51xxx -FS00 -FL0200000 -FP0($$Device:nRF51822_xxAA$Flash\nrf51xxx.flm))</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>JL2CM3</Key>
<Name>-U480209265 -O78 -S0 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -N00("ARM CoreSight SW-DP") -D00(0BB11477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8004 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO15 -FD20000000 -FC2000 -FN1 -FF0nrf51xxx -FS00 -FL0200000</Name>
</SetRegEntry>
</TargetDriverDllRegistry>
<Breakpoint/>
<Tracepoint>
<THDelay>0</THDelay>
</Tracepoint>
<DebugFlag>
<trace>0</trace>
<periodic>0</periodic>
<aLwin>1</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
<aPa>0</aPa>
<viewmode>1</viewmode>
<vrSel>0</vrSel>
<aSym>0</aSym>
<aTbox>0</aTbox>
<AscS1>0</AscS1>
<AscS2>0</AscS2>
<AscS3>0</AscS3>
<aSer3>0</aSer3>
<eProf>0</eProf>
<aLa>0</aLa>
<aPa1>0</aPa1>
<AscS4>0</AscS4>
<aSer4>0</aSer4>
<StkLoc>0</StkLoc>
<TrcWin>0</TrcWin>
<newCpu>0</newCpu>
<uProt>0</uProt>
</DebugFlag>
<LintExecutable></LintExecutable>
<LintConfigFile></LintConfigFile>
</TargetOption>
</Target>
<Target>
<TargetName>nrf51822_xxab_s110 (128K)</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<CLKADS>16000000</CLKADS>
<OPTTT>
<gFlags>0</gFlags>
<BeepAtEnd>1</BeepAtEnd>
<RunSim>1</RunSim>
<RunTarget>0</RunTarget>
</OPTTT>
<OPTHX>
<HexSelection>1</HexSelection>
<FlashByte>65535</FlashByte>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
</OPTHX>
<OPTLEX>
<PageWidth>79</PageWidth>
<PageLength>66</PageLength>
<TabStop>8</TabStop>
<ListingPath>.\_build\</ListingPath>
</OPTLEX>
<ListingPage>
<CreateCListing>1</CreateCListing>
<CreateAListing>1</CreateAListing>
<CreateLListing>1</CreateLListing>
<CreateIListing>0</CreateIListing>
<AsmCond>1</AsmCond>
<AsmSymb>1</AsmSymb>
<AsmXref>0</AsmXref>
<CCond>1</CCond>
<CCode>0</CCode>
<CListInc>0</CListInc>
<CSymb>0</CSymb>
<LinkerCodeListing>0</LinkerCodeListing>
</ListingPage>
<OPTXL>
<LMap>1</LMap>
<LComments>1</LComments>
<LGenerateSymbols>1</LGenerateSymbols>
<LLibSym>1</LLibSym>
<LLines>1</LLines>
<LLocSym>1</LLocSym>
<LPubSym>1</LPubSym>
<LXref>0</LXref>
<LExpSel>0</LExpSel>
</OPTXL>
<OPTFL>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<IsCurrentTarget>0</IsCurrentTarget>
</OPTFL>
<CpuCode>0</CpuCode>
<DebugOpt>
<uSim>0</uSim>
<uTrg>1</uTrg>
<sLdApp>1</sLdApp>
<sGomain>1</sGomain>
<sRbreak>1</sRbreak>
<sRwatch>1</sRwatch>
<sRmem>1</sRmem>
<sRfunc>1</sRfunc>
<sRbox>1</sRbox>
<tLdApp>1</tLdApp>
<tGomain>0</tGomain>
<tRbreak>1</tRbreak>
<tRwatch>1</tRwatch>
<tRmem>1</tRmem>
<tRfunc>0</tRfunc>
<tRbox>1</tRbox>
<tRtrace>0</tRtrace>
<sRSysVw>1</sRSysVw>
<tRSysVw>1</tRSysVw>
<tPdscDbg>1</tPdscDbg>
<sRunDeb>0</sRunDeb>
<sLrtime>0</sLrtime>
<nTsel>7</nTsel>
<sDll></sDll>
<sDllPa></sDllPa>
<sDlgDll></sDlgDll>
<sDlgPa></sDlgPa>
<sIfile></sIfile>
<tDll></tDll>
<tDllPa></tDllPa>
<tDlgDll></tDlgDll>
<tDlgPa></tDlgPa>
<tIfile></tIfile>
<pMon>Segger\JL2CM3.dll</pMon>
</DebugOpt>
<TargetDriverDllRegistry>
<SetRegEntry>
<Number>0</Number>
<Key>JL2CM3</Key>
<Name>-U -O78 -S0 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -TO18 -TC10000000 -TP21 -TDS8004 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO15 -FD20000000 -FC2000 -FN1 -FP0($$Device:nRF51822_xxAA$Flash\nrf51xxx.flm) -FF0nrf51xxx -FS00 -FL0200000</Name>
</SetRegEntry>
</TargetDriverDllRegistry>
<Breakpoint/>
<Tracepoint>
<THDelay>0</THDelay>
</Tracepoint>
<DebugFlag>
<trace>0</trace>
<periodic>0</periodic>
<aLwin>0</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
<aPa>0</aPa>
<viewmode>0</viewmode>
<vrSel>0</vrSel>
<aSym>0</aSym>
<aTbox>0</aTbox>
<AscS1>0</AscS1>
<AscS2>0</AscS2>
<AscS3>0</AscS3>
<aSer3>0</aSer3>
<eProf>0</eProf>
<aLa>0</aLa>
<aPa1>0</aPa1>
<AscS4>0</AscS4>
<aSer4>0</aSer4>
<StkLoc>0</StkLoc>
<TrcWin>0</TrcWin>
<newCpu>0</newCpu>
<uProt>0</uProt>
</DebugFlag>
<LintExecutable></LintExecutable>
<LintConfigFile></LintConfigFile>
</TargetOption>
</Target>
<Group>
<GroupName>Startup Code</GroupName>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>1</FileNumber>
<FileType>2</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\..\..\..\..\..\..\Source\templates\arm\arm_startup_nrf51.s</PathWithFileName>
<FilenameWithoutPath>arm_startup_nrf51.s</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>2</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\..\..\..\..\..\..\Source\templates\system_nrf51.c</PathWithFileName>
<FilenameWithoutPath>system_nrf51.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>Source Code</GroupName>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>2</GroupNumber>
<FileNumber>3</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\..\main.c</PathWithFileName>
<FilenameWithoutPath>main.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>Services</GroupName>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>3</GroupNumber>
<FileNumber>4</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\ble\ble_services\ble_srv_common.c</PathWithFileName>
<FilenameWithoutPath>ble_srv_common.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>3</GroupNumber>
<FileNumber>5</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\ble_nus.c</PathWithFileName>
<FilenameWithoutPath>ble_nus.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>Libraries</GroupName>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>6</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\ble\ble_advdata.c</PathWithFileName>
<FilenameWithoutPath>ble_advdata.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>7</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\ble\ble_conn_params.c</PathWithFileName>
<FilenameWithoutPath>ble_conn_params.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>8</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\sd_common\softdevice_handler.c</PathWithFileName>
<FilenameWithoutPath>softdevice_handler.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>9</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\app_common\app_timer.c</PathWithFileName>
<FilenameWithoutPath>app_timer.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>10</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\app_uart_fifo_mod.c</PathWithFileName>
<FilenameWithoutPath>app_uart_fifo_mod.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>11</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\app_common\app_fifo.c</PathWithFileName>
<FilenameWithoutPath>app_fifo.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>12</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\app_common\app_gpiote.c</PathWithFileName>
<FilenameWithoutPath>app_gpiote.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>13</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\ble\ble_debug_assert_handler.c</PathWithFileName>
<FilenameWithoutPath>ble_debug_assert_handler.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
</ProjectOpt>

652
arm/ble_app_uart.uvoptx Normal file
View File

@ -0,0 +1,652 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<ProjectOpt xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_optx.xsd">
<SchemaVersion>1.0</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Extensions>
<cExt>*.c</cExt>
<aExt>*.s*; *.src; *.a*</aExt>
<oExt>*.obj</oExt>
<lExt>*.lib</lExt>
<tExt>*.txt; *.h; *.inc</tExt>
<pExt>*.plm</pExt>
<CppX>*.cpp</CppX>
</Extensions>
<DaveTm>
<dwLowDateTime>0</dwLowDateTime>
<dwHighDateTime>0</dwHighDateTime>
</DaveTm>
<Target>
<TargetName>nrf51822_xxaa_s110 (256K)</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<CLKADS>16000000</CLKADS>
<OPTTT>
<gFlags>1</gFlags>
<BeepAtEnd>1</BeepAtEnd>
<RunSim>0</RunSim>
<RunTarget>1</RunTarget>
</OPTTT>
<OPTHX>
<HexSelection>1</HexSelection>
<FlashByte>65535</FlashByte>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
</OPTHX>
<OPTLEX>
<PageWidth>79</PageWidth>
<PageLength>66</PageLength>
<TabStop>8</TabStop>
<ListingPath>.\_build\</ListingPath>
</OPTLEX>
<ListingPage>
<CreateCListing>1</CreateCListing>
<CreateAListing>1</CreateAListing>
<CreateLListing>1</CreateLListing>
<CreateIListing>0</CreateIListing>
<AsmCond>1</AsmCond>
<AsmSymb>1</AsmSymb>
<AsmXref>0</AsmXref>
<CCond>1</CCond>
<CCode>0</CCode>
<CListInc>0</CListInc>
<CSymb>0</CSymb>
<LinkerCodeListing>0</LinkerCodeListing>
</ListingPage>
<OPTXL>
<LMap>1</LMap>
<LComments>1</LComments>
<LGenerateSymbols>1</LGenerateSymbols>
<LLibSym>1</LLibSym>
<LLines>1</LLines>
<LLocSym>1</LLocSym>
<LPubSym>1</LPubSym>
<LXref>0</LXref>
<LExpSel>0</LExpSel>
</OPTXL>
<OPTFL>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<IsCurrentTarget>1</IsCurrentTarget>
</OPTFL>
<CpuCode>0</CpuCode>
<DebugOpt>
<uSim>0</uSim>
<uTrg>1</uTrg>
<sLdApp>1</sLdApp>
<sGomain>1</sGomain>
<sRbreak>1</sRbreak>
<sRwatch>1</sRwatch>
<sRmem>1</sRmem>
<sRfunc>1</sRfunc>
<sRbox>1</sRbox>
<tLdApp>1</tLdApp>
<tGomain>1</tGomain>
<tRbreak>1</tRbreak>
<tRwatch>1</tRwatch>
<tRmem>1</tRmem>
<tRfunc>0</tRfunc>
<tRbox>1</tRbox>
<tRtrace>0</tRtrace>
<sRSysVw>1</sRSysVw>
<tRSysVw>1</tRSysVw>
<tPdscDbg>1</tPdscDbg>
<sRunDeb>0</sRunDeb>
<sLrtime>0</sLrtime>
<nTsel>6</nTsel>
<sDll></sDll>
<sDllPa></sDllPa>
<sDlgDll></sDlgDll>
<sDlgPa></sDlgPa>
<sIfile></sIfile>
<tDll></tDll>
<tDllPa></tDllPa>
<tDlgDll></tDlgDll>
<tDlgPa></tDlgPa>
<tIfile></tIfile>
<pMon>Segger\JL2CM3.dll</pMon>
</DebugOpt>
<TargetDriverDllRegistry>
<SetRegEntry>
<Number>0</Number>
<Key>DLGTARM</Key>
<Name>(1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>ARMDBGFLAGS</Key>
<Name></Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>DLGUARM</Key>
<Name>/</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>JL2CM3</Key>
<Name>-U480205250 -O78 -S0 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -N00("ARM CoreSight SW-DP") -D00(0BB11477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO15 -FD20000000 -FC2000 -FN1 -FF0nrf51xxx.flm -FS00 -FL0200000 -FP0($$Device:nRF51822_xxAA$Flash\nrf51xxx.flm)</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>UL2CM3</Key>
<Name>UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0nrf51xxx -FS00 -FL0200000 -FP0($$Device:nRF51822_xxAA$Flash\nrf51xxx.flm))</Name>
</SetRegEntry>
</TargetDriverDllRegistry>
<Breakpoint>
<Bp>
<Number>0</Number>
<Type>0</Type>
<LineNumber>129</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>90910</Address>
<ByteObject>0</ByteObject>
<HtxType>0</HtxType>
<ManyObjects>0</ManyObjects>
<SizeOfObject>0</SizeOfObject>
<BreakByAccess>0</BreakByAccess>
<BreakIfRCount>1</BreakIfRCount>
<Filename>.\..\main.c</Filename>
<ExecCommand></ExecCommand>
<Expression></Expression>
</Bp>
<Bp>
<Number>1</Number>
<Type>0</Type>
<LineNumber>109</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>90874</Address>
<ByteObject>0</ByteObject>
<HtxType>0</HtxType>
<ManyObjects>0</ManyObjects>
<SizeOfObject>0</SizeOfObject>
<BreakByAccess>0</BreakByAccess>
<BreakIfRCount>1</BreakIfRCount>
<Filename>.\..\main.c</Filename>
<ExecCommand></ExecCommand>
<Expression></Expression>
</Bp>
</Breakpoint>
<Tracepoint>
<THDelay>0</THDelay>
</Tracepoint>
<DebugFlag>
<trace>0</trace>
<periodic>0</periodic>
<aLwin>1</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
<aPa>0</aPa>
<viewmode>1</viewmode>
<vrSel>0</vrSel>
<aSym>0</aSym>
<aTbox>0</aTbox>
<AscS1>0</AscS1>
<AscS2>0</AscS2>
<AscS3>0</AscS3>
<aSer3>0</aSer3>
<eProf>0</eProf>
<aLa>0</aLa>
<aPa1>0</aPa1>
<AscS4>0</AscS4>
<aSer4>0</aSer4>
<StkLoc>0</StkLoc>
<TrcWin>0</TrcWin>
<newCpu>0</newCpu>
<uProt>0</uProt>
</DebugFlag>
<LintExecutable></LintExecutable>
<LintConfigFile></LintConfigFile>
<SystemViewers>
<Entry>
<Name>System Viewer\UART0</Name>
<WinId>35905</WinId>
</Entry>
</SystemViewers>
</TargetOption>
</Target>
<Target>
<TargetName>nrf51822_xxab_s110 (128K)</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<CLKADS>16000000</CLKADS>
<OPTTT>
<gFlags>1</gFlags>
<BeepAtEnd>1</BeepAtEnd>
<RunSim>0</RunSim>
<RunTarget>1</RunTarget>
</OPTTT>
<OPTHX>
<HexSelection>1</HexSelection>
<FlashByte>65535</FlashByte>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
</OPTHX>
<OPTLEX>
<PageWidth>79</PageWidth>
<PageLength>66</PageLength>
<TabStop>8</TabStop>
<ListingPath>.\_build\</ListingPath>
</OPTLEX>
<ListingPage>
<CreateCListing>1</CreateCListing>
<CreateAListing>1</CreateAListing>
<CreateLListing>1</CreateLListing>
<CreateIListing>0</CreateIListing>
<AsmCond>1</AsmCond>
<AsmSymb>1</AsmSymb>
<AsmXref>0</AsmXref>
<CCond>1</CCond>
<CCode>0</CCode>
<CListInc>0</CListInc>
<CSymb>0</CSymb>
<LinkerCodeListing>0</LinkerCodeListing>
</ListingPage>
<OPTXL>
<LMap>1</LMap>
<LComments>1</LComments>
<LGenerateSymbols>1</LGenerateSymbols>
<LLibSym>1</LLibSym>
<LLines>1</LLines>
<LLocSym>1</LLocSym>
<LPubSym>1</LPubSym>
<LXref>0</LXref>
<LExpSel>0</LExpSel>
</OPTXL>
<OPTFL>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<IsCurrentTarget>0</IsCurrentTarget>
</OPTFL>
<CpuCode>0</CpuCode>
<DebugOpt>
<uSim>0</uSim>
<uTrg>1</uTrg>
<sLdApp>1</sLdApp>
<sGomain>1</sGomain>
<sRbreak>1</sRbreak>
<sRwatch>1</sRwatch>
<sRmem>1</sRmem>
<sRfunc>1</sRfunc>
<sRbox>1</sRbox>
<tLdApp>1</tLdApp>
<tGomain>1</tGomain>
<tRbreak>1</tRbreak>
<tRwatch>1</tRwatch>
<tRmem>1</tRmem>
<tRfunc>0</tRfunc>
<tRbox>1</tRbox>
<tRtrace>0</tRtrace>
<sRSysVw>1</sRSysVw>
<tRSysVw>1</tRSysVw>
<tPdscDbg>1</tPdscDbg>
<sRunDeb>0</sRunDeb>
<sLrtime>0</sLrtime>
<nTsel>7</nTsel>
<sDll></sDll>
<sDllPa></sDllPa>
<sDlgDll></sDlgDll>
<sDlgPa></sDlgPa>
<sIfile></sIfile>
<tDll></tDll>
<tDllPa></tDllPa>
<tDlgDll></tDlgDll>
<tDlgPa></tDlgPa>
<tIfile></tIfile>
<pMon>Segger\JL2CM3.dll</pMon>
</DebugOpt>
<TargetDriverDllRegistry>
<SetRegEntry>
<Number>0</Number>
<Key>JL2CM3</Key>
<Name>-U408001579 -O78 -S0 -A0 -C0 -JU1 -JI127.0.0.1 -JP0 -RST0 -N00("ARM CoreSight SW-DP") -D00(0BB11477) -L00(0) -TO18 -TC10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -TB1 -TFE0 -FO15 -FD20000000 -FC2000 -FN1 -FF0nrf51xxx.flm -FS00 -FL0200000 -FP0($$Device:nRF51822_xxAA$Flash\nrf51xxx.flm)</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>UL2CM3</Key>
<Name>UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0nrf51xxx -FS00 -FL0200000 -FP0($$Device:nRF51822_xxAA$Flash\nrf51xxx.flm))</Name>
</SetRegEntry>
</TargetDriverDllRegistry>
<Breakpoint>
<Bp>
<Number>0</Number>
<Type>0</Type>
<LineNumber>549</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>0</Address>
<ByteObject>0</ByteObject>
<HtxType>0</HtxType>
<ManyObjects>0</ManyObjects>
<SizeOfObject>0</SizeOfObject>
<BreakByAccess>0</BreakByAccess>
<BreakIfRCount>0</BreakIfRCount>
<Filename>.\..\main.c</Filename>
<ExecCommand></ExecCommand>
<Expression></Expression>
</Bp>
<Bp>
<Number>1</Number>
<Type>0</Type>
<LineNumber>109</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>0</Address>
<ByteObject>0</ByteObject>
<HtxType>0</HtxType>
<ManyObjects>0</ManyObjects>
<SizeOfObject>0</SizeOfObject>
<BreakByAccess>0</BreakByAccess>
<BreakIfRCount>0</BreakIfRCount>
<Filename>.\..\main.c</Filename>
<ExecCommand></ExecCommand>
<Expression></Expression>
</Bp>
<Bp>
<Number>2</Number>
<Type>0</Type>
<LineNumber>129</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>0</Address>
<ByteObject>0</ByteObject>
<HtxType>0</HtxType>
<ManyObjects>0</ManyObjects>
<SizeOfObject>0</SizeOfObject>
<BreakByAccess>0</BreakByAccess>
<BreakIfRCount>0</BreakIfRCount>
<Filename>.\..\main.c</Filename>
<ExecCommand></ExecCommand>
<Expression></Expression>
</Bp>
</Breakpoint>
<Tracepoint>
<THDelay>0</THDelay>
</Tracepoint>
<DebugFlag>
<trace>0</trace>
<periodic>0</periodic>
<aLwin>0</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
<aPa>0</aPa>
<viewmode>0</viewmode>
<vrSel>0</vrSel>
<aSym>0</aSym>
<aTbox>0</aTbox>
<AscS1>0</AscS1>
<AscS2>0</AscS2>
<AscS3>0</AscS3>
<aSer3>0</aSer3>
<eProf>0</eProf>
<aLa>0</aLa>
<aPa1>0</aPa1>
<AscS4>0</AscS4>
<aSer4>0</aSer4>
<StkLoc>0</StkLoc>
<TrcWin>0</TrcWin>
<newCpu>0</newCpu>
<uProt>0</uProt>
</DebugFlag>
<LintExecutable></LintExecutable>
<LintConfigFile></LintConfigFile>
</TargetOption>
</Target>
<Group>
<GroupName>::Device</GroupName>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>1</RteFlg>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>1</FileNumber>
<FileType>2</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>RTE\Device\nRF51822_xxAA\arm_startup_nrf51.s</PathWithFileName>
<FilenameWithoutPath>arm_startup_nrf51.s</FilenameWithoutPath>
<RteFlg>1</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>2</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>RTE\Device\nRF51822_xxAA\system_nrf51.c</PathWithFileName>
<FilenameWithoutPath>system_nrf51.c</FilenameWithoutPath>
<RteFlg>1</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>3</FileNumber>
<FileType>2</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>RTE\Device\nRF51822_xxAB\arm_startup_nrf51.s</PathWithFileName>
<FilenameWithoutPath>arm_startup_nrf51.s</FilenameWithoutPath>
<RteFlg>1</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>4</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>RTE\Device\nRF51822_xxAB\system_nrf51.c</PathWithFileName>
<FilenameWithoutPath>system_nrf51.c</FilenameWithoutPath>
<RteFlg>1</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>Source Code</GroupName>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>2</GroupNumber>
<FileNumber>5</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\..\main.c</PathWithFileName>
<FilenameWithoutPath>main.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>Services</GroupName>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>3</GroupNumber>
<FileNumber>6</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\ble\ble_services\ble_srv_common.c</PathWithFileName>
<FilenameWithoutPath>ble_srv_common.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>3</GroupNumber>
<FileNumber>7</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\ble_nus.c</PathWithFileName>
<FilenameWithoutPath>ble_nus.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>Libraries</GroupName>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>8</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\ble\ble_advdata.c</PathWithFileName>
<FilenameWithoutPath>ble_advdata.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>9</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\ble\ble_conn_params.c</PathWithFileName>
<FilenameWithoutPath>ble_conn_params.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>10</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\sd_common\softdevice_handler.c</PathWithFileName>
<FilenameWithoutPath>softdevice_handler.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>11</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\simple_uart\simple_uart.c</PathWithFileName>
<FilenameWithoutPath>simple_uart.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>12</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\app_common\app_timer.c</PathWithFileName>
<FilenameWithoutPath>app_timer.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>13</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\app_common\app_gpiote.c</PathWithFileName>
<FilenameWithoutPath>app_gpiote.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>14</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\app_common\app_fifo.c</PathWithFileName>
<FilenameWithoutPath>app_fifo.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>15</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\..\..\..\Source\ble\ble_debug_assert_handler.c</PathWithFileName>
<FilenameWithoutPath>ble_debug_assert_handler.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>16</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\app_uart_fifo_mod.c</PathWithFileName>
<FilenameWithoutPath>app_uart_fifo_mod.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>::CMSIS</GroupName>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>1</RteFlg>
</Group>
</ProjectOpt>

985
arm/ble_app_uart.uvproj Normal file
View File

@ -0,0 +1,985 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<Project xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_proj.xsd">
<SchemaVersion>1.1</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Targets>
<Target>
<TargetName>nrf51822_xxaa_s110 (256K)</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<TargetCommonOption>
<Device>nRF51822_xxAA</Device>
<Vendor>Nordic Semiconductor</Vendor>
<PackID>NordicSemiconductor.nRF_InternalDeviceFamilyPack.1.1.0</PackID>
<PackURL>http://www.keil.com/pack/</PackURL>
<Cpu>IRAM(0x20000000-0x20003FFF) IROM(0-0x3FFFF) CLOCK(16000000) CPUTYPE("Cortex-M0") ESEL ELITTLE</Cpu>
<FlashUtilSpec></FlashUtilSpec>
<StartupFile>"Device\Nordic\nRF51822\Source\templates\arm\arm_startup_nrf51.s"("Nordic Semiconductor nRF51822 Startup Code")</StartupFile>
<FlashDriverDll>UL2CM3(-UM0364FCE -O78 -S0 -C0 -TO18 -TC16000000 -TP21 -TDS800D -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO15 -FD20000000 -FC2000 -FN1 -FF0nRF51xxx -FS00 -FL0200000)</FlashDriverDll>
<DeviceId>0</DeviceId>
<RegisterFile>nrf.h</RegisterFile>
<MemoryEnv></MemoryEnv>
<Cmp></Cmp>
<Asm></Asm>
<Linker></Linker>
<OHString></OHString>
<InfinionOptionDll></InfinionOptionDll>
<SLE66CMisc></SLE66CMisc>
<SLE66AMisc></SLE66AMisc>
<SLE66LinkerMisc></SLE66LinkerMisc>
<SFDFile>SFD\Nordic\nRF51\nrf51822.sfr</SFDFile>
<bCustSvd>0</bCustSvd>
<UseEnv>0</UseEnv>
<BinPath></BinPath>
<IncludePath></IncludePath>
<LibPath></LibPath>
<RegisterFilePath>..\Device\Nordic\nRF51822\Include\</RegisterFilePath>
<DBRegisterFilePath>..\Device\Nordic\nRF51822\Include\</DBRegisterFilePath>
<TargetStatus>
<Error>0</Error>
<ExitCodeStop>0</ExitCodeStop>
<ButtonStop>0</ButtonStop>
<NotGenerated>0</NotGenerated>
<InvalidFlash>1</InvalidFlash>
</TargetStatus>
<OutputDirectory>.\_build\</OutputDirectory>
<OutputName>ble_app_uart</OutputName>
<CreateExecutable>1</CreateExecutable>
<CreateLib>0</CreateLib>
<CreateHexFile>1</CreateHexFile>
<DebugInformation>1</DebugInformation>
<BrowseInformation>1</BrowseInformation>
<ListingPath>.\_build\</ListingPath>
<HexFormatSelection>1</HexFormatSelection>
<Merge32K>0</Merge32K>
<CreateBatchFile>0</CreateBatchFile>
<BeforeCompile>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopU1X>0</nStopU1X>
<nStopU2X>0</nStopU2X>
</BeforeCompile>
<BeforeMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopB1X>0</nStopB1X>
<nStopB2X>0</nStopB2X>
</BeforeMake>
<AfterMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
</AfterMake>
<SelectedForBatchBuild>0</SelectedForBatchBuild>
<SVCSIdString></SVCSIdString>
</TargetCommonOption>
<CommonProperty>
<UseCPPCompiler>0</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>1</IncludeInBuild>
<AlwaysBuild>0</AlwaysBuild>
<GenerateAssemblyFile>0</GenerateAssemblyFile>
<AssembleAssemblyFile>0</AssembleAssemblyFile>
<PublicsOnly>0</PublicsOnly>
<StopOnExitCode>3</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
<ComprImg>1</ComprImg>
</CommonProperty>
<DllOption>
<SimDllName></SimDllName>
<SimDllArguments></SimDllArguments>
<SimDlgDll></SimDlgDll>
<SimDlgDllArguments></SimDlgDllArguments>
<TargetDllName>SARMCM3.DLL</TargetDllName>
<TargetDllArguments></TargetDllArguments>
<TargetDlgDll>TARMCM1.DLL</TargetDlgDll>
<TargetDlgDllArguments>-pCM0</TargetDlgDllArguments>
</DllOption>
<DebugOption>
<OPTHX>
<HexSelection>1</HexSelection>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
<Oh166RecLen>16</Oh166RecLen>
</OPTHX>
<Simulator>
<UseSimulator>0</UseSimulator>
<LoadApplicationAtStartup>1</LoadApplicationAtStartup>
<RunToMain>1</RunToMain>
<RestoreBreakpoints>1</RestoreBreakpoints>
<RestoreWatchpoints>1</RestoreWatchpoints>
<RestoreMemoryDisplay>1</RestoreMemoryDisplay>
<RestoreFunctions>1</RestoreFunctions>
<RestoreToolbox>1</RestoreToolbox>
<LimitSpeedToRealTime>0</LimitSpeedToRealTime>
<RestoreSysVw>1</RestoreSysVw>
</Simulator>
<Target>
<UseTarget>1</UseTarget>
<LoadApplicationAtStartup>1</LoadApplicationAtStartup>
<RunToMain>1</RunToMain>
<RestoreBreakpoints>1</RestoreBreakpoints>
<RestoreWatchpoints>1</RestoreWatchpoints>
<RestoreMemoryDisplay>1</RestoreMemoryDisplay>
<RestoreFunctions>0</RestoreFunctions>
<RestoreToolbox>1</RestoreToolbox>
<RestoreTracepoints>0</RestoreTracepoints>
<RestoreSysVw>1</RestoreSysVw>
<UsePdscDebugDescription>1</UsePdscDebugDescription>
</Target>
<RunDebugAfterBuild>0</RunDebugAfterBuild>
<TargetSelection>6</TargetSelection>
<SimDlls>
<CpuDll></CpuDll>
<CpuDllArguments></CpuDllArguments>
<PeripheralDll></PeripheralDll>
<PeripheralDllArguments></PeripheralDllArguments>
<InitializationFile></InitializationFile>
</SimDlls>
<TargetDlls>
<CpuDll></CpuDll>
<CpuDllArguments></CpuDllArguments>
<PeripheralDll></PeripheralDll>
<PeripheralDllArguments></PeripheralDllArguments>
<InitializationFile></InitializationFile>
<Driver>Segger\JL2CM3.dll</Driver>
</TargetDlls>
</DebugOption>
<Utilities>
<Flash1>
<UseTargetDll>1</UseTargetDll>
<UseExternalTool>0</UseExternalTool>
<RunIndependent>0</RunIndependent>
<UpdateFlashBeforeDebugging>1</UpdateFlashBeforeDebugging>
<Capability>1</Capability>
<DriverSelection>4099</DriverSelection>
</Flash1>
<bUseTDR>1</bUseTDR>
<Flash2>Segger\JL2CM3.dll</Flash2>
<Flash3>"" ()</Flash3>
<Flash4></Flash4>
<pFcarmOut></pFcarmOut>
<pFcarmGrp></pFcarmGrp>
<pFcArmRoot></pFcArmRoot>
<FcArmLst>0</FcArmLst>
</Utilities>
<TargetArmAds>
<ArmAdsMisc>
<GenerateListings>0</GenerateListings>
<asHll>1</asHll>
<asAsm>1</asAsm>
<asMacX>1</asMacX>
<asSyms>1</asSyms>
<asFals>1</asFals>
<asDbgD>1</asDbgD>
<asForm>1</asForm>
<ldLst>0</ldLst>
<ldmm>1</ldmm>
<ldXref>1</ldXref>
<BigEnd>0</BigEnd>
<AdsALst>1</AdsALst>
<AdsACrf>1</AdsACrf>
<AdsANop>0</AdsANop>
<AdsANot>0</AdsANot>
<AdsLLst>1</AdsLLst>
<AdsLmap>1</AdsLmap>
<AdsLcgr>1</AdsLcgr>
<AdsLsym>1</AdsLsym>
<AdsLszi>1</AdsLszi>
<AdsLtoi>1</AdsLtoi>
<AdsLsun>1</AdsLsun>
<AdsLven>1</AdsLven>
<AdsLsxf>1</AdsLsxf>
<RvctClst>0</RvctClst>
<GenPPlst>0</GenPPlst>
<AdsCpuType>"Cortex-M0"</AdsCpuType>
<RvctDeviceName></RvctDeviceName>
<mOS>0</mOS>
<uocRom>0</uocRom>
<uocRam>0</uocRam>
<hadIROM>1</hadIROM>
<hadIRAM>1</hadIRAM>
<hadXRAM>0</hadXRAM>
<uocXRam>0</uocXRam>
<RvdsVP>0</RvdsVP>
<hadIRAM2>0</hadIRAM2>
<hadIROM2>0</hadIROM2>
<StupSel>8</StupSel>
<useUlib>0</useUlib>
<EndSel>1</EndSel>
<uLtcg>0</uLtcg>
<RoSelD>3</RoSelD>
<RwSelD>3</RwSelD>
<CodeSel>0</CodeSel>
<OptFeed>0</OptFeed>
<NoZi1>0</NoZi1>
<NoZi2>0</NoZi2>
<NoZi3>0</NoZi3>
<NoZi4>0</NoZi4>
<NoZi5>0</NoZi5>
<Ro1Chk>0</Ro1Chk>
<Ro2Chk>0</Ro2Chk>
<Ro3Chk>0</Ro3Chk>
<Ir1Chk>1</Ir1Chk>
<Ir2Chk>0</Ir2Chk>
<Ra1Chk>0</Ra1Chk>
<Ra2Chk>0</Ra2Chk>
<Ra3Chk>0</Ra3Chk>
<Im1Chk>1</Im1Chk>
<Im2Chk>0</Im2Chk>
<OnChipMemories>
<Ocm1>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm1>
<Ocm2>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm2>
<Ocm3>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm3>
<Ocm4>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm4>
<Ocm5>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm5>
<Ocm6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm6>
<IRAM>
<Type>0</Type>
<StartAddress>0x20000000</StartAddress>
<Size>0x4000</Size>
</IRAM>
<IROM>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x40000</Size>
</IROM>
<XRAM>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</XRAM>
<OCR_RVCT1>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT1>
<OCR_RVCT2>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT2>
<OCR_RVCT3>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT3>
<OCR_RVCT4>
<Type>1</Type>
<StartAddress>0x16000</StartAddress>
<Size>0x29000</Size>
</OCR_RVCT4>
<OCR_RVCT5>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT5>
<OCR_RVCT6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT6>
<OCR_RVCT7>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT7>
<OCR_RVCT8>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT8>
<OCR_RVCT9>
<Type>0</Type>
<StartAddress>0x20002000</StartAddress>
<Size>0x2000</Size>
</OCR_RVCT9>
<OCR_RVCT10>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT10>
</OnChipMemories>
<RvctStartVector></RvctStartVector>
</ArmAdsMisc>
<Cads>
<interw>1</interw>
<Optim>1</Optim>
<oTime>0</oTime>
<SplitLS>0</SplitLS>
<OneElfS>0</OneElfS>
<Strict>0</Strict>
<EnumInt>1</EnumInt>
<PlainCh>0</PlainCh>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<wLevel>2</wLevel>
<uThumb>0</uThumb>
<uSurpInc>0</uSurpInc>
<uC99>0</uC99>
<useXO>0</useXO>
<VariousControls>
<MiscControls>--c99</MiscControls>
<Define>BOARD_PCA10001 NRF51,DEBUG_NRF_USER, BLE_STACK_SUPPORT_REQD</Define>
<Undefine></Undefine>
<IncludePath>..;..\..\..\..\..\..\Include;..\..\..\..\..\..\Include\app_common;..\..\..\..\..\..\Include\ble;..\..\..\..\..\..\Include\ble\ble_services;..\..\..\..\..\..\Include\s110;..\..\..\..\..\..\Include\sd_common</IncludePath>
</VariousControls>
</Cads>
<Aads>
<interw>1</interw>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<thumb>0</thumb>
<SplitLS>0</SplitLS>
<SwStkChk>0</SwStkChk>
<NoWarn>0</NoWarn>
<uSurpInc>0</uSurpInc>
<useXO>0</useXO>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Aads>
<LDads>
<umfTarg>1</umfTarg>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<noStLib>0</noStLib>
<RepFail>1</RepFail>
<useFile>0</useFile>
<TextAddressRange>0x00000000</TextAddressRange>
<DataAddressRange>0x20000000</DataAddressRange>
<pXoBase></pXoBase>
<ScatterFile>..\scatter.sct</ScatterFile>
<IncludeLibs></IncludeLibs>
<IncludeLibsPath></IncludeLibsPath>
<Misc></Misc>
<LinkerInputFile></LinkerInputFile>
<DisabledWarnings></DisabledWarnings>
</LDads>
</TargetArmAds>
</TargetOption>
<Groups>
<Group>
<GroupName>Startup Code</GroupName>
<Files>
<File>
<FileName>arm_startup_nrf51.s</FileName>
<FileType>2</FileType>
<FilePath>.\..\..\..\..\..\..\Source\templates\arm\arm_startup_nrf51.s</FilePath>
</File>
<File>
<FileName>system_nrf51.c</FileName>
<FileType>1</FileType>
<FilePath>.\..\..\..\..\..\..\Source\templates\system_nrf51.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>Source Code</GroupName>
<Files>
<File>
<FileName>main.c</FileName>
<FileType>1</FileType>
<FilePath>.\..\main.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>Services</GroupName>
<Files>
<File>
<FileName>ble_srv_common.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\ble\ble_services\ble_srv_common.c</FilePath>
</File>
<File>
<FileName>ble_nus.c</FileName>
<FileType>1</FileType>
<FilePath>..\ble_nus.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>Libraries</GroupName>
<Files>
<File>
<FileName>ble_advdata.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\ble\ble_advdata.c</FilePath>
</File>
<File>
<FileName>ble_conn_params.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\ble\ble_conn_params.c</FilePath>
</File>
<File>
<FileName>softdevice_handler.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\sd_common\softdevice_handler.c</FilePath>
</File>
<File>
<FileName>app_timer.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\app_common\app_timer.c</FilePath>
</File>
<File>
<FileName>app_uart_fifo_mod.c</FileName>
<FileType>1</FileType>
<FilePath>..\app_uart_fifo_mod.c</FilePath>
</File>
<File>
<FileName>app_fifo.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\app_common\app_fifo.c</FilePath>
</File>
<File>
<FileName>app_gpiote.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\app_common\app_gpiote.c</FilePath>
</File>
<File>
<FileName>ble_debug_assert_handler.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\ble\ble_debug_assert_handler.c</FilePath>
</File>
</Files>
</Group>
</Groups>
</Target>
<Target>
<TargetName>nrf51822_xxab_s110 (128K)</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<TargetCommonOption>
<Device>nRF51822_xxAB</Device>
<Vendor>Nordic Semiconductor</Vendor>
<PackID>NordicSemiconductor.nRF_InternalDeviceFamilyPack.1.1.0</PackID>
<PackURL>http://www.keil.com/pack/</PackURL>
<Cpu>IRAM(0x20000000-0x20003FFF) IROM(0-0x3FFFF) CLOCK(16000000) CPUTYPE("Cortex-M0") ESEL ELITTLE</Cpu>
<FlashUtilSpec></FlashUtilSpec>
<StartupFile>"Device\Nordic\nRF51822\Source\templates\arm\arm_startup_nrf51.s"("Nordic Semiconductor nRF51822 Startup Code")</StartupFile>
<FlashDriverDll>UL2CM3(-UM0364FCE -O78 -S0 -C0 -TO18 -TC16000000 -TP21 -TDS800D -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO15 -FD20000000 -FC2000 -FN1 -FF0nRF51xxx -FS00 -FL0200000)</FlashDriverDll>
<DeviceId>0</DeviceId>
<RegisterFile>nrf.h</RegisterFile>
<MemoryEnv></MemoryEnv>
<Cmp></Cmp>
<Asm></Asm>
<Linker></Linker>
<OHString></OHString>
<InfinionOptionDll></InfinionOptionDll>
<SLE66CMisc></SLE66CMisc>
<SLE66AMisc></SLE66AMisc>
<SLE66LinkerMisc></SLE66LinkerMisc>
<SFDFile>SFD\Nordic\nRF51\nrf51822.sfr</SFDFile>
<bCustSvd>0</bCustSvd>
<UseEnv>0</UseEnv>
<BinPath></BinPath>
<IncludePath></IncludePath>
<LibPath></LibPath>
<RegisterFilePath>..\Device\Nordic\nRF51822\Include\</RegisterFilePath>
<DBRegisterFilePath>..\Device\Nordic\nRF51822\Include\</DBRegisterFilePath>
<TargetStatus>
<Error>0</Error>
<ExitCodeStop>0</ExitCodeStop>
<ButtonStop>0</ButtonStop>
<NotGenerated>0</NotGenerated>
<InvalidFlash>1</InvalidFlash>
</TargetStatus>
<OutputDirectory>.\_build\</OutputDirectory>
<OutputName>ble_app_uart</OutputName>
<CreateExecutable>1</CreateExecutable>
<CreateLib>0</CreateLib>
<CreateHexFile>1</CreateHexFile>
<DebugInformation>1</DebugInformation>
<BrowseInformation>1</BrowseInformation>
<ListingPath>.\_build\</ListingPath>
<HexFormatSelection>1</HexFormatSelection>
<Merge32K>0</Merge32K>
<CreateBatchFile>0</CreateBatchFile>
<BeforeCompile>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopU1X>0</nStopU1X>
<nStopU2X>0</nStopU2X>
</BeforeCompile>
<BeforeMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopB1X>0</nStopB1X>
<nStopB2X>0</nStopB2X>
</BeforeMake>
<AfterMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
</AfterMake>
<SelectedForBatchBuild>0</SelectedForBatchBuild>
<SVCSIdString></SVCSIdString>
</TargetCommonOption>
<CommonProperty>
<UseCPPCompiler>0</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>1</IncludeInBuild>
<AlwaysBuild>0</AlwaysBuild>
<GenerateAssemblyFile>0</GenerateAssemblyFile>
<AssembleAssemblyFile>0</AssembleAssemblyFile>
<PublicsOnly>0</PublicsOnly>
<StopOnExitCode>3</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
<ComprImg>1</ComprImg>
</CommonProperty>
<DllOption>
<SimDllName></SimDllName>
<SimDllArguments></SimDllArguments>
<SimDlgDll></SimDlgDll>
<SimDlgDllArguments></SimDlgDllArguments>
<TargetDllName>SARMCM3.DLL</TargetDllName>
<TargetDllArguments></TargetDllArguments>
<TargetDlgDll>TARMCM1.DLL</TargetDlgDll>
<TargetDlgDllArguments>-pCM0</TargetDlgDllArguments>
</DllOption>
<DebugOption>
<OPTHX>
<HexSelection>1</HexSelection>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
<Oh166RecLen>16</Oh166RecLen>
</OPTHX>
<Simulator>
<UseSimulator>0</UseSimulator>
<LoadApplicationAtStartup>1</LoadApplicationAtStartup>
<RunToMain>1</RunToMain>
<RestoreBreakpoints>1</RestoreBreakpoints>
<RestoreWatchpoints>1</RestoreWatchpoints>
<RestoreMemoryDisplay>1</RestoreMemoryDisplay>
<RestoreFunctions>1</RestoreFunctions>
<RestoreToolbox>1</RestoreToolbox>
<LimitSpeedToRealTime>0</LimitSpeedToRealTime>
<RestoreSysVw>1</RestoreSysVw>
</Simulator>
<Target>
<UseTarget>1</UseTarget>
<LoadApplicationAtStartup>1</LoadApplicationAtStartup>
<RunToMain>0</RunToMain>
<RestoreBreakpoints>1</RestoreBreakpoints>
<RestoreWatchpoints>1</RestoreWatchpoints>
<RestoreMemoryDisplay>1</RestoreMemoryDisplay>
<RestoreFunctions>0</RestoreFunctions>
<RestoreToolbox>1</RestoreToolbox>
<RestoreTracepoints>0</RestoreTracepoints>
<RestoreSysVw>1</RestoreSysVw>
<UsePdscDebugDescription>1</UsePdscDebugDescription>
</Target>
<RunDebugAfterBuild>0</RunDebugAfterBuild>
<TargetSelection>7</TargetSelection>
<SimDlls>
<CpuDll></CpuDll>
<CpuDllArguments></CpuDllArguments>
<PeripheralDll></PeripheralDll>
<PeripheralDllArguments></PeripheralDllArguments>
<InitializationFile></InitializationFile>
</SimDlls>
<TargetDlls>
<CpuDll></CpuDll>
<CpuDllArguments></CpuDllArguments>
<PeripheralDll></PeripheralDll>
<PeripheralDllArguments></PeripheralDllArguments>
<InitializationFile></InitializationFile>
<Driver>Segger\JL2CM3.dll</Driver>
</TargetDlls>
</DebugOption>
<Utilities>
<Flash1>
<UseTargetDll>1</UseTargetDll>
<UseExternalTool>0</UseExternalTool>
<RunIndependent>0</RunIndependent>
<UpdateFlashBeforeDebugging>1</UpdateFlashBeforeDebugging>
<Capability>1</Capability>
<DriverSelection>4099</DriverSelection>
</Flash1>
<bUseTDR>1</bUseTDR>
<Flash2>Segger\JL2CM3.dll</Flash2>
<Flash3>"" ()</Flash3>
<Flash4></Flash4>
<pFcarmOut></pFcarmOut>
<pFcarmGrp></pFcarmGrp>
<pFcArmRoot></pFcArmRoot>
<FcArmLst>0</FcArmLst>
</Utilities>
<TargetArmAds>
<ArmAdsMisc>
<GenerateListings>0</GenerateListings>
<asHll>1</asHll>
<asAsm>1</asAsm>
<asMacX>1</asMacX>
<asSyms>1</asSyms>
<asFals>1</asFals>
<asDbgD>1</asDbgD>
<asForm>1</asForm>
<ldLst>0</ldLst>
<ldmm>1</ldmm>
<ldXref>1</ldXref>
<BigEnd>0</BigEnd>
<AdsALst>1</AdsALst>
<AdsACrf>1</AdsACrf>
<AdsANop>0</AdsANop>
<AdsANot>0</AdsANot>
<AdsLLst>1</AdsLLst>
<AdsLmap>1</AdsLmap>
<AdsLcgr>1</AdsLcgr>
<AdsLsym>1</AdsLsym>
<AdsLszi>1</AdsLszi>
<AdsLtoi>1</AdsLtoi>
<AdsLsun>1</AdsLsun>
<AdsLven>1</AdsLven>
<AdsLsxf>1</AdsLsxf>
<RvctClst>0</RvctClst>
<GenPPlst>0</GenPPlst>
<AdsCpuType>"Cortex-M0"</AdsCpuType>
<RvctDeviceName></RvctDeviceName>
<mOS>0</mOS>
<uocRom>0</uocRom>
<uocRam>0</uocRam>
<hadIROM>1</hadIROM>
<hadIRAM>1</hadIRAM>
<hadXRAM>0</hadXRAM>
<uocXRam>0</uocXRam>
<RvdsVP>0</RvdsVP>
<hadIRAM2>0</hadIRAM2>
<hadIROM2>0</hadIROM2>
<StupSel>8</StupSel>
<useUlib>0</useUlib>
<EndSel>1</EndSel>
<uLtcg>0</uLtcg>
<RoSelD>3</RoSelD>
<RwSelD>3</RwSelD>
<CodeSel>0</CodeSel>
<OptFeed>0</OptFeed>
<NoZi1>0</NoZi1>
<NoZi2>0</NoZi2>
<NoZi3>0</NoZi3>
<NoZi4>0</NoZi4>
<NoZi5>0</NoZi5>
<Ro1Chk>0</Ro1Chk>
<Ro2Chk>0</Ro2Chk>
<Ro3Chk>0</Ro3Chk>
<Ir1Chk>1</Ir1Chk>
<Ir2Chk>0</Ir2Chk>
<Ra1Chk>0</Ra1Chk>
<Ra2Chk>0</Ra2Chk>
<Ra3Chk>0</Ra3Chk>
<Im1Chk>1</Im1Chk>
<Im2Chk>0</Im2Chk>
<OnChipMemories>
<Ocm1>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm1>
<Ocm2>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm2>
<Ocm3>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm3>
<Ocm4>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm4>
<Ocm5>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm5>
<Ocm6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm6>
<IRAM>
<Type>0</Type>
<StartAddress>0x20000000</StartAddress>
<Size>0x4000</Size>
</IRAM>
<IROM>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x40000</Size>
</IROM>
<XRAM>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</XRAM>
<OCR_RVCT1>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT1>
<OCR_RVCT2>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT2>
<OCR_RVCT3>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT3>
<OCR_RVCT4>
<Type>1</Type>
<StartAddress>0x16000</StartAddress>
<Size>0x9000</Size>
</OCR_RVCT4>
<OCR_RVCT5>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT5>
<OCR_RVCT6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT6>
<OCR_RVCT7>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT7>
<OCR_RVCT8>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT8>
<OCR_RVCT9>
<Type>0</Type>
<StartAddress>0x20002000</StartAddress>
<Size>0x2000</Size>
</OCR_RVCT9>
<OCR_RVCT10>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT10>
</OnChipMemories>
<RvctStartVector></RvctStartVector>
</ArmAdsMisc>
<Cads>
<interw>1</interw>
<Optim>1</Optim>
<oTime>0</oTime>
<SplitLS>0</SplitLS>
<OneElfS>0</OneElfS>
<Strict>0</Strict>
<EnumInt>1</EnumInt>
<PlainCh>0</PlainCh>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<wLevel>2</wLevel>
<uThumb>0</uThumb>
<uSurpInc>0</uSurpInc>
<uC99>0</uC99>
<useXO>0</useXO>
<VariousControls>
<MiscControls>--c99</MiscControls>
<Define>BOARD_PCA10001 NRF51,DEBUG_NRF_USER, BLE_STACK_SUPPORT_REQD</Define>
<Undefine></Undefine>
<IncludePath>..;..\..\..\..\..\..\Include;..\..\..\..\..\..\Include\app_common;..\..\..\..\..\..\Include\ble;..\..\..\..\..\..\Include\ble\ble_services;..\..\..\..\..\..\Include\s110;..\..\..\..\..\..\Include\sd_common</IncludePath>
</VariousControls>
</Cads>
<Aads>
<interw>1</interw>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<thumb>0</thumb>
<SplitLS>0</SplitLS>
<SwStkChk>0</SwStkChk>
<NoWarn>0</NoWarn>
<uSurpInc>0</uSurpInc>
<useXO>0</useXO>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Aads>
<LDads>
<umfTarg>1</umfTarg>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<noStLib>0</noStLib>
<RepFail>1</RepFail>
<useFile>0</useFile>
<TextAddressRange>0x00000000</TextAddressRange>
<DataAddressRange>0x20000000</DataAddressRange>
<pXoBase></pXoBase>
<ScatterFile>..\scatter.sct</ScatterFile>
<IncludeLibs></IncludeLibs>
<IncludeLibsPath></IncludeLibsPath>
<Misc></Misc>
<LinkerInputFile></LinkerInputFile>
<DisabledWarnings></DisabledWarnings>
</LDads>
</TargetArmAds>
</TargetOption>
<Groups>
<Group>
<GroupName>Startup Code</GroupName>
<Files>
<File>
<FileName>arm_startup_nrf51.s</FileName>
<FileType>2</FileType>
<FilePath>.\..\..\..\..\..\..\Source\templates\arm\arm_startup_nrf51.s</FilePath>
</File>
<File>
<FileName>system_nrf51.c</FileName>
<FileType>1</FileType>
<FilePath>.\..\..\..\..\..\..\Source\templates\system_nrf51.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>Source Code</GroupName>
<Files>
<File>
<FileName>main.c</FileName>
<FileType>1</FileType>
<FilePath>.\..\main.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>Services</GroupName>
<Files>
<File>
<FileName>ble_srv_common.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\ble\ble_services\ble_srv_common.c</FilePath>
</File>
<File>
<FileName>ble_nus.c</FileName>
<FileType>1</FileType>
<FilePath>..\ble_nus.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>Libraries</GroupName>
<Files>
<File>
<FileName>ble_advdata.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\ble\ble_advdata.c</FilePath>
</File>
<File>
<FileName>ble_conn_params.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\ble\ble_conn_params.c</FilePath>
</File>
<File>
<FileName>softdevice_handler.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\sd_common\softdevice_handler.c</FilePath>
</File>
<File>
<FileName>app_timer.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\app_common\app_timer.c</FilePath>
</File>
<File>
<FileName>app_uart_fifo_mod.c</FileName>
<FileType>1</FileType>
<FilePath>..\app_uart_fifo_mod.c</FilePath>
</File>
<File>
<FileName>app_fifo.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\app_common\app_fifo.c</FilePath>
</File>
<File>
<FileName>app_gpiote.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\app_common\app_gpiote.c</FilePath>
</File>
<File>
<FileName>ble_debug_assert_handler.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\..\..\Source\ble\ble_debug_assert_handler.c</FilePath>
</File>
</Files>
</Group>
</Groups>
</Target>
</Targets>
</Project>

1247
arm/ble_app_uart.uvprojx Normal file

File diff suppressed because it is too large Load Diff

308
ble_nus.c Normal file
View File

@ -0,0 +1,308 @@
/* Copyright (c) 2012 Nordic Semiconductor. All Rights Reserved.
*
* The information contained herein is property of Nordic Semiconductor ASA.
* Terms and conditions of usage are described in detail in NORDIC
* SEMICONDUCTOR STANDARD SOFTWARE LICENSE AGREEMENT.
*
* Licensees are granted free, non-transferable use of the information. NO
* WARRANTY of ANY KIND is provided. This heading must NOT be removed from
* the file.
*
*/
#include "ble_nus.h"
#include "nordic_common.h"
#include "ble_srv_common.h"
#include <string.h>
/**@brief Function for handling the @ref BLE_GAP_EVT_CONNECTED event from the S110 SoftDevice.
*
* @param[in] p_nus Nordic UART Service structure.
* @param[in] p_ble_evt Pointer to the event received from BLE stack.
*/
static void on_connect(ble_nus_t * p_nus, ble_evt_t * p_ble_evt)
{
p_nus->conn_handle = p_ble_evt->evt.gap_evt.conn_handle;
}
/**@brief Function for handling the @ref BLE_GAP_EVT_DISCONNECTED event from the S110
* SoftDevice.
*
* @param[in] p_nus Nordic UART Service structure.
* @param[in] p_ble_evt Pointer to the event received from BLE stack.
*/
static void on_disconnect(ble_nus_t * p_nus, ble_evt_t * p_ble_evt)
{
UNUSED_PARAMETER(p_ble_evt);
p_nus->conn_handle = BLE_CONN_HANDLE_INVALID;
}
/**@brief Function for handling the @ref BLE_GATTS_EVT_WRITE event from the S110 SoftDevice.
*
* @param[in] p_dfu Nordic UART Service structure.
* @param[in] p_ble_evt Pointer to the event received from BLE stack.
*/
static void on_write(ble_nus_t * p_nus, ble_evt_t * p_ble_evt)
{
ble_gatts_evt_write_t * p_evt_write = &p_ble_evt->evt.gatts_evt.params.write;
if (
(p_evt_write->handle == p_nus->rx_handles.cccd_handle)
&&
(p_evt_write->len == 2)
)
{
if (ble_srv_is_notification_enabled(p_evt_write->data))
{
p_nus->is_notification_enabled = true;
}
else
{
p_nus->is_notification_enabled = false;
}
}
else if (
(p_evt_write->handle == p_nus->tx_handles.value_handle)
&&
(p_nus->data_handler != NULL)
)
{
p_nus->data_handler(p_nus, p_evt_write->data, p_evt_write->len);
}
else
{
// Do Nothing. This event is not relevant to this service.
}
}
/**@brief Function for adding RX characteristic.
*
* @param[in] p_nus Nordic UART Service structure.
* @param[in] p_nus_init Information needed to initialize the service.
*
* @return NRF_SUCCESS on success, otherwise an error code.
*/
static uint32_t rx_char_add(ble_nus_t * p_nus, const ble_nus_init_t * p_nus_init)
{
/**@snippet [Adding proprietary characteristic to S110 SoftDevice] */
ble_gatts_char_md_t char_md;
ble_gatts_attr_md_t cccd_md;
ble_gatts_attr_t attr_char_value;
ble_uuid_t ble_uuid;
ble_gatts_attr_md_t attr_md;
memset(&cccd_md, 0, sizeof(cccd_md));
BLE_GAP_CONN_SEC_MODE_SET_OPEN(&cccd_md.read_perm);
BLE_GAP_CONN_SEC_MODE_SET_OPEN(&cccd_md.write_perm);
cccd_md.vloc = BLE_GATTS_VLOC_STACK;
memset(&char_md, 0, sizeof(char_md));
char_md.char_props.notify = 1;
char_md.p_char_user_desc = NULL;
char_md.p_char_pf = NULL;
char_md.p_user_desc_md = NULL;
char_md.p_cccd_md = &cccd_md;
char_md.p_sccd_md = NULL;
ble_uuid.type = p_nus->uuid_type;
ble_uuid.uuid = BLE_UUID_NUS_RX_CHARACTERISTIC;
memset(&attr_md, 0, sizeof(attr_md));
BLE_GAP_CONN_SEC_MODE_SET_OPEN(&attr_md.read_perm);
BLE_GAP_CONN_SEC_MODE_SET_OPEN(&attr_md.write_perm);
attr_md.vloc = BLE_GATTS_VLOC_STACK;
attr_md.rd_auth = 0;
attr_md.wr_auth = 0;
attr_md.vlen = 1;
memset(&attr_char_value, 0, sizeof(attr_char_value));
attr_char_value.p_uuid = &ble_uuid;
attr_char_value.p_attr_md = &attr_md;
attr_char_value.init_len = sizeof(uint8_t);
attr_char_value.init_offs = 0;
attr_char_value.max_len = BLE_NUS_MAX_RX_CHAR_LEN;
return sd_ble_gatts_characteristic_add(p_nus->service_handle,
&char_md,
&attr_char_value,
&p_nus->rx_handles);
/**@snippet [Adding proprietary characteristic to S110 SoftDevice] */
}
/**@brief Function for adding TX characteristic.
*
* @param[in] p_nus Nordic UART Service structure.
* @param[in] p_nus_init Information needed to initialize the service.
*
* @return NRF_SUCCESS on success, otherwise an error code.
*/
static uint32_t tx_char_add(ble_nus_t * p_nus, const ble_nus_init_t * p_nus_init)
{
ble_gatts_char_md_t char_md;
ble_gatts_attr_t attr_char_value;
ble_uuid_t ble_uuid;
ble_gatts_attr_md_t attr_md;
memset(&char_md, 0, sizeof(char_md));
char_md.char_props.write = 1;
char_md.char_props.write_wo_resp = 1;
char_md.p_char_user_desc = NULL;
char_md.p_char_pf = NULL;
char_md.p_user_desc_md = NULL;
char_md.p_cccd_md = NULL;
char_md.p_sccd_md = NULL;
ble_uuid.type = p_nus->uuid_type;
ble_uuid.uuid = BLE_UUID_NUS_TX_CHARACTERISTIC;
memset(&attr_md, 0, sizeof(attr_md));
BLE_GAP_CONN_SEC_MODE_SET_OPEN(&attr_md.read_perm);
BLE_GAP_CONN_SEC_MODE_SET_OPEN(&attr_md.write_perm);
attr_md.vloc = BLE_GATTS_VLOC_STACK;
attr_md.rd_auth = 0;
attr_md.wr_auth = 0;
attr_md.vlen = 1;
memset(&attr_char_value, 0, sizeof(attr_char_value));
attr_char_value.p_uuid = &ble_uuid;
attr_char_value.p_attr_md = &attr_md;
attr_char_value.init_len = 1;
attr_char_value.init_offs = 0;
attr_char_value.max_len = BLE_NUS_MAX_TX_CHAR_LEN;
return sd_ble_gatts_characteristic_add(p_nus->service_handle,
&char_md,
&attr_char_value,
&p_nus->tx_handles);
}
void ble_nus_on_ble_evt(ble_nus_t * p_nus, ble_evt_t * p_ble_evt)
{
if ((p_nus == NULL) || (p_ble_evt == NULL))
{
return;
}
switch (p_ble_evt->header.evt_id)
{
case BLE_GAP_EVT_CONNECTED:
on_connect(p_nus, p_ble_evt);
break;
case BLE_GAP_EVT_DISCONNECTED:
on_disconnect(p_nus, p_ble_evt);
break;
case BLE_GATTS_EVT_WRITE:
on_write(p_nus, p_ble_evt);
break;
default:
// No implementation needed.
break;
}
}
uint32_t ble_nus_init(ble_nus_t * p_nus, const ble_nus_init_t * p_nus_init)
{
uint32_t err_code;
ble_uuid_t ble_uuid;
ble_uuid128_t nus_base_uuid = {{0x9E, 0xCA, 0xDC, 0x24, 0x0E, 0xE5, 0xA9, 0xE0,
0x93, 0xF3, 0xA3, 0xB5, 0x00, 0x00, 0x40, 0x6E}};
if ((p_nus == NULL) || (p_nus_init == NULL))
{
return NRF_ERROR_NULL;
}
// Initialize service structure.
p_nus->conn_handle = BLE_CONN_HANDLE_INVALID;
p_nus->data_handler = p_nus_init->data_handler;
p_nus->is_notification_enabled = false;
/**@snippet [Adding proprietary Service to S110 SoftDevice] */
// Add custom base UUID.
err_code = sd_ble_uuid_vs_add(&nus_base_uuid, &p_nus->uuid_type);
if (err_code != NRF_SUCCESS)
{
return err_code;
}
ble_uuid.type = p_nus->uuid_type;
ble_uuid.uuid = BLE_UUID_NUS_SERVICE;
// Add service.
err_code = sd_ble_gatts_service_add(BLE_GATTS_SRVC_TYPE_PRIMARY,
&ble_uuid,
&p_nus->service_handle);
/**@snippet [Adding proprietary Service to S110 SoftDevice] */
if (err_code != NRF_SUCCESS)
{
return err_code;
}
// Add RX Characteristic.
err_code = rx_char_add(p_nus, p_nus_init);
if (err_code != NRF_SUCCESS)
{
return err_code;
}
// Add TX Characteristic.
err_code = tx_char_add(p_nus, p_nus_init);
if (err_code != NRF_SUCCESS)
{
return err_code;
}
return NRF_SUCCESS;
}
uint32_t ble_nus_send_string(ble_nus_t * p_nus, uint8_t * string, uint16_t length)
{
ble_gatts_hvx_params_t hvx_params;
if (p_nus == NULL)
{
return NRF_ERROR_NULL;
}
if ((p_nus->conn_handle == BLE_CONN_HANDLE_INVALID) || (!p_nus->is_notification_enabled))
{
return NRF_ERROR_INVALID_STATE;
}
if (length > BLE_NUS_MAX_DATA_LEN)
{
return NRF_ERROR_INVALID_PARAM;
}
memset(&hvx_params, 0, sizeof(hvx_params));
hvx_params.handle = p_nus->rx_handles.value_handle;
hvx_params.p_data = string;
hvx_params.p_len = &length;
hvx_params.type = BLE_GATT_HVX_NOTIFICATION;
return sd_ble_gatts_hvx(p_nus->conn_handle, &hvx_params);
}

125
ble_nus.h Normal file
View File

@ -0,0 +1,125 @@
/* Copyright (c) 2012 Nordic Semiconductor. All Rights Reserved.
*
* The information contained herein is property of Nordic Semiconductor ASA.
* Terms and conditions of usage are described in detail in NORDIC
* SEMICONDUCTOR STANDARD SOFTWARE LICENSE AGREEMENT.
*
* Licensees are granted free, non-transferable use of the information. NO
* WARRANTY of ANY KIND is provided. This heading must NOT be removed from
* the file.
*
*/
/**@file
*
* @defgroup ble_sdk_srv_nus Nordic UART Service - Experimental
* @{
* @ingroup ble_sdk_srv
* @brief Nordic UART Service implementation.
*
* @details The Nordic UART Service is a simple GATT based service with a TX and RX
* characteristics. Data received from the peer will be passed to the application and the
* data received from the application of this service will be sent to the peer as Handle
* Value Notifications. This module is intended to demonstrate how custom GATT based
* service and characteristics can be implemented using the S110 SoftDevice. This service
* is used by the application to send and receive ASCII text strings to and from the
* peer.
*
* @note The application must propagate S110 SoftDevice events to the Nordic UART Service module
* by calling the ble_nus_on_ble_evt() function from the @ref ble_stack_handler callback.
*/
#ifndef BLE_NUS_H__
#define BLE_NUS_H__
#include "ble.h"
#include "ble_srv_common.h"
#include <stdint.h>
#include <stdbool.h>
#define BLE_UUID_NUS_SERVICE 0x0001 /**< The UUID of the Nordic UART Service. */
#define BLE_UUID_NUS_TX_CHARACTERISTIC 0x0002 /**< The UUID of the TX Characteristic. */
#define BLE_UUID_NUS_RX_CHARACTERISTIC 0x0003 /**< The UUID of the RX Characteristic. */
#define BLE_NUS_MAX_DATA_LEN (GATT_MTU_SIZE_DEFAULT - 3) /**< Maximum length of data (in bytes) that can be transmitted by the Nordic UART service module to the peer. */
#define BLE_NUS_MAX_RX_CHAR_LEN BLE_NUS_MAX_DATA_LEN /**< Maximum length of the RX Characteristic (in bytes). */
#define BLE_NUS_MAX_TX_CHAR_LEN 20 /**< Maximum length of the TX Characteristic (in bytes). */
// Forward declaration of the ble_nus_t type.
typedef struct ble_nus_s ble_nus_t;
/**@brief Nordic UART Service event handler type. */
typedef void (*ble_nus_data_handler_t) (ble_nus_t * p_nus, uint8_t * data, uint16_t length);
/**@brief Nordic UART Service init structure.
*
* @details This structure contains the initialization information for the service. The application
* needs to fill this structure and pass it to the service using the @ref ble_nus_init
* function.
*/
typedef struct
{
ble_nus_data_handler_t data_handler; /**< Event handler to be called for handling received data. */
} ble_nus_init_t;
/**@brief Nordic UART Service structure.
*
* @details This structure contains status information related to the service.
*/
typedef struct ble_nus_s
{
uint8_t uuid_type; /**< UUID type for Nordic UART Service Base UUID. */
uint16_t service_handle; /**< Handle of Nordic UART Service (as provided by the S110 SoftDevice). */
ble_gatts_char_handles_t tx_handles; /**< Handles related to the TX characteristic. (as provided by the S110 SoftDevice)*/
ble_gatts_char_handles_t rx_handles; /**< Handles related to the RX characteristic. (as provided by the S110 SoftDevice)*/
uint16_t conn_handle; /**< Handle of the current connection (as provided by the S110 SoftDevice). This will be BLE_CONN_HANDLE_INVALID if not in a connection. */
bool is_notification_enabled; /**< Variable to indicate if the peer has enabled notification of the RX characteristic.*/
ble_nus_data_handler_t data_handler; /**< Event handler to be called for handling received data. */
} ble_nus_t;
/**@brief Function for initializing the Nordic UART Service.
*
* @param[out] p_nus Nordic UART Service structure. This structure will have to be supplied
* by the application. It will be initialized by this function and will
* later be used to identify this particular service instance.
* @param[in] p_nus_init Information needed to initialize the service.
*
* @return NRF_SUCCESS on successful initialization of service, otherwise an error code.
* This function returns NRF_ERROR_NULL if either of the pointers p_nus or p_nus_init
* is NULL.
*/
uint32_t ble_nus_init(ble_nus_t * p_nus, const ble_nus_init_t * p_nus_init);
/**@brief Nordic UART Service BLE event handler.
*
* @details The Nordic UART service expects the application to call this function each time an
* event is received from the S110 SoftDevice. This function processes the event if it
* is relevant for it and calls the Nordic UART Service event handler of the
* application if necessary.
*
* @param[in] p_nus Nordic UART Service structure.
* @param[in] p_ble_evt Event received from the S110 SoftDevice.
*/
void ble_nus_on_ble_evt(ble_nus_t * p_nus, ble_evt_t * p_ble_evt);
/**@brief Function for sending a string to the peer.
*
* @details This function will send the input string as a RX characteristic notification to the
* peer.
*
* @param[in] p_nus Pointer to the Nordic UART Service structure.
* @param[in] string String to be sent.
* @param[in] length Length of string.
*
* @return NRF_SUCCESS if the DFU Service has successfully requested the S110 SoftDevice to
* send the notification. Otherwise an error code.
* This function returns NRF_ERROR_INVALID_STATE if the device is not connected to a
* peer or if the notification of the RX characteristic was not enabled by the peer.
* It returns NRF_ERROR_NULL if the pointer p_nus is NULL.
*/
uint32_t ble_nus_send_string(ble_nus_t * p_nus, uint8_t * string, uint16_t length);
#endif // BLE_NUS_H__
/** @} */

56
gcc/Makefile Normal file
View File

@ -0,0 +1,56 @@
TARGET_CHIP := NRF51822_QFAA_CA
BOARD := BOARD_PCA10001
# application source
C_SOURCE_FILES += main.c
C_SOURCE_FILES += ble_srv_common.c
C_SOURCE_FILES += ble_nus.c
C_SOURCE_FILES += ble_advdata.c
C_SOURCE_FILES += ble_conn_params.c
C_SOURCE_FILES += softdevice_handler.c
C_SOURCE_FILES += app_timer.c
C_SOURCE_FILES += app_uart_fifo_mod.c
C_SOURCE_FILES += app_fifo.c
C_SOURCE_FILES += app_gpiote.c
C_SOURCE_FILES += ble_debug_assert_handler.c
SDK_PATH = ../../../../../
#SDK_PATH = /Users/pg/code/blenano/7_0/
OUTPUT_FILENAME := ble_app_uart
DEVICE_VARIANT := xxaa
#DEVICE_VARIANT := blenano
#DEVICE_VARIANT := xxab
USE_SOFTDEVICE := S110
#USE_SOFTDEVICE := S210
CFLAGS := -DDEBUG_NRF_USER -DBLE_STACK_SUPPORT_REQD -DS110 -Wall
# we do not use heap in this app
ASMFLAGS := -D__HEAP_SIZE=0
# keep every function in separate section. This will allow linker to dump unused functions
CFLAGS += -ffunction-sections
# let linker to dump unused sections
#LDFLAGS := -Wl,--gc-sections
INCLUDEPATHS += -I"../"
INCLUDEPATHS += -I"$(SDK_PATH)Include/s110"
INCLUDEPATHS += -I"$(SDK_PATH)Include/ble"
INCLUDEPATHS += -I"$(SDK_PATH)Include/ble/device_manager"
INCLUDEPATHS += -I"$(SDK_PATH)Include/ble/ble_services"
INCLUDEPATHS += -I"$(SDK_PATH)Include/app_common"
INCLUDEPATHS += -I"$(SDK_PATH)Include/sd_common"
C_SOURCE_PATHS += $(SDK_PATH)Source/ble
C_SOURCE_PATHS += $(SDK_PATH)Source/ble/device_manager
C_SOURCE_PATHS += $(SDK_PATH)Source/app_common
C_SOURCE_PATHS += $(SDK_PATH)Source/sd_common
include $(SDK_PATH)Source/templates/gcc/Makefile.common

24
gcc/_build/app_fifo.d Normal file
View File

@ -0,0 +1,24 @@
_build/app_fifo.o: \
/Users/pg/code/blenano/nrf51822/Source/app_common/app_fifo.c \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_fifo.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/ieeefp.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/newlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/config.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stddef.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/reent.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/lock.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/alloca.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h

BIN
gcc/_build/app_fifo.o Normal file

Binary file not shown.

42
gcc/_build/app_gpiote.d Normal file
View File

@ -0,0 +1,42 @@
_build/app_gpiote.o: \
/Users/pg/code/blenano/nrf51822/Source/app_common/app_gpiote.c \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_gpiote.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/Users/pg/code/blenano/nrf51822/Include/nrf.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cm0.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmInstr.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmFunc.h \
/Users/pg/code/blenano/nrf51822/Include/system_nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_bitfields.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_deprecated.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/ieeefp.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/newlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/config.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stddef.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/reent.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/lock.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/alloca.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/string.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include-fixed/sys/cdefs.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/string.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/sd_common/app_util_platform.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/nrf_gpio.h

BIN
gcc/_build/app_gpiote.o Normal file

Binary file not shown.

50
gcc/_build/app_timer.d Normal file
View File

@ -0,0 +1,50 @@
_build/app_timer.o: \
/Users/pg/code/blenano/nrf51822/Source/app_common/app_timer.c \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_timer.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdio.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/newlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/config.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/ieeefp.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stddef.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdarg.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/reent.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/lock.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/stdio.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_scheduler.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/alloca.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cm0.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmInstr.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmFunc.h \
/Users/pg/code/blenano/nrf51822/Include/system_nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_bitfields.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_soc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_svc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error_soc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/nrf_delay.h \
/Users/pg/code/blenano/nrf51822/Include/nrf.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_bitfields.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_deprecated.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/sd_common/app_util_platform.h

BIN
gcc/_build/app_timer.o Normal file

Binary file not shown.

View File

@ -0,0 +1,40 @@
_build/app_uart_fifo_mod.o: ../app_uart_fifo_mod.c \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_uart.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/Users/pg/code/blenano/nrf51822/Include/sd_common/app_util_platform.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cm0.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmInstr.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmFunc.h \
/Users/pg/code/blenano/nrf51822/Include/system_nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_fifo.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/ieeefp.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/newlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/config.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stddef.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/reent.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/lock.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/alloca.h \
/Users/pg/code/blenano/nrf51822/Include/nrf.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_bitfields.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_deprecated.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/nrf_gpio.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_gpiote.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h

Binary file not shown.

40
gcc/_build/ble_advdata.d Normal file
View File

@ -0,0 +1,40 @@
_build/ble_advdata.o: \
/Users/pg/code/blenano/nrf51822/Source/ble/ble_advdata.c \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_advdata.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/string.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/newlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/config.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/ieeefp.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/reent.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stddef.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/lock.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include-fixed/sys/cdefs.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/string.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_ranges.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_types.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_svc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_l2cap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_err.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatt.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gattc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatts.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/nordic_common.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gap.h \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_services/ble_srv_common.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_types.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatt.h

BIN
gcc/_build/ble_advdata.o Normal file

Binary file not shown.

Binary file not shown.

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

Binary file not shown.

View File

@ -0,0 +1,50 @@
_build/ble_conn_params.o: \
/Users/pg/code/blenano/nrf51822/Source/ble/ble_conn_params.c \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_conn_params.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_ranges.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_types.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_svc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_l2cap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_err.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatt.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gattc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatts.h \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_services/ble_srv_common.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_types.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatt.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/ieeefp.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/newlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/config.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stddef.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/reent.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/lock.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/alloca.h \
/Users/pg/code/blenano/nrf51822/Include/nordic_common.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_hci.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_timer.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdio.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdarg.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/stdio.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_scheduler.h

Binary file not shown.

View File

@ -0,0 +1,29 @@
_build/ble_debug_assert_handler.o: \
/Users/pg/code/blenano/nrf51822/Source/ble/ble_debug_assert_handler.c \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_debug_assert_handler.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/string.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/newlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/config.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/ieeefp.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/reent.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stddef.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/lock.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include-fixed/sys/cdefs.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/string.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cm0.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmInstr.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmFunc.h \
/Users/pg/code/blenano/nrf51822/Include/system_nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_error_log.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_flash.h \
/Users/pg/code/blenano/nrf51822/Include/nordic_common.h

Binary file not shown.

37
gcc/_build/ble_nus.d Normal file
View File

@ -0,0 +1,37 @@
_build/ble_nus.o: ../ble_nus.c ../ble_nus.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_ranges.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_svc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_l2cap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_err.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatt.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gattc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatts.h \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_services/ble_srv_common.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_types.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatt.h \
/Users/pg/code/blenano/nrf51822/Include/nordic_common.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/string.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/newlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/config.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/ieeefp.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/reent.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stddef.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/lock.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include-fixed/sys/cdefs.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/string.h

BIN
gcc/_build/ble_nus.o Normal file

Binary file not shown.

View File

@ -0,0 +1,32 @@
_build/ble_srv_common.o: \
/Users/pg/code/blenano/nrf51822//Source/ble/ble_services/ble_srv_common.c \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_services/ble_srv_common.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_types.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_types.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_ranges.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_svc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatt.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/string.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/newlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/config.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/ieeefp.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/reent.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stddef.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/lock.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include-fixed/sys/cdefs.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/string.h \
/Users/pg/code/blenano/nrf51822/Include/nordic_common.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h

BIN
gcc/_build/ble_srv_common.o Normal file

Binary file not shown.

Binary file not shown.

82
gcc/_build/main.d Normal file
View File

@ -0,0 +1,82 @@
_build/main.o: ../main.c \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/string.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/newlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/config.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/ieeefp.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/reent.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stddef.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/lock.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include-fixed/sys/cdefs.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/string.h \
/Users/pg/code/blenano/nrf51822/Include/nordic_common.h \
/Users/pg/code/blenano/nrf51822/Include/nrf.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cm0.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmInstr.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmFunc.h \
/Users/pg/code/blenano/nrf51822/Include/system_nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_bitfields.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_deprecated.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_bitfields.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_hci.h \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_advdata.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_ranges.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_types.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_svc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_l2cap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_err.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatt.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gattc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatts.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_conn_params.h \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_services/ble_srv_common.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_types.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatt.h \
/Users/pg/code/blenano/nrf51822/Include/sd_common/softdevice_handler.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/alloca.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_sdm.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_soc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error_soc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error_sdm.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_scheduler.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/sd_common/ble_stack_handler_types.h \
/Users/pg/code/blenano/nrf51822/Include/sd_common/ant_stack_handler_types.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_timer.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdio.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdarg.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/stdio.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_scheduler.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_button.h \
/Users/pg/code/blenano/nrf51822/Include/nrf_gpio.h ../ble_nus.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_uart.h \
/Users/pg/code/blenano/nrf51822/Include/sd_common/app_util_platform.h \
../uart_conf.h /Users/pg/code/blenano/nrf51822/Include/boards.h \
/Users/pg/code/blenano/nrf51822/Include/boards/pca10001.h \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_error_log.h \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_flash.h \
/Users/pg/code/blenano/nrf51822/Include/ble/ble_debug_assert_handler.h

BIN
gcc/_build/main.o Normal file

Binary file not shown.

View File

@ -0,0 +1,53 @@
_build/softdevice_handler.o: \
/Users/pg/code/blenano/nrf51822/Source/sd_common/softdevice_handler.c \
/Users/pg/code/blenano/nrf51822/Include/sd_common/softdevice_handler.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/ieeefp.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/newlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/config.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stddef.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/reent.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/_ansi.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/lock.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/stdlib.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/alloca.h \
/Users/pg/code/blenano/nrf51822/Include/nordic_common.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_sdm.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_svc.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cm0.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmInstr.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmFunc.h \
/Users/pg/code/blenano/nrf51822/Include/system_nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_soc.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_bitfields.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error_soc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error_sdm.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_error.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_scheduler.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_error.h \
/Users/pg/code/blenano/nrf51822/Include/app_common/app_util.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/sd_common/ble_stack_handler_types.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_ranges.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_types.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_l2cap.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_err.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatt.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gattc.h \
/Users/pg/code/blenano/nrf51822/Include/s110/ble_gatts.h \
/Users/pg/code/blenano/nrf51822/Include/sd_common/ant_stack_handler_types.h \
/Users/pg/code/blenano/nrf51822/Include/nrf_assert.h \
/Users/pg/code/blenano/nrf51822/Include/s110/nrf_soc.h

Binary file not shown.

17
gcc/_build/system_nrf51.d Normal file
View File

@ -0,0 +1,17 @@
_build/system_nrf51.o: \
/Users/pg/code/blenano/nrf51822//Source/templates/system_nrf51.c \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/stdint.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/machine/_default_types.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/arm-none-eabi/include/sys/features.h \
/usr/local/gcc-arm-none-eabi-4_8-2014q1/lib/gcc/arm-none-eabi/4.8.3/include/stdbool.h \
/Users/pg/code/blenano/nrf51822/Include/nrf.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cm0.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmInstr.h \
/Users/pg/code/blenano/nrf51822/Include/gcc/core_cmFunc.h \
/Users/pg/code/blenano/nrf51822/Include/system_nrf51.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_bitfields.h \
/Users/pg/code/blenano/nrf51822/Include/nrf51_deprecated.h \
/Users/pg/code/blenano/nrf51822/Include/compiler_abstraction.h \
/Users/pg/code/blenano/nrf51822/Include/system_nrf51.h

BIN
gcc/_build/system_nrf51.o Normal file

Binary file not shown.

8835
gcc/_build/uart.hex Normal file

File diff suppressed because it is too large Load Diff

653
main.c Normal file
View File

@ -0,0 +1,653 @@
/* Copyright (c) 2014 Nordic Semiconductor. All Rights Reserved.
*
* Use of this source code is governed by a BSD-style license that can be
* found in the license.txt file.
*/
/** @file
* @brief UART over BLE application using the app_uart library (event driven).
*
* This UART example is configured with flow control enabled which is necessary when softdevice
* is enabled, in order to prevent data loss. To connect the development kit with your PC via
* UART, connect the configured RXD, TXD, RTS and CTS pins to the RXD, TXD, RTS and CTS pins
* on header P15 on the motherboard. Then connect the RS232 port on the nRFgo motherboard to
* your PC. Configuration for UART pins is defined in the uart_conf.h header file.
*
* This file contains source code for a sample application that uses the Nordic UART service.
* Connect to the UART example via Master Control Panel and the PCA10000 USB dongle, or via
* nRF UART 2.0 app for Android, or nRF UART app for IOS, available on
* https://www.nordicsemi.com/Products/nRFready-Demo-APPS.
*
* This example should be operated in the same way as the UART example for the evaluation board
* in the SDK. Follow the same guide for this example, given on:
* https://devzone.nordicsemi.com/documentation/nrf51/6.0.0/s110/html/a00066.html#project_uart_nus_eval_test
*
* This example uses FIFO RX and FIFO TX buffer to operate with the UART. You can set the size
* for the FIFO buffers by modifying the RX_BUFFER_SIZE and TX_BUFFER_SIZE constants.
*
* Documentation for the app_uart library is given in UART driver documentation in the SDK at:
* https://devzone.nordicsemi.com/documentation/nrf51/6.1.0/s110/html/a00008.html
*/
/** @file
*
* @defgroup ble_sdk_uart_over_ble_main main.c
* @{
* @ingroup ble_sdk_app_nus_eval
* @brief UART over BLE application main file.
*
* This file contains the source code for a sample application that uses the Nordic UART service.
* This application uses the @ref srvlib_conn_params module.
*/
#include <stdint.h>
#include <string.h>
#include "nordic_common.h"
#include "nrf.h"
#include "nrf51_bitfields.h"
#include "ble_hci.h"
#include "ble_advdata.h"
#include "ble_conn_params.h"
#include "softdevice_handler.h"
#include "app_timer.h"
#include "app_button.h"
#include "ble_nus.h"
#include "app_uart.h"
#include "uart_conf.h"
#include "boards.h"
#include "ble_error_log.h"
#include "ble_debug_assert_handler.h"
#include "app_util_platform.h"
#define IS_SRVC_CHANGED_CHARACT_PRESENT 0 /**< Include or not the service_changed characteristic. if not enabled, the server's database cannot be changed for the lifetime of the device*/
#define WAKEUP_BUTTON_PIN BUTTON_0 /**< Button used to wake up the application. */
#define ADVERTISING_LED_PIN_NO LED_0 /**< LED to indicate advertising state. */
#define CONNECTED_LED_PIN_NO LED_1 /**< LED to indicate connected state. */
#define DEVICE_NAME "MY_UART" /**< Name of device. Will be included in the advertising data. */
#define APP_ADV_INTERVAL 64 /**< The advertising interval (in units of 0.625 ms. This value corresponds to 40 ms). */
#define APP_ADV_TIMEOUT_IN_SECONDS 180 /**< The advertising timeout (in units of seconds). */
#define APP_TIMER_PRESCALER 0 /**< Value of the RTC1 PRESCALER register. */
#define APP_TIMER_MAX_TIMERS 2 /**< Maximum number of simultaneously created timers. */
#define APP_TIMER_OP_QUEUE_SIZE 4 /**< Size of timer operation queues. */
#define MIN_CONN_INTERVAL 7.5 /**< Minimum acceptable connection interval (20 ms), Connection interval uses 1.25 ms units. */
#define MAX_CONN_INTERVAL 60 /**< Maximum acceptable connection interval (75 ms), Connection interval uses 1.25 ms units. */
#define SLAVE_LATENCY 0 /**< slave latency. */
#define CONN_SUP_TIMEOUT 400 /**< Connection supervisory timeout (4 seconds), Supervision Timeout uses 10 ms units. */
#define FIRST_CONN_PARAMS_UPDATE_DELAY APP_TIMER_TICKS(5000, APP_TIMER_PRESCALER) /**< Time from initiating event (connect or start of notification) to first time sd_ble_gap_conn_param_update is called (5 seconds). */
#define NEXT_CONN_PARAMS_UPDATE_DELAY APP_TIMER_TICKS(30000, APP_TIMER_PRESCALER) /**< Time between each call to sd_ble_gap_conn_param_update after the first call (30 seconds). */
#define MAX_CONN_PARAMS_UPDATE_COUNT 3 /**< Number of attempts before giving up the connection parameter negotiation. */
#define BUTTON_DETECTION_DELAY APP_TIMER_TICKS(50, APP_TIMER_PRESCALER) /**< Delay from a GPIOTE event until a button is reported as pushed (in number of timer ticks). */
#define SEC_PARAM_TIMEOUT 30 /**< Timeout for Pairing Request or Security Request (in seconds). */
#define SEC_PARAM_BOND 1 /**< Perform bonding. */
#define SEC_PARAM_MITM 0 /**< Man In The Middle protection not required. */
#define SEC_PARAM_IO_CAPABILITIES BLE_GAP_IO_CAPS_NONE /**< No I/O capabilities. */
#define SEC_PARAM_OOB 0 /**< Out Of Band data not available. */
#define SEC_PARAM_MIN_KEY_SIZE 7 /**< Minimum encryption key size. */
#define SEC_PARAM_MAX_KEY_SIZE 16 /**< Maximum encryption key size. */
#define START_STRING "Start...\n" /**< The string that will be sent over the UART when the application starts. */
#define DEAD_BEEF 0xDEADBEEF /**< Value used as error code on stack dump, can be used to identify stack location on stack unwind. */
#define APP_GPIOTE_MAX_USERS 1
static ble_gap_sec_params_t m_sec_params; /**< Security requirements for this application. */
static uint16_t m_conn_handle = BLE_CONN_HANDLE_INVALID; /**< Handle of the current connection. */
static ble_nus_t m_nus; /**< Structure to identify the Nordic UART Service. */
static bool ble_buffer_available = true;
static bool tx_complete = false;
/**@brief Error handler function, which is called when an error has occurred.
*
* @warning This handler is an example only and does not fit a final product. You need to analyze
* how your product is supposed to react in case of error.
*
* @param[in] error_code Error code supplied to the handler.
* @param[in] line_num Line number where the handler is called.
* @param[in] p_file_name Pointer to the file name.
*/
void uart_putstring(const uint8_t * str);
void app_error_handler(uint32_t error_code, uint32_t line_num, const uint8_t * p_file_name)
{
// This call can be used for debug purposes during application development.
// @note CAUTION: Activating this code will write the stack to flash on an error.
// This function should NOT be used in a final product.
// It is intended STRICTLY for development/debugging purposes.
// The flash write will happen EVEN if the radio is active, thus interrupting
// any communication.
// Use with care. Un-comment the line below to use.
//ble_debug_assert_handler(error_code, line_num, p_file_name);
// On assert, the system can only recover with a reset.
NVIC_SystemReset();
}
/**@brief Assert macro callback function.
*
* @details This function will be called in case of an assert in the SoftDevice.
*
* @warning This handler is an example only and does not fit a final product. You need to
* analyze how your product is supposed to react in case of Assert.
* @warning On assert from the SoftDevice, the system can only recover on reset.
*
* @param[in] line_num Line number of the failing ASSERT call.
* @param[in] file_name File name of the failing ASSERT call.
*/
void assert_nrf_callback(uint16_t line_num, const uint8_t * p_file_name)
{
app_error_handler(DEAD_BEEF, line_num, p_file_name);
}
/**@brief Function for the LEDs initialization.
*
* @details Initializes all LEDs used by this application.
*/
static void leds_init(void)
{
nrf_gpio_cfg_output(ADVERTISING_LED_PIN_NO);
nrf_gpio_cfg_output(CONNECTED_LED_PIN_NO);
}
/**@brief Function for Timer initialization.
*
* @details Initializes the timer module.
*/
static void timers_init(void)
{
// Initialize timer module
APP_TIMER_INIT(APP_TIMER_PRESCALER, APP_TIMER_MAX_TIMERS, APP_TIMER_OP_QUEUE_SIZE, false);
}
/**@brief Function for the GAP initialization.
*
* @details This function will setup all the necessary GAP (Generic Access Profile)
* parameters of the device. It also sets the permissions and appearance.
*/
static void gap_params_init(void)
{
uint32_t err_code;
ble_gap_conn_params_t gap_conn_params;
ble_gap_conn_sec_mode_t sec_mode;
BLE_GAP_CONN_SEC_MODE_SET_OPEN(&sec_mode);
err_code = sd_ble_gap_device_name_set(&sec_mode,
(const uint8_t *) DEVICE_NAME,
strlen(DEVICE_NAME));
APP_ERROR_CHECK(err_code);
memset(&gap_conn_params, 0, sizeof(gap_conn_params));
gap_conn_params.min_conn_interval = MIN_CONN_INTERVAL;
gap_conn_params.max_conn_interval = MAX_CONN_INTERVAL;
gap_conn_params.slave_latency = SLAVE_LATENCY;
gap_conn_params.conn_sup_timeout = CONN_SUP_TIMEOUT;
err_code = sd_ble_gap_ppcp_set(&gap_conn_params);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for the Advertising functionality initialization.
*
* @details Encodes the required advertising data and passes it to the stack.
* Also builds a structure to be passed to the stack when starting advertising.
*/
static void advertising_init(void)
{
char buf[80];
uint32_t err_code;
ble_advdata_t advdata;
//ble_advdata_t scanrsp;
uint8_t flags = BLE_GAP_ADV_FLAGS_LE_ONLY_LIMITED_DISC_MODE;
ble_uuid_t adv_uuids[] = {{BLE_UUID_NUS_SERVICE, BLE_UUID_TYPE_VENDOR_BEGIN}};
memset(&advdata, 0, sizeof(advdata));
advdata.name_type = BLE_ADVDATA_FULL_NAME;
advdata.include_appearance = false;
advdata.flags.size = sizeof(flags);
advdata.flags.p_data = &flags;
//memset(&scanrsp, 0, sizeof(scanrsp));
advdata.uuids_complete.uuid_cnt = sizeof(adv_uuids) / sizeof(adv_uuids[0]);
advdata.uuids_complete.p_uuids = adv_uuids;
//err_code = ble_advdata_set(&advdata, &scanrsp);
err_code = ble_advdata_set(&advdata, NULL);
//printf("err code : %s\n","prout");
snprintf(buf, sizeof(buf), "err : %u\n", (unsigned int)err_code);
uart_putstring((const uint8_t*)buf);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for handling the data from the Nordic UART Service.
*
* @details This function will process the data received from the Nordic UART BLE Service and send
* it to the UART module.
*/
/**@snippet [Handling the data received over BLE] */
void nus_data_handler(ble_nus_t * p_nus, uint8_t * p_data, uint16_t length)
{
for (int i = 0; i < length; i++)
{
app_uart_put(p_data[i]);
}
app_uart_put('\n');
}
/**@snippet [Handling the data received over BLE] */
/**@brief Function for initializing services that will be used by the application.
*/
static void services_init(void)
{
uint32_t err_code;
ble_nus_init_t nus_init;
memset(&nus_init, 0, sizeof(nus_init));
nus_init.data_handler = nus_data_handler;
err_code = ble_nus_init(&m_nus, &nus_init);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for initializing security parameters.
*/
static void sec_params_init(void)
{
m_sec_params.timeout = SEC_PARAM_TIMEOUT;
m_sec_params.bond = SEC_PARAM_BOND;
m_sec_params.mitm = SEC_PARAM_MITM;
m_sec_params.io_caps = SEC_PARAM_IO_CAPABILITIES;
m_sec_params.oob = SEC_PARAM_OOB;
m_sec_params.min_key_size = SEC_PARAM_MIN_KEY_SIZE;
m_sec_params.max_key_size = SEC_PARAM_MAX_KEY_SIZE;
}
/**@brief Function for handling an event from the Connection Parameters Module.
*
* @details This function will be called for all events in the Connection Parameters Module
* which are passed to the application.
*
* @note All this function does is to disconnect. This could have been done by simply setting
* the disconnect_on_fail config parameter, but instead we use the event handler
* mechanism to demonstrate its use.
*
* @param[in] p_evt Event received from the Connection Parameters Module.
*/
static void on_conn_params_evt(ble_conn_params_evt_t * p_evt)
{
uint32_t err_code;
if(p_evt->evt_type == BLE_CONN_PARAMS_EVT_FAILED)
{
err_code = sd_ble_gap_disconnect(m_conn_handle, BLE_HCI_CONN_INTERVAL_UNACCEPTABLE);
APP_ERROR_CHECK(err_code);
}
}
/**@brief Function for handling errors from the Connection Parameters module.
*
* @param[in] nrf_error Error code containing information about what went wrong.
*/
static void conn_params_error_handler(uint32_t nrf_error)
{
APP_ERROR_HANDLER(nrf_error);
}
/**@brief Function for initializing the Connection Parameters module.
*/
static void conn_params_init(void)
{
uint32_t err_code;
ble_conn_params_init_t cp_init;
memset(&cp_init, 0, sizeof(cp_init));
cp_init.p_conn_params = NULL;
cp_init.first_conn_params_update_delay = FIRST_CONN_PARAMS_UPDATE_DELAY;
cp_init.next_conn_params_update_delay = NEXT_CONN_PARAMS_UPDATE_DELAY;
cp_init.max_conn_params_update_count = MAX_CONN_PARAMS_UPDATE_COUNT;
cp_init.start_on_notify_cccd_handle = BLE_GATT_HANDLE_INVALID;
cp_init.disconnect_on_fail = false;
cp_init.evt_handler = on_conn_params_evt;
cp_init.error_handler = conn_params_error_handler;
err_code = ble_conn_params_init(&cp_init);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for starting advertising.
*/
static void advertising_start(void)
{
uint32_t err_code;
ble_gap_adv_params_t adv_params;
// Start advertising
memset(&adv_params, 0, sizeof(adv_params));
adv_params.type = BLE_GAP_ADV_TYPE_ADV_IND;
adv_params.p_peer_addr = NULL;
adv_params.fp = BLE_GAP_ADV_FP_ANY;
adv_params.interval = APP_ADV_INTERVAL;
adv_params.timeout = APP_ADV_TIMEOUT_IN_SECONDS;
err_code = sd_ble_gap_adv_start(&adv_params);
APP_ERROR_CHECK(err_code);
nrf_gpio_pin_set(ADVERTISING_LED_PIN_NO);
}
/**@brief Function for the Application's S110 SoftDevice event handler.
*
* @param[in] p_ble_evt S110 SoftDevice event.
*/
static void on_ble_evt(ble_evt_t * p_ble_evt)
{
uint32_t err_code;
static ble_gap_evt_auth_status_t m_auth_status;
ble_gap_enc_info_t * p_enc_info;
uart_putstring(( const uint8_t *)"on_ble_evt\n" ) ;
switch (p_ble_evt->header.evt_id)
{
case BLE_GAP_EVT_CONNECTED:
nrf_gpio_pin_set(CONNECTED_LED_PIN_NO);
nrf_gpio_pin_clear(ADVERTISING_LED_PIN_NO);
m_conn_handle = p_ble_evt->evt.gap_evt.conn_handle;
break;
case BLE_GAP_EVT_DISCONNECTED:
nrf_gpio_pin_clear(CONNECTED_LED_PIN_NO);
m_conn_handle = BLE_CONN_HANDLE_INVALID;
advertising_start();
break;
case BLE_GAP_EVT_SEC_PARAMS_REQUEST:
err_code = sd_ble_gap_sec_params_reply(m_conn_handle,
BLE_GAP_SEC_STATUS_SUCCESS,
&m_sec_params);
APP_ERROR_CHECK(err_code);
break;
case BLE_GATTS_EVT_SYS_ATTR_MISSING:
err_code = sd_ble_gatts_sys_attr_set(m_conn_handle, NULL, 0);
APP_ERROR_CHECK(err_code);
break;
case BLE_GAP_EVT_AUTH_STATUS:
m_auth_status = p_ble_evt->evt.gap_evt.params.auth_status;
break;
case BLE_GAP_EVT_SEC_INFO_REQUEST:
p_enc_info = &m_auth_status.periph_keys.enc_info;
if (p_enc_info->div == p_ble_evt->evt.gap_evt.params.sec_info_request.div)
{
err_code = sd_ble_gap_sec_info_reply(m_conn_handle, p_enc_info, NULL);
APP_ERROR_CHECK(err_code);
}
else
{
// No keys found for this device
err_code = sd_ble_gap_sec_info_reply(m_conn_handle, NULL, NULL);
APP_ERROR_CHECK(err_code);
}
break;
case BLE_GAP_EVT_TIMEOUT:
if (p_ble_evt->evt.gap_evt.params.timeout.src == BLE_GAP_TIMEOUT_SRC_ADVERTISEMENT)
{
nrf_gpio_pin_clear(ADVERTISING_LED_PIN_NO);
// Configure buttons with sense level low as wakeup source.
nrf_gpio_cfg_sense_input(WAKEUP_BUTTON_PIN,
BUTTON_PULL,
NRF_GPIO_PIN_SENSE_LOW);
// Go to system-off mode (this function will not return; wakeup will cause a reset)
err_code = sd_power_system_off();
APP_ERROR_CHECK(err_code);
}
break;
case BLE_EVT_TX_COMPLETE:
if(!ble_buffer_available) tx_complete = true;
break;
default:
// No implementation needed.
break;
}
}
/**@brief Function for dispatching a S110 SoftDevice event to all modules with a S110
* SoftDevice event handler.
*
* @details This function is called from the S110 SoftDevice event interrupt handler after a
* S110 SoftDevice event has been received.
*
* @param[in] p_ble_evt S110 SoftDevice event.
*/
static void ble_evt_dispatch(ble_evt_t * p_ble_evt)
{
ble_conn_params_on_ble_evt(p_ble_evt);
ble_nus_on_ble_evt(&m_nus, p_ble_evt);
on_ble_evt(p_ble_evt);
}
/**@brief Function for the S110 SoftDevice initialization.
*
* @details This function initializes the S110 SoftDevice and the BLE event interrupt.
*/
static void ble_stack_init(void)
{
uint32_t err_code;
// Initialize SoftDevice.
SOFTDEVICE_HANDLER_INIT(NRF_CLOCK_LFCLKSRC_XTAL_20_PPM, false);
// Enable BLE stack
ble_enable_params_t ble_enable_params;
memset(&ble_enable_params, 0, sizeof(ble_enable_params));
ble_enable_params.gatts_enable_params.service_changed = IS_SRVC_CHANGED_CHARACT_PRESENT;
err_code = sd_ble_enable(&ble_enable_params);
APP_ERROR_CHECK(err_code);
// Subscribe for BLE events.
err_code = softdevice_ble_evt_handler_set(ble_evt_dispatch);
APP_ERROR_CHECK(err_code);
}
/**@brief Function for configuring the buttons.
*/
static void buttons_init(void)
{
nrf_gpio_cfg_sense_input(WAKEUP_BUTTON_PIN,
BUTTON_PULL,
NRF_GPIO_PIN_SENSE_LOW);
}
/**@brief Function for placing the application in low power state while waiting for events.
*/
static void power_manage(void)
{
uint32_t err_code = sd_app_evt_wait();
APP_ERROR_CHECK(err_code);
}
void uart_putstring(const uint8_t * str)
{
uint32_t err_code;
uint8_t len = strlen((char *) str);
for (uint8_t i = 0; i < len; i++)
{
err_code = app_uart_put(str[i]);
APP_ERROR_CHECK(err_code);
}
}
/**@brief Function for handling UART interrupts.
*
* @details This function will receive a single character from the UART and append it to a string.
* The string will be be sent over BLE when the last character received was a 'new line'
* i.e '\n' (hex 0x0D) or if the string has reached a length of @ref NUS_MAX_DATA_LENGTH.
*/
void uart_evt_callback(app_uart_evt_t * uart_evt)
{
//uint32_t err_code;
switch (uart_evt->evt_type)
{
case APP_UART_DATA:
//Data is ready on the UART
break;
case APP_UART_DATA_READY:
//Data is ready on the UART FIFO
break;
case APP_UART_TX_EMPTY:
//Data has been successfully transmitted on the UART
break;
default:
break;
}
}
/**@brief Function for initializing the UART module.
*/
static void uart_init(void)
{
uint32_t err_code;
APP_UART_FIFO_INIT(&comm_params,
RX_BUF_SIZE,
TX_BUF_SIZE,
uart_evt_callback,
UART_IRQ_PRIORITY,
err_code);
APP_ERROR_CHECK(err_code);
}
bool ble_attempt_to_send(uint8_t * data, uint8_t length)
{
uint32_t err_code;
err_code = ble_nus_send_string(&m_nus, data,length);
if(err_code == BLE_ERROR_NO_TX_BUFFERS)
{
/* ble tx buffer full*/
return false;
}
else if (err_code != NRF_ERROR_INVALID_STATE)
{
APP_ERROR_CHECK(err_code);
}
return true;
}
/**@brief Application main function.
*/
int main(void)
{
static uint8_t data_array[BLE_NUS_MAX_DATA_LEN];
static uint8_t index = 0;
uint8_t newbyte;
// Initialize
leds_init();
timers_init();
buttons_init();
uart_init();
uart_putstring((const uint8_t *)"Hello\n");
ble_stack_init();
gap_params_init();
services_init();
advertising_init();
conn_params_init();
sec_params_init();
uart_putstring((const uint8_t *)START_STRING);
advertising_start();
uart_putstring((const uint8_t*)"Start Loop\n");
// Enter main loop
for (;;)
{
/*Stop reading new data if there are no ble buffers available */
if(ble_buffer_available)
{
if(app_uart_get(&newbyte) == NRF_SUCCESS)
{
data_array[index++] = newbyte;
if (index >= (BLE_NUS_MAX_DATA_LEN))
{
ble_buffer_available=ble_attempt_to_send(&data_array[0],index);
if(ble_buffer_available) index=0;
}
}
}
/* Re-transmission if ble_buffer_available was set to false*/
if(tx_complete)
{
tx_complete=false;
ble_buffer_available=ble_attempt_to_send(&data_array[0],index);
if(ble_buffer_available) index =0;
}
power_manage();
}
}
/**
* @}
*/

10
note.md Normal file
View File

@ -0,0 +1,10 @@
# Flashing nrf firmaware on OSX 10.8
```
sudo mount -u -w -o sync /Volumes/MBED
srec_cat /Users/pg/code/blenano/s110_nrf51822_7.3.0_softdevice.hex -intel _build/ble_app_uart_s110_xxaa.hex -intel -o _build/uart.hex -intel --line-length=44
cp -X _build/uart.hex /Volumes/MBED/
sudo rm /Library/Preferences/com.apple.Bluetooth.plist
pkill bluez
```

49
uart_conf.h Normal file
View File

@ -0,0 +1,49 @@
/* Copyright (c) 2013 Nordic Semiconductor. All Rights Reserved.
*
* The information contained herein is property of Nordic Semiconductor ASA.
* Terms and conditions of usage are described in detail in NORDIC
* SEMICONDUCTOR STANDARD SOFTWARE LICENSE AGREEMENT.
*
* Licensees are granted free, non-transferable use of the information. NO
* WARRANTY of ANY KIND is provided. This heading must NOT be removed from
* the file.
*
*/
/**@file
*
* @defgroup app_uart UART module
* @{
* @ingroup app_common
*
* @brief UART module interface.
*/
#ifndef UART_CONF_H__
#define UART_CONF_H__
#include "boards.h"
#include "app_uart.h"
#define UART_IRQ_PRIORITY APP_IRQ_PRIORITY_LOW
#define RX_BUF_SIZE 32 /**< Size of desired RX buffer, must be a power of 2 or ZERO (No FIFO). */
#define TX_BUF_SIZE 32 /**< Size of desired TX buffer, must be a power of 2 or ZERO (No FIFO) */
/**
*@breif UART configuration structure
*/
static const app_uart_comm_params_t comm_params =
{
.rx_pin_no = RX_PIN_NUMBER,
.tx_pin_no = TX_PIN_NUMBER,
.rts_pin_no = RTS_PIN_NUMBER,
.cts_pin_no = CTS_PIN_NUMBER,
//Below values are defined in ser_config.h common for application and connectivity
.flow_control = APP_UART_FLOW_CONTROL_ENABLED,
.use_parity = false,
.baud_rate = UART_BAUDRATE_BAUDRATE_Baud9600
};
/** @} */
#endif //UART_CONF_H__