nrf: Remove even more unused files

This commit is contained in:
arturo182 2018-07-08 19:58:36 +02:00
parent 2c63fb2a94
commit eab00ff140
8 changed files with 0 additions and 925 deletions

View File

@ -95,10 +95,7 @@ SRC_NRFX = $(addprefix nrfx/,\
SRC_C += \
mphalport.c \
fatfs_port.c \
fifo.c \
tick.c \
drivers/softpwm.c \
drivers/ticker.c \
drivers/bluetooth/ble_drv.c \
drivers/bluetooth/ble_uart.c \
boards/$(BOARD)/board.c \

View File

@ -1,257 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 Mark Shannon
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "py/mphal.h"
#if MICROPY_PY_MACHINE_SOFT_PWM
#include "stddef.h"
#include "py/runtime.h"
#include "py/gc.h"
#include "hal_timer.h"
#include "hal_gpio.h"
#include "pin.h"
#include "ticker.h"
#define CYCLES_PER_MICROSECONDS 16
#define MICROSECONDS_PER_TICK 16
#define CYCLES_PER_TICK (CYCLES_PER_MICROSECONDS*MICROSECONDS_PER_TICK)
// This must be an integer multiple of MICROSECONDS_PER_TICK
#define MICROSECONDS_PER_MACRO_TICK 6000
#define MILLISECONDS_PER_MACRO_TICK 6
#define PWM_TICKER_INDEX 2
// Default period of 20ms
#define DEFAULT_PERIOD ((20*1000)/MICROSECONDS_PER_TICK)
typedef struct _pwm_event {
uint16_t time;
uint8_t pin;
uint8_t turn_on;
} pwm_event;
typedef struct _pwm_events {
uint8_t count;
uint16_t period;
uint32_t all_pins;
pwm_event events[1];
} pwm_events;
static const pwm_events OFF_EVENTS = {
.count = 1,
.period = DEFAULT_PERIOD,
.all_pins = 0,
.events = {
{
.time = 1024,
.pin = 31,
.turn_on = 0
}
}
};
#define active_events MP_STATE_PORT(pwm_active_events)
#define pending_events MP_STATE_PORT(pwm_pending_events)
void softpwm_init(void) {
active_events = &OFF_EVENTS;
pending_events = NULL;
}
static uint8_t next_event = 0;
static inline int32_t pwm_get_period_ticks(void) {
const pwm_events *tmp = pending_events;
if (tmp == NULL)
tmp = active_events;
return tmp->period;
}
#if 0
void pwm_dump_events(const pwm_events *events) {
printf("Count %d, period %d, all pins %d\r\n", events->count, events->period, events->all_pins);
for (uint32_t i = 0; i < events->count; i++) {
const pwm_event *event = &events->events[i];
printf("Event. pin: %d, duty cycle: %d, turn_on: %d\r\n",
event->pin, event->time, event->turn_on);
}
}
void pwm_dump_state(void) {
while(pending_events);
pwm_dump_events(active_events);
}
#endif
static const pwm_events *swap_pending(const pwm_events *in) {
__disable_irq();
const pwm_events *result = pending_events;
pending_events = in;
__enable_irq();
return result;
}
static pwm_events *copy_events(const pwm_events *orig, uint32_t count) {
pwm_events *events = m_malloc(sizeof(pwm_events) + (count-1)*sizeof(pwm_event));
events->count = count;
uint32_t copy = count > orig->count ? orig->count : count;
for (uint32_t i = 0; i < copy; i++) {
events->events[i] = orig->events[i];
}
return events;
}
static int find_pin_in_events(const pwm_events *events, uint32_t pin) {
for (int i = 0; i < events->count; i++) {
if (events->events[i].pin == pin)
return i;
}
return -1;
}
static void sort_events(pwm_events *events) {
// Insertion sort
for (int32_t i = 1; i < events->count; i++) {
pwm_event x = events->events[i];
int32_t j;
for (j = i - 1; j >= 0 && events->events[j].time > x.time; j--) {
events->events[j+1] = events->events[j];
}
events->events[j+1] = x;
}
}
int32_t pwm_callback(void) {
int32_t tdiff;
const pwm_events *events = active_events;
const pwm_event *event = &events->events[next_event];
int32_t tnow = (event->time*events->period)>>10;
do {
if (event->turn_on) {
hal_gpio_pin_set(0, event->pin);
next_event++;
} else {
hal_gpio_out_clear(0, events->all_pins);
next_event = 0;
tnow = 0;
if (pending_events) {
events = pending_events;
active_events = events;
pending_events = NULL;
}
}
event = &events->events[next_event];
tdiff = ((event->time*events->period)>>10) - tnow;
} while (tdiff == 0);
return tdiff;
}
void pwm_start(void) {
set_ticker_callback(PWM_TICKER_INDEX, pwm_callback, 120);
}
void pwm_stop(void) {
clear_ticker_callback(PWM_TICKER_INDEX);
}
static void pwm_set_period_ticks(int32_t ticks) {
const pwm_events *old_events = swap_pending(NULL);
if (old_events == NULL) {
old_events = active_events;
}
pwm_events *events = copy_events(old_events, old_events->count);
events->all_pins = old_events->all_pins;
events->period = ticks;
pending_events = events;
}
int pwm_set_period_us(int32_t us) {
if ((us < 256) ||
(us > 1000000)) {
return -1;
}
pwm_set_period_ticks(us/MICROSECONDS_PER_TICK);
return 0;
}
int32_t pwm_get_period_us(void) {
return pwm_get_period_ticks()*MICROSECONDS_PER_TICK;
}
void pwm_set_duty_cycle(int32_t pin, uint32_t value) {
if (value >= (1<<10)) {
value = (1<<10)-1;
}
uint32_t turn_on_time = 1024-value;
const pwm_events *old_events = swap_pending(NULL);
if (old_events == NULL) {
old_events = active_events;
}
if (((1<<pin)&old_events->all_pins) == 0) {
hal_gpio_cfg_pin(0, pin, HAL_GPIO_MODE_OUTPUT, HAL_GPIO_PULL_DISABLED);
}
int ev = find_pin_in_events(old_events, pin);
pwm_events *events;
if (ev < 0 && value == 0) {
return;
} else if (ev < 0) {
events = copy_events(old_events, old_events->count+1);
events->all_pins = old_events->all_pins | (1<<pin);
events->events[old_events->count].time = turn_on_time;
events->events[old_events->count].pin = pin;
events->events[old_events->count].turn_on = 1;
} else if (value == 0) {
events = copy_events(old_events, old_events->count-1);
events->all_pins = old_events->all_pins & ~(1<<pin);
if (ev < old_events->count-1) {
events->events[ev] = old_events->events[old_events->count-1];
}
} else {
events = copy_events(old_events, old_events->count);
events->all_pins = old_events->all_pins;
events->events[ev].time = turn_on_time;
}
events->period = old_events->period;
sort_events(events);
pending_events = events;
return;
}
void pwm_release(int32_t pin) {
pwm_set_duty_cycle(pin, 0);
const pwm_events *ev = active_events;
int i = find_pin_in_events(ev, pin);
if (i < 0)
return;
// If i >= 0 it means that `ev` is in RAM, so it safe to discard the const qualifier
((pwm_events *)ev)->events[i].pin = 31;
hal_gpio_pin_clear(0, pin);
}
#endif // MICROPY_PY_MACHINE_SOFT_PWM

View File

@ -1,13 +0,0 @@
#ifndef __MICROPY_INCLUDED_LIB_PWM_H__
#define __MICROPY_INCLUDED_LIB_PWM_H__
void softpwm_init(void);
void pwm_start(void);
void pwm_stop(void);
int pwm_set_period_us(int32_t us);
int32_t pwm_get_period_us(void);
void pwm_set_duty_cycle(int32_t pin, int32_t value);
void pwm_release(int32_t pin);
#endif // __MICROPY_INCLUDED_LIB_PWM_H__

View File

@ -1,162 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 Mark Shannon
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "py/mphal.h"
#if MICROPY_PY_MACHINE_SOFT_PWM
#include "ticker.h"
#include "hal_irq.h"
#define FastTicker NRF_TIMER1
#define FastTicker_IRQn TIMER1_IRQn
#define FastTicker_IRQHandler TIMER1_IRQHandler
#define SlowTicker_IRQn SWI0_IRQn
#define SlowTicker_IRQHandler SWI0_IRQHandler
// Ticker callback function called every MACRO_TICK
static volatile callback_ptr slow_ticker;
void ticker_init(callback_ptr slow_ticker_callback) {
slow_ticker = slow_ticker_callback;
NRF_TIMER_Type *ticker = FastTicker;
#ifdef NRF51
ticker->POWER = 1;
#endif
__NOP();
ticker_stop();
ticker->TASKS_CLEAR = 1;
ticker->CC[3] = MICROSECONDS_PER_MACRO_TICK;
ticker->MODE = TIMER_MODE_MODE_Timer;
ticker->BITMODE = TIMER_BITMODE_BITMODE_24Bit << TIMER_BITMODE_BITMODE_Pos;
ticker->PRESCALER = 4; // 1 tick == 1 microsecond
ticker->INTENSET = TIMER_INTENSET_COMPARE3_Msk;
ticker->SHORTS = 0;
#ifdef NRF51
hal_irq_priority(FastTicker_IRQn, 1);
#else
hal_irq_priority(FastTicker_IRQn, 2);
#endif
hal_irq_priority(SlowTicker_IRQn, 3);
hal_irq_priority(SlowTicker_IRQn, 3);
hal_irq_enable(SlowTicker_IRQn);
}
/* Start and stop timer 1 including workarounds for Anomaly 73 for Timer
* http://www.nordicsemi.com/eng/content/download/29490/494569/file/nRF51822-PAN%20v3.0.pdf
*/
void ticker_start(void) {
hal_irq_enable(FastTicker_IRQn);
#ifdef NRF51
*(uint32_t *)0x40009C0C = 1; // for Timer 1
#endif
FastTicker->TASKS_START = 1;
}
void ticker_stop(void) {
hal_irq_disable(FastTicker_IRQn);
FastTicker->TASKS_STOP = 1;
#ifdef NRF51
*(uint32_t *)0x40009C0C = 0; // for Timer 1
#endif
}
int32_t noop(void) {
return -1;
}
volatile uint32_t ticks;
static ticker_callback_ptr callbacks[3] = { noop, noop, noop };
void FastTicker_IRQHandler(void) {
NRF_TIMER_Type *ticker = FastTicker;
ticker_callback_ptr *call = callbacks;
if (ticker->EVENTS_COMPARE[0]) {
ticker->EVENTS_COMPARE[0] = 0;
ticker->CC[0] += call[0]()*MICROSECONDS_PER_TICK;
}
if (ticker->EVENTS_COMPARE[1]) {
ticker->EVENTS_COMPARE[1] = 0;
ticker->CC[1] += call[1]()*MICROSECONDS_PER_TICK;
}
if (ticker->EVENTS_COMPARE[2]) {
ticker->EVENTS_COMPARE[2] = 0;
ticker->CC[2] += call[2]()*MICROSECONDS_PER_TICK;
}
if (ticker->EVENTS_COMPARE[3]) {
ticker->EVENTS_COMPARE[3] = 0;
ticker->CC[3] += MICROSECONDS_PER_MACRO_TICK;
ticks += MILLISECONDS_PER_MACRO_TICK;
hal_irq_pending(SlowTicker_IRQn);
}
}
static const uint32_t masks[3] = {
TIMER_INTENCLR_COMPARE0_Msk,
TIMER_INTENCLR_COMPARE1_Msk,
TIMER_INTENCLR_COMPARE2_Msk,
};
int set_ticker_callback(uint32_t index, ticker_callback_ptr func, int32_t initial_delay_us) {
if (index > 3)
return -1;
NRF_TIMER_Type *ticker = FastTicker;
callbacks[index] = noop;
ticker->INTENCLR = masks[index];
ticker->TASKS_CAPTURE[index] = 1;
uint32_t t = FastTicker->CC[index];
// Need to make sure that set tick is aligned to lastest tick
// Use CC[3] as a reference, as that is always up-to-date.
int32_t cc3 = FastTicker->CC[3];
int32_t delta = t+initial_delay_us-cc3;
delta = (delta/MICROSECONDS_PER_TICK+1)*MICROSECONDS_PER_TICK;
callbacks[index] = func;
ticker->INTENSET = masks[index];
FastTicker->CC[index] = cc3 + delta;
return 0;
}
int clear_ticker_callback(uint32_t index) {
if (index > 3)
return -1;
FastTicker->INTENCLR = masks[index];
callbacks[index] = noop;
return 0;
}
void SlowTicker_IRQHandler(void)
{
slow_ticker();
}
#endif // MICROPY_PY_MACHINE_SOFT_PWM

View File

@ -1,30 +0,0 @@
#ifndef __MICROPY_INCLUDED_LIB_TICKER_H__
#define __MICROPY_INCLUDED_LIB_TICKER_H__
/*************************************
* 62.5kHz (16µs cycle time) ticker.
************************************/
#include "nrf.h"
typedef void (*callback_ptr)(void);
typedef int32_t (*ticker_callback_ptr)(void);
void ticker_init(callback_ptr slow_ticker_callback);
void ticker_start(void);
void ticker_stop(void);
int clear_ticker_callback(uint32_t index);
int set_ticker_callback(uint32_t index, ticker_callback_ptr func, int32_t initial_delay_us);
int set_low_priority_callback(callback_ptr callback, int id);
#define CYCLES_PER_MICROSECONDS 16
#define MICROSECONDS_PER_TICK 16
#define CYCLES_PER_TICK (CYCLES_PER_MICROSECONDS*MICROSECONDS_PER_TICK)
// This must be an integer multiple of MICROSECONDS_PER_TICK
#define MICROSECONDS_PER_MACRO_TICK 6000
#define MILLISECONDS_PER_MACRO_TICK 6
#endif // __MICROPY_INCLUDED_LIB_TICKER_H__

View File

@ -1,267 +0,0 @@
/******************************************************************************/
/*!
@file fifo.c
@author hathach (tinyusb.org)
@section DESCRIPTION
Light-weight FIFO buffer with basic mutex support
@section LICENSE
Software License Agreement (BSD License)
Copyright (c) 2012, K. Townsend (microBuilder.eu)
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
3. Neither the name of the copyright holders nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/******************************************************************************/
#include "fifo.h"
/*------------------------------------------------------------------*/
/*
*------------------------------------------------------------------*/
#if CFG_FIFO_MUTEX
#define mutex_lock_if_needed(_ff) if (_ff->mutex) fifo_mutex_lock(_ff->mutex)
#define mutex_unlock_if_needed(_ff) if (_ff->mutex) fifo_mutex_unlock(_ff->mutex)
#else
#define mutex_lock_if_needed(_ff)
#define mutex_unlock_if_needed(_ff)
#endif
static inline uint16_t min16_of(uint16_t x, uint16_t y)
{
return (x < y) ? x : y;
}
static inline bool fifo_initalized(fifo_t* f)
{
return (f->buffer != NULL) && (f->depth > 0) && (f->item_size > 0);
}
/******************************************************************************/
/*!
@brief Read one byte out of the RX buffer.
This function will return the byte located at the array index of the
read pointer, and then increment the read pointer index. If the read
pointer exceeds the maximum buffer size, it will roll over to zero.
@param[in] f
Pointer to the FIFO buffer to manipulate
@param[in] p_buffer
Pointer to the place holder for data read from the buffer
@returns TRUE if the queue is not empty
*/
/******************************************************************************/
bool fifo_read(fifo_t* f, void * p_buffer)
{
if( !fifo_initalized(f) ) return false;
if( fifo_empty(f) ) return false;
mutex_lock_if_needed(f);
memcpy(p_buffer,
f->buffer + (f->rd_idx * f->item_size),
f->item_size);
f->rd_idx = (f->rd_idx + 1) % f->depth;
f->count--;
mutex_unlock_if_needed(f);
return true;
}
/******************************************************************************/
/*!
@brief This function will read n elements into the array index specified by
the write pointer and increment the write index. If the write index
exceeds the max buffer size, then it will roll over to zero.
@param[in] f
Pointer to the FIFO buffer to manipulate
@param[in] p_data
The pointer to data location
@param[in] count
Number of element that buffer can afford
@returns number of bytes read from the FIFO
*/
/******************************************************************************/
uint16_t fifo_read_n (fifo_t* f, void * p_buffer, uint16_t count)
{
if( !fifo_initalized(f) ) return false;
if( fifo_empty(f) ) return false;
/* Limit up to fifo's count */
count = min16_of(count, f->count);
if( count == 0 ) return 0;
mutex_lock_if_needed(f);
/* Could copy up to 2 portions marked as 'x' if queue is wrapped around
* case 1: ....RxxxxW.......
* case 2: xxxxxW....Rxxxxxx
*/
// uint16_t index2upper = min16_of(count, f->count-f->rd_idx);
uint8_t* p_buf = (uint8_t*) p_buffer;
uint16_t len = 0;
while( (len < count) && fifo_read(f, p_buf) )
{
len++;
p_buf += f->item_size;
}
mutex_unlock_if_needed(f);
return len;
}
/******************************************************************************/
/*!
@brief Reads one item without removing it from the FIFO
@param[in] f
Pointer to the FIFO buffer to manipulate
@param[in] position
Position to read from in the FIFO buffer
@param[in] p_buffer
Pointer to the place holder for data read from the buffer
@returns TRUE if the queue is not empty
*/
/******************************************************************************/
bool fifo_peek_at(fifo_t* f, uint16_t position, void * p_buffer)
{
if ( !fifo_initalized(f) ) return false;
if ( position >= f->count ) return false;
// rd_idx is position=0
uint16_t index = (f->rd_idx + position) % f->depth;
memcpy(p_buffer,
f->buffer + (index * f->item_size),
f->item_size);
return true;
}
/******************************************************************************/
/*!
@brief Write one element into the RX buffer.
This function will write one element into the array index specified by
the write pointer and increment the write index. If the write index
exceeds the max buffer size, then it will roll over to zero.
@param[in] f
Pointer to the FIFO buffer to manipulate
@param[in] p_data
The byte to add to the FIFO
@returns TRUE if the data was written to the FIFO (overwrittable
FIFO will always return TRUE)
*/
/******************************************************************************/
bool fifo_write(fifo_t* f, void const * p_data)
{
if ( !fifo_initalized(f) ) return false;
if ( fifo_full(f) && !f->overwritable ) return false;
mutex_lock_if_needed(f);
memcpy( f->buffer + (f->wr_idx * f->item_size),
p_data,
f->item_size);
f->wr_idx = (f->wr_idx + 1) % f->depth;
if (fifo_full(f))
{
f->rd_idx = f->wr_idx; // keep the full state (rd == wr && len = size)
}
else
{
f->count++;
}
mutex_unlock_if_needed(f);
return true;
}
/******************************************************************************/
/*!
@brief This function will write n elements into the array index specified by
the write pointer and increment the write index. If the write index
exceeds the max buffer size, then it will roll over to zero.
@param[in] f
Pointer to the FIFO buffer to manipulate
@param[in] p_data
The pointer to data to add to the FIFO
@param[in] count
Number of element
@return Number of written elements
*/
/******************************************************************************/
uint16_t fifo_write_n(fifo_t* f, void const * p_data, uint16_t count)
{
if ( count == 0 ) return 0;
uint8_t* p_buf = (uint8_t*) p_data;
uint16_t len = 0;
while( (len < count) && fifo_write(f, p_buf) )
{
len++;
p_buf += f->item_size;
}
return len;
}
/******************************************************************************/
/*!
@brief Clear the fifo read and write pointers and set length to zero
@param[in] f
Pointer to the FIFO buffer to manipulate
*/
/******************************************************************************/
void fifo_clear(fifo_t *f)
{
mutex_lock_if_needed(f);
f->rd_idx = f->wr_idx = f->count = 0;
mutex_unlock_if_needed(f);
}

View File

@ -1,148 +0,0 @@
/******************************************************************************/
/*!
@file fifo.h
@author hathach (tinyusb.org)
@section LICENSE
Software License Agreement (BSD License)
Copyright (c) 2012, K. Townsend (microBuilder.eu)
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
3. Neither the name of the copyright holders nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/******************************************************************************/
#ifndef __FIFO_H__
#define __FIFO_H__
#define CFG_FIFO_MUTEX 1
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#ifdef __cplusplus
extern "C" {
#endif
#if CFG_FIFO_MUTEX
#include "nrf.h"
#define fifo_mutex_t IRQn_Type
#define fifo_mutex_lock(m) NVIC_DisableIRQ(m)
#define fifo_mutex_unlock(m) NVIC_EnableIRQ(m)
/* Internal use only */
#define _mutex_declare(m) .mutex = m
#else
#define _mutex_declare(m)
#endif
typedef struct _fifo_t
{
uint8_t* const buffer ; ///< buffer pointer
uint16_t const depth ; ///< max items
uint16_t const item_size ; ///< size of each item
volatile uint16_t count ; ///< number of items in queue
volatile uint16_t wr_idx ; ///< write pointer
volatile uint16_t rd_idx ; ///< read pointer
bool const overwritable;
#if CFG_FIFO_MUTEX
fifo_mutex_t const mutex;
#endif
} fifo_t;
/**
* Macro to declare a fifo
* @param name : name of the fifo
* @param depth : max number of items
* @param type : data type of item
* @param overwritable : whether fifo should be overwrite when full
* @param mutex : mutex object
*/
#define FIFO_DEF(_name, _depth, _type, _overwritable, _mutex)\
_type _name##_buffer[_depth];\
fifo_t _name##_fifo = {\
.buffer = (uint8_t*) _name##_buffer,\
.depth = _depth,\
.item_size = sizeof(_type),\
.overwritable = _overwritable,\
_mutex_declare(_mutex)\
};\
fifo_t* _name = &_name##_fifo
void fifo_clear (fifo_t *f);
bool fifo_write (fifo_t* f, void const * p_data);
uint16_t fifo_write_n (fifo_t* f, void const * p_data, uint16_t count);
bool fifo_read (fifo_t* f, void * p_buffer);
uint16_t fifo_read_n (fifo_t* f, void * p_buffer, uint16_t count);
bool fifo_peek_at (fifo_t* f, uint16_t position, void * p_buffer);
static inline bool fifo_peek(fifo_t* f, void * p_buffer)
{
return fifo_peek_at(f, 0, p_buffer);
}
static inline bool fifo_empty(fifo_t* f)
{
return (f->count == 0);
}
static inline bool fifo_full(fifo_t* f)
{
return (f->count == f->depth);
}
static inline uint16_t fifo_count(fifo_t* f)
{
return f->count;
}
static inline uint16_t fifo_remaining(fifo_t* f)
{
return f->depth - f->count;
}
static inline uint16_t fifo_depth(fifo_t* f)
{
return f->depth;
}
#ifdef __cplusplus
}
#endif
#endif

View File

@ -1,45 +0,0 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2013, 2014 Damien P. George
* Copyright (c) 2016 Glenn Ruben Bakke
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef GC_COLLECT_H__
#define GC_COLLECT_H__
extern uint32_t _etext;
extern uint32_t _sidata;
extern uint32_t _ram_start;
extern uint32_t _sdata;
extern uint32_t _edata;
extern uint32_t _sbss;
extern uint32_t _ebss;
extern uint32_t _heap_start;
extern uint32_t _heap_end;
extern uint32_t _estack;
extern uint32_t _ram_end;
void gc_collect(void);
#endif