├── BLESerial.cpp ├── BLESerial.h ├── Makefile ├── PPI.cpp ├── PPI.h ├── README.md ├── Timer.cpp ├── Timer.h ├── communication.cpp ├── communication.h ├── firmware.h ├── firmware.ino ├── nRF_SDK ├── nrf_gpiote.h ├── nrf_ppi.h └── nrf_timer.h ├── photosensors.cpp ├── photosensors.h ├── pinout.h ├── pulse.cpp ├── pulse.h ├── reception └── reception.py ├── ts4231.cpp └── ts4231.h /BLESerial.cpp: -------------------------------------------------------------------------------- 1 | #include "BLESerial.h" 2 | 3 | // #define BLE_SERIAL_DEBUG 4 | 5 | BLESerial* BLESerial::_instance = NULL; 6 | 7 | BLESerial::BLESerial(unsigned char req, unsigned char rdy, unsigned char rst) : 8 | BLEPeripheral(req, rdy, rst) 9 | { 10 | this->_txCount = 0; 11 | this->_rxHead = this->_rxTail = 0; 12 | this->_flushed = 0; 13 | BLESerial::_instance = this; 14 | 15 | addAttribute(this->_uartService); 16 | addAttribute(this->_uartNameDescriptor); 17 | setAdvertisedServiceUuid(this->_uartService.uuid()); 18 | addAttribute(this->_rxCharacteristic); 19 | addAttribute(this->_rxNameDescriptor); 20 | this->_rxCharacteristic.setEventHandler(BLEWritten, BLESerial::_received); 21 | addAttribute(this->_txCharacteristic); 22 | addAttribute(this->_txNameDescriptor); 23 | } 24 | 25 | void BLESerial::begin(...) { 26 | BLEPeripheral::begin(); 27 | #ifdef BLE_SERIAL_DEBUG 28 | Serial.println(F("BLESerial::begin()")); 29 | #endif 30 | } 31 | 32 | void BLESerial::poll() { 33 | if (millis() < this->_flushed + 100) { 34 | BLEPeripheral::poll(); 35 | } else { 36 | flush(); 37 | } 38 | } 39 | 40 | void BLESerial::end() { 41 | this->_rxCharacteristic.setEventHandler(BLEWritten, NULL); 42 | this->_rxHead = this->_rxTail = 0; 43 | flush(); 44 | BLEPeripheral::disconnect(); 45 | } 46 | 47 | int BLESerial::available(void) { 48 | BLEPeripheral::poll(); 49 | int retval = (this->_rxHead - this->_rxTail + sizeof(this->_rxBuffer)) % sizeof(this->_rxBuffer); 50 | #ifdef BLE_SERIAL_DEBUG 51 | Serial.print(F("BLESerial::available() = ")); 52 | Serial.println(retval); 53 | #endif 54 | return retval; 55 | } 56 | 57 | int BLESerial::peek(void) { 58 | BLEPeripheral::poll(); 59 | if (this->_rxTail == this->_rxHead) return -1; 60 | uint8_t byte = this->_rxBuffer[this->_rxTail]; 61 | #ifdef BLE_SERIAL_DEBUG 62 | Serial.print(F("BLESerial::peek() = ")); 63 | Serial.print((char) byte); 64 | Serial.print(F(" 0x")); 65 | Serial.println(byte, HEX); 66 | #endif 67 | return byte; 68 | } 69 | 70 | int BLESerial::read(void) { 71 | BLEPeripheral::poll(); 72 | if (this->_rxTail == this->_rxHead) return -1; 73 | this->_rxTail = (this->_rxTail + 1) % sizeof(this->_rxBuffer); 74 | uint8_t byte = this->_rxBuffer[this->_rxTail]; 75 | #ifdef BLE_SERIAL_DEBUG 76 | Serial.print(F("BLESerial::read() = ")); 77 | Serial.print((char) byte); 78 | Serial.print(F(" 0x")); 79 | Serial.println(byte, HEX); 80 | #endif 81 | return byte; 82 | } 83 | 84 | void BLESerial::flush(void) { 85 | if (this->_txCount == 0) return; 86 | this->_txCharacteristic.setValue(this->_txBuffer, this->_txCount); 87 | this->_flushed = millis(); 88 | this->_txCount = 0; 89 | BLEPeripheral::poll(); 90 | #ifdef BLE_SERIAL_DEBUG 91 | Serial.println(F("BLESerial::flush()")); 92 | #endif 93 | } 94 | 95 | size_t BLESerial::write(uint8_t byte) { 96 | BLEPeripheral::poll(); 97 | if (this->_txCharacteristic.subscribed() == false) return 0; 98 | this->_txBuffer[this->_txCount++] = byte; 99 | if (this->_txCount == sizeof(this->_txBuffer)) flush(); 100 | #ifdef BLE_SERIAL_DEBUG 101 | Serial.print(F("BLESerial::write(")); 102 | Serial.print((char) byte); 103 | Serial.print(F(" 0x")); 104 | Serial.print(byte, HEX); 105 | Serial.println(F(") = 1")); 106 | #endif 107 | return 1; 108 | } 109 | 110 | BLESerial::operator bool() { 111 | bool retval = BLEPeripheral::connected(); 112 | #ifdef BLE_SERIAL_DEBUG 113 | Serial.print(F("BLESerial::operator bool() = ")); 114 | Serial.println(retval); 115 | #endif 116 | return retval; 117 | } 118 | 119 | void BLESerial::_received(const uint8_t* data, size_t size) { 120 | for (int i = 0; i < size; i++) { 121 | this->_rxHead = (this->_rxHead + 1) % sizeof(this->_rxBuffer); 122 | this->_rxBuffer[this->_rxHead] = data[i]; 123 | } 124 | #ifdef BLE_SERIAL_DEBUG 125 | Serial.print(F("BLESerial::received(")); 126 | for (int i = 0; i < size; i++) Serial.print((char) data[i]); 127 | Serial.println(F(")")); 128 | #endif 129 | } 130 | 131 | void BLESerial::_received(BLECentral& /*central*/, BLECharacteristic& rxCharacteristic) { 132 | BLESerial::_instance->_received(rxCharacteristic.value(), rxCharacteristic.valueLength()); 133 | } 134 | -------------------------------------------------------------------------------- /BLESerial.h: -------------------------------------------------------------------------------- 1 | #ifndef _BLE_SERIAL_H_ 2 | #define _BLE_SERIAL_H_ 3 | 4 | #include 5 | #include 6 | 7 | 8 | //#warning "THIS IS A CUSTOM IMPLEMENTATION" 9 | 10 | class BLESerial : public BLEPeripheral, public Stream 11 | { 12 | public: 13 | BLESerial(unsigned char req=0, unsigned char rdy=0, unsigned char rst=0); 14 | 15 | void begin(...); 16 | void poll(); 17 | void end(); 18 | 19 | virtual int available(void); 20 | virtual int peek(void); 21 | virtual int read(void); 22 | virtual void flush(void); 23 | virtual size_t write(uint8_t byte); 24 | using Print::write; 25 | virtual operator bool(); 26 | 27 | private: 28 | unsigned long _flushed; 29 | static BLESerial* _instance; 30 | 31 | size_t _rxHead; 32 | size_t _rxTail; 33 | size_t _rxCount() const; 34 | uint8_t _rxBuffer[BLE_ATTRIBUTE_MAX_VALUE_LENGTH]; 35 | size_t _txCount; 36 | uint8_t _txBuffer[BLE_ATTRIBUTE_MAX_VALUE_LENGTH]; 37 | 38 | BLEService _uartService = BLEService("6E400001-B5A3-F393-E0A9-E50E24DCCA9E"); 39 | BLEDescriptor _uartNameDescriptor = BLEDescriptor("2901", "UART"); 40 | BLECharacteristic _rxCharacteristic = BLECharacteristic("6E400002-B5A3-F393-E0A9-E50E24DCCA9E", BLEWriteWithoutResponse, BLE_ATTRIBUTE_MAX_VALUE_LENGTH); 41 | BLEDescriptor _rxNameDescriptor = BLEDescriptor("2901", "RX - Receive Data (Write)"); 42 | BLECharacteristic _txCharacteristic = BLECharacteristic("6E400003-B5A3-F393-E0A9-E50E24DCCA9E", BLENotify, BLE_ATTRIBUTE_MAX_VALUE_LENGTH); 43 | BLEDescriptor _txNameDescriptor = BLEDescriptor("2901", "TX - Transfer Data (Notify)"); 44 | 45 | void _received(const uint8_t* data, size_t size); 46 | static void _received(BLECentral& /*central*/, BLECharacteristic& rxCharacteristic); 47 | }; 48 | 49 | #endif 50 | -------------------------------------------------------------------------------- /Makefile: -------------------------------------------------------------------------------- 1 | BIN_DIR = /tmp/arduino_build 2 | 3 | ELF = $(BIN_DIR)/*elf 4 | 5 | GDB_SRV = JLinkGDBServer 6 | ARM_GDB = arm-none-eabi-gdb 7 | 8 | ARG = -if swd -speed 1000 -device NRF52832_xxAA 9 | 10 | TERM = gnome-terminal -- 11 | BOARD = sandeepmistry:nRF5:Generic_nRF52832:softdevice=s132 12 | 13 | .PHONY: all upload compile pref_list debug startgdbserver local_startgdbserver \ 14 | stopgdbserver clean clean_cache c l d 15 | 16 | 17 | all: upload 18 | 19 | 20 | # TODO: make install (upload could depend on it too) examples: 21 | # 22 | # Install AVR board support, 1.6.2 23 | # arduino --install-boards "arduino:avr:1.6.2" 24 | # 25 | # Install Bridge and Servo libraries 26 | # arduino --install-library "Bridge:1.0.0,Servo:1.2.0" 27 | 28 | 29 | # Documentation: 30 | # https://github.com/arduino/Arduino/blob/master/build/shared/manpage.adoc 31 | 32 | upload: *.ino *.cpp *.h stopgdbserver clean_cache 33 | arduino --pref build.path=$(BIN_DIR) --preserve-temp-files --board $(BOARD) \ 34 | --upload --verbose-upload --useprogrammer --verbose *.ino 35 | 36 | # optional 37 | compile: *.ino *.cpp *.h clean_cache 38 | arduino --pref build.path=$(BIN_DIR) --preserve-temp-files --board $(BOARD) \ 39 | --verify --verbose *ino 40 | 41 | 42 | # optional 43 | pref_list: 44 | arduino --get-pref 45 | 46 | # TODO: use precise ELF name 47 | debug: $(ELF) startgdbserver 48 | $(ARM_GDB) $(ELF) 49 | 50 | startgdbserver: 51 | @pidof $(GDB_SRV) > /dev/null || { $(TERM) $(GDB_SRV) $(ARG) & sleep 1 ; } 52 | 53 | #optional 54 | local_startgdbserver: 55 | @pidof $(GDB_SRV) > /dev/null || $(GDB_SRV) $(ARG) 56 | 57 | stopgdbserver: 58 | @pidof $(ARM_GDB) > /dev/null && killall $(ARM_GDB) || true 59 | @pidof $(GDB_SRV) > /dev/null && killall $(GDB_SRV) || true 60 | 61 | clean_cache: 62 | rm -rf /tmp/arduino_cache* 63 | 64 | clean: clean_cache 65 | rm -rf $(BIN_DIR) 66 | 67 | ############################################################################### 68 | # Lazy aliases: 69 | 70 | c: compile 71 | 72 | l: local_startgdbserver 73 | 74 | d: debug 75 | 76 | -------------------------------------------------------------------------------- /PPI.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | PPI class for nRF52. 3 | Written by Chiara Ruggeri (chiara@arduino.org) 4 | 5 | Copyright (c) 2016 Arduino. All right reserved. 6 | 7 | This library is free software; you can redistribute it and/or 8 | modify it under the terms of the GNU Lesser General Public 9 | License as published by the Free Software Foundation; either 10 | version 2.1 of the License, or (at your option) any later version. 11 | 12 | This library is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. 15 | See the GNU Lesser General Public License for more details. 16 | 17 | You should have received a copy of the GNU Lesser General Public 18 | License along with this library; if not, write to the Free Software 19 | Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA 20 | 21 | Enjoy! 22 | */ 23 | 24 | 25 | #include "PPI.h" 26 | #include "nRF_SDK/nrf_timer.h" 27 | 28 | const nrf_ppi_channel_t channels[20] = {NRF_PPI_CHANNEL0, NRF_PPI_CHANNEL1, 29 | NRF_PPI_CHANNEL2, NRF_PPI_CHANNEL3, NRF_PPI_CHANNEL4, NRF_PPI_CHANNEL5, 30 | NRF_PPI_CHANNEL6, NRF_PPI_CHANNEL7, NRF_PPI_CHANNEL8, NRF_PPI_CHANNEL9, 31 | NRF_PPI_CHANNEL10, NRF_PPI_CHANNEL11, NRF_PPI_CHANNEL12, NRF_PPI_CHANNEL13, 32 | NRF_PPI_CHANNEL14, NRF_PPI_CHANNEL15, NRF_PPI_CHANNEL16, NRF_PPI_CHANNEL17, 33 | NRF_PPI_CHANNEL18, NRF_PPI_CHANNEL19}; 34 | 35 | const nrf_gpiote_tasks_t gpio_taskNo[] = {NRF_GPIOTE_TASKS_OUT_0, 36 | NRF_GPIOTE_TASKS_OUT_1, NRF_GPIOTE_TASKS_OUT_2, NRF_GPIOTE_TASKS_OUT_3, 37 | NRF_GPIOTE_TASKS_OUT_4, NRF_GPIOTE_TASKS_OUT_5, NRF_GPIOTE_TASKS_OUT_6, 38 | NRF_GPIOTE_TASKS_OUT_7}; 39 | 40 | const nrf_gpiote_events_t gpio_eventNo[] = {NRF_GPIOTE_EVENTS_IN_0, 41 | NRF_GPIOTE_EVENTS_IN_1, NRF_GPIOTE_EVENTS_IN_2, NRF_GPIOTE_EVENTS_IN_3, 42 | NRF_GPIOTE_EVENTS_IN_4, NRF_GPIOTE_EVENTS_IN_5, NRF_GPIOTE_EVENTS_IN_6, 43 | NRF_GPIOTE_EVENTS_IN_7}; 44 | 45 | NRF_TIMER_Type* const nrf_timers[] = { NRF_TIMER0, NRF_TIMER1, NRF_TIMER2, 46 | NRF_TIMER3, NRF_TIMER4 }; 47 | 48 | const nrf_gpiote_polarity_t gpio_polarity[] = { NRF_GPIOTE_POLARITY_LOTOHI, 49 | NRF_GPIOTE_POLARITY_HITOLO, NRF_GPIOTE_POLARITY_TOGGLE }; 50 | 51 | const nrf_timer_task_t capture_tasks[] = { NRF_TIMER_TASK_CAPTURE0, 52 | NRF_TIMER_TASK_CAPTURE1, NRF_TIMER_TASK_CAPTURE2, NRF_TIMER_TASK_CAPTURE3 }; 53 | 54 | //public functions 55 | 56 | PPIClass::PPIClass() { 57 | timerNo = 1; // 0 is used by soft device 58 | configureTimer(3); 59 | configureTimer(4); // TODO CHEEEECK ! 60 | } 61 | 62 | 63 | int PPIClass::setShortcut(event_type event, task_type task, 64 | int forkTimer, task_type forkTask) { 65 | //check if there is still a free channel 66 | if(first_free_channel==20) { 67 | Serial.println("\n !!! WAAARNING !!! first_free_channel==20 !!!"); 68 | return 0; 69 | } 70 | 71 | //enable sensing 72 | nrf_gpiote_event_enable(event_index); 73 | 74 | configureGPIOEvent(event); 75 | 76 | nrf_timer_task_t nrf_task = nrf_timer_task_t(task); 77 | 78 | 79 | static int capture_index = 0; 80 | if (task == TIMER_CAPTURE) { 81 | nrf_task = capture_tasks[capture_index]; 82 | capture_index = (capture_index >= 3)? 0 : capture_index+1; 83 | } 84 | 85 | nrf_ppi_channel_endpoint_setup(channels[first_free_channel], 86 | (uint32_t)nrf_gpiote_event_addr_get(gpio_eventNo[event_index]), 87 | (uint32_t)nrf_timer_task_address_get(nrf_timers[timerNo], nrf_task)); 88 | 89 | uint32_t fep = 0; // fork end point 90 | 91 | if (forkTimer >= 0 || forkTask != TIMER_NONE) { 92 | 93 | nrf_timer_task_t nrf_fork = (forkTask==TIMER_NONE) 94 | ? nrf_task 95 | : nrf_timer_task_t(forkTask); 96 | 97 | if (forkTimer < 0) { 98 | forkTimer = timerNo; 99 | } 100 | 101 | fep = (uint32_t)nrf_timer_task_address_get(nrf_timers[forkTimer], nrf_fork); 102 | } 103 | 104 | // always configure forks but if not necessary, use 0 as fork end point. 105 | nrf_ppi_fork_endpoint_setup(channels[first_free_channel], fep); 106 | 107 | nrf_ppi_channel_enable(channels[first_free_channel]); 108 | 109 | first_free_channel++; 110 | return (first_free_channel-1); 111 | } 112 | 113 | 114 | void PPIClass::setInputPin(uint32_t pin){ 115 | inputPin=pin; 116 | } 117 | 118 | void PPIClass::setTimer(int _timerNo) { 119 | timerNo = _timerNo; 120 | } 121 | 122 | 123 | //private function 124 | 125 | //functions to configure events 126 | void PPIClass::configureTimer(int _timerNo){ // TODO: CHECK WITH INTERRUPT LIB! 127 | nrf_timer_mode_set(nrf_timers[_timerNo], NRF_TIMER_MODE_TIMER); 128 | nrf_timer_bit_width_set(nrf_timers[_timerNo], NRF_TIMER_BIT_WIDTH_32); 129 | nrf_timer_frequency_set(nrf_timers[_timerNo], NRF_TIMER_FREQ_16MHz); 130 | } 131 | 132 | void PPIClass::configureGPIOEvent(event_type event){ 133 | //if user use more than the allowed number of gpio, overwrite previous configuration 134 | if(gpiote_config_index==8) { 135 | Serial.println("\n !!! WAAARNING !!! gpiote_config_index==8 !!!"); 136 | gpiote_config_index=0; 137 | } 138 | nrf_gpiote_event_configure(gpiote_config_index, inputPin, gpio_polarity[event]); 139 | 140 | event_index=gpiote_config_index; 141 | gpiote_config_index++; 142 | } 143 | 144 | void PPIClass::resetChannels(){ 145 | first_free_channel = 0; 146 | gpiote_config_index = 0; 147 | } 148 | 149 | 150 | PPIClass PPI; 151 | 152 | -------------------------------------------------------------------------------- /PPI.h: -------------------------------------------------------------------------------- 1 | /* 2 | PPI class for nRF52. 3 | Written by Chiara Ruggeri (chiara@arduino.org) 4 | 5 | Copyright (c) 2016 Arduino. All right reserved. 6 | 7 | This library is free software; you can redistribute it and/or 8 | modify it under the terms of the GNU Lesser General Public 9 | License as published by the Free Software Foundation; either 10 | version 2.1 of the License, or (at your option) any later version. 11 | 12 | This library is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. 15 | See the GNU Lesser General Public License for more details. 16 | 17 | You should have received a copy of the GNU Lesser General Public 18 | License along with this library; if not, write to the Free Software 19 | Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA 20 | 21 | Enjoy! 22 | */ 23 | 24 | 25 | #ifndef PPI_h 26 | #define PPI_h 27 | 28 | #include "Arduino.h" 29 | #include "nRF_SDK/nrf_ppi.h" 30 | #include "nRF_SDK/nrf_timer.h" 31 | #include "nRF_SDK/nrf_gpiote.h" 32 | 33 | 34 | //enumerate events and tasks 35 | typedef enum{ 36 | PIN_HIGH = 0, 37 | PIN_LOW = 1, 38 | PIN_CHANGE = 2, 39 | }event_type; 40 | 41 | typedef enum{ 42 | TIMER_START = NRF_TIMER_TASK_START, 43 | TIMER_STOP = NRF_TIMER_TASK_STOP, 44 | TIMER_CLEAR = NRF_TIMER_TASK_CLEAR, 45 | TIMER_CAPTURE, 46 | TIMER_NONE 47 | }task_type; 48 | 49 | class PPIClass{ 50 | 51 | public: 52 | 53 | PPIClass(); 54 | 55 | /** 56 | * @brief 57 | * Name: 58 | * setShortcut 59 | * Description: 60 | * The function allows to make an action when a given event occurs without 61 | * involving MCU. 62 | * Arguments: 63 | * -event: event to which bind the related action. 64 | * -task: action to be taken when the event occurs. 65 | * -forkTimer: optional secondary timer as for action to be taken 66 | * -forkTask: optional secondary action to be taken when the event occurs. 67 | */ 68 | int setShortcut(event_type event, task_type task, 69 | int forkTimer = -1, task_type forkTask = TIMER_NONE); 70 | 71 | 72 | /** 73 | * @brief 74 | * Name: 75 | * setInputPin 76 | * Description: 77 | * Select the pin that will be taken into account in the next 78 | * event -> action interaction. 79 | * Argument: 80 | * pin: pin's number. 81 | */ 82 | void setInputPin(uint32_t pin); 83 | 84 | 85 | /** 86 | * @brief 87 | * Name: 88 | * setTimer 89 | * Description: 90 | * Set timer number for the object 91 | * Argument: 92 | * _timerNo: the number of the timer 93 | */ 94 | void setTimer(int _timerNo); 95 | 96 | 97 | /** 98 | * @brief 99 | * Name: 100 | * resetChannels 101 | * Description: 102 | * Reset PPI channels 103 | */ 104 | void resetChannels(); 105 | 106 | private: 107 | 108 | uint8_t timerNo; 109 | 110 | uint8_t first_free_channel; 111 | uint8_t gpiote_config_index; 112 | uint8_t event_index; 113 | 114 | uint32_t inputPin; 115 | 116 | void configureTimer(int timerNo); 117 | void configureGPIOEvent(event_type event); 118 | 119 | }; 120 | 121 | extern PPIClass PPI; 122 | 123 | #endif //PPI_h 124 | 125 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Firmware 2 | 3 | This project is about a miniaturization of the Vive Tracker by HTC. 4 | It allows sub-millimetric 3d positioning, and embeds a 9DoF IMU with sensor 5 | fusion. This project is open source, all the materials can be found online: 6 | 7 | https://hivetracker.github.io 8 | 9 | This repository contains the Arduino code to program it, more explanations to 10 | use it are below: 11 | 12 | 13 | ## Install 14 | 15 | The processor used in this project is not Arduino compatible by default but 16 | the following steps explain how to do it anyway. 17 | 18 | 1) Download the Arduino IDE: 19 | 20 | https://www.arduino.cc/en/Main/Software 21 | 22 | 2) Install the nRF52 support - read carefully these instructions (no need to follow the "From git" instructions): 23 | 24 | https://github.com/sandeepmistry/arduino-nRF5#installing 25 | 26 | 3) Install the BLE peripheral library with these instructions: 27 | 28 | https://github.com/sandeepmistry/arduino-BLEPeripheral/#using-the-arduino-ide-library-manager 29 | 30 | 31 | ## Compile 32 | 33 | In the "Tools" menu select: 34 | - "Board->Generic nRF52" 35 | - "Softdevice->S132" (select "None" if you don't use BLE) 36 | - The rest depends on your personal configuration. 37 | 38 | If you prefer command line, you can also do: 39 | 40 | make compile 41 | 42 | ## Program 43 | 44 | ### Probes 45 | 46 | This board doesn't come with a programmer for now but several cheap solutions 47 | exist: 48 | 49 | 1) Adafruit sells J-Link and ST-Link probes: 50 | 51 | https://www.adafruit.com/product/3571 52 | 53 | https://www.adafruit.com/product/2548 54 | 55 | 2) For those with limited budget, these alternatives work too: 56 | 57 | https://www.aliexpress.com/item/1PCS-ST-LINK-Stlink-ST-Link-V2-Mini-STM8-STM32-Simulator-Download-Programmer-Programming-With-Cover/32839270086.html 58 | 59 | https://www.aliexpress.com/item/1PCS-Jlink-for-SWD-Jlink-3-Wire-for-STM32-on-SWD-Debug-New/32746364818.html 60 | 61 | 3) But if you already have a [Teensy](https://www.pjrc.com/teensy/) or a 3.3V 62 | Arduino compatible board with ATmega32U4 (such as 63 | [this one](https://www.aliexpress.com/item/Beetle-USB-ATMEGA32U4-Mini-Development-Board-Module-Leonardo-R3/32710925124.html)), 64 | you can build your own programmer thanks to this repository: 65 | 66 | https://github.com/myelin/arduino-cmsis-dap 67 | 68 | 69 | ### Setup 70 | 71 | The above Install section should be enough in most cases but you might need to 72 | install udev rule on linux: 73 | 74 | https://raw.githubusercontent.com/arduino/OpenOCD/master/contrib/60-openocd.rules 75 | 76 | Finally, in the "Tools" menu select the right SWD probe: 77 | - "Programmer->J-Link" 78 | - "Programmer->ST-Link" 79 | 80 | 81 | ### Upload 82 | 83 | In the Arduino IDE it's the same as usual... 84 | 85 | ...and if you prefer command line, you can also do: 86 | 87 | make # upload is by default 88 | 89 | ## Licence 90 | [GNU General Public License version 3](https://opensource.org/licenses/GPL-3.0) 91 | 92 | 93 | ## Enjoy! 94 | 95 | -------------------------------------------------------------------------------- /Timer.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "nRF_SDK/nrf_timer.h" 3 | #include "Timer.h" 4 | 5 | static void defaultFunc() {}; 6 | static funcPtr_t Timer_callbackPtr; 7 | 8 | 9 | TimerClass::TimerClass(int timer, int channel) { 10 | nrf_timer = nrf_timers[timer]; 11 | cc_channel = nrf_timer_cc_channel_t(channel); 12 | 13 | Timer_callbackPtr = defaultFunc; 14 | Timers[timer] = this; 15 | 16 | // Timer mode with 32bit width 17 | nrf_timer_bit_width_set(nrf_timer, NRF_TIMER_BIT_WIDTH_32); 18 | nrf_timer_mode_set(nrf_timer, NRF_TIMER_MODE_TIMER); 19 | nrf_timer_frequency_set(nrf_timer, NRF_TIMER_FREQ_16MHz); 20 | } 21 | 22 | 23 | void TimerClass::NVIC_set(IRQn_Type IRQn) { 24 | // enable IRQ and avoid clashes with soft device 25 | NVIC_SetPriority(IRQn, 3); 26 | NVIC_ClearPendingIRQ(IRQn); 27 | NVIC_EnableIRQ(IRQn); 28 | } 29 | 30 | 31 | void TimerClass::attachInterrupt(funcPtr_t callback, int microsec) { 32 | // This function will be called when time out interrupt will occur 33 | if (callback) { 34 | Timer_callbackPtr = callback; 35 | } else { 36 | Serial.println("ERROR: callback function pointer is null."); 37 | return; 38 | } 39 | 40 | // Start if not already running (and reset?) 41 | nrf_timer_task_trigger(nrf_timer, NRF_TIMER_TASK_START); 42 | nrf_timer_task_trigger(nrf_timer, NRF_TIMER_TASK_CLEAR); 43 | 44 | // Clear and enable compare interrupt 45 | nrf_timer_int_mask_t chanel_mask = nrf_timer_compare_int_get(cc_channel); 46 | nrf_timer_int_enable(nrf_timer, chanel_mask); 47 | 48 | if (nrf_timer == nrf_timers[1]) NVIC_set(TIMER1_IRQn); 49 | if (nrf_timer == nrf_timers[2]) NVIC_set(TIMER2_IRQn); 50 | if (nrf_timer == nrf_timers[3]) NVIC_set(TIMER3_IRQn); 51 | if (nrf_timer == nrf_timers[4]) NVIC_set(TIMER4_IRQn); 52 | 53 | // Program compare register between 0 & 2**28 (max on 32 bits @16 ticks/us) 54 | if (microsec < 0) microsec = 0; 55 | if (microsec >= 1 << 28) microsec = (1 << 28) - 1; 56 | uint32_t ticks = nrf_timer_us_to_ticks(microsec, NRF_TIMER_FREQ_16MHz); 57 | nrf_timer_cc_write(nrf_timer, cc_channel, ticks); 58 | } 59 | 60 | 61 | // Should be called in the Timer_callbackPtr() function 62 | inline void TimerClass::detachInterrupt() { 63 | // Stop timer 64 | nrf_timer_task_trigger(nrf_timer, NRF_TIMER_TASK_STOP); 65 | 66 | // Disable timer compare interrupt 67 | nrf_timer_int_mask_t chanel_mask = nrf_timer_compare_int_get(cc_channel); 68 | nrf_timer_int_disable(nrf_timer, chanel_mask); 69 | 70 | // Clear event - TODO? 71 | nrf_timer_event_t event = nrf_timer_compare_event_get(chanel_mask); 72 | nrf_timer_event_clear(nrf_timer, event); 73 | } 74 | 75 | 76 | // Timer 0 is used by the soft device but Timer 1, 2, 3 and 4 are available 77 | extern "C" void TIMER1_IRQHandler(void) { 78 | if (Timers[1]) { 79 | Timers[1]->detachInterrupt(); 80 | Timer_callbackPtr(); 81 | } 82 | } 83 | 84 | extern "C" void TIMER2_IRQHandler(void) { 85 | if (Timers[2]) { 86 | Timers[2]->detachInterrupt(); 87 | Timer_callbackPtr(); 88 | } 89 | } 90 | 91 | extern "C" void TIMER3_IRQHandler(void) { 92 | if (Timers[3]) { 93 | Timers[3]->detachInterrupt(); 94 | Timer_callbackPtr(); 95 | } 96 | } 97 | 98 | extern "C" void TIMER4_IRQHandler(void) { 99 | if (Timers[4]) { 100 | Timers[4]->detachInterrupt(); 101 | Timer_callbackPtr(); 102 | } 103 | } 104 | 105 | 106 | NRF_TIMER_Type* nrf_timers[] = {NRF_TIMER0, NRF_TIMER1, NRF_TIMER2, 107 | NRF_TIMER3, NRF_TIMER4}; 108 | 109 | TimerClass* Timers[5] = {0}; 110 | 111 | -------------------------------------------------------------------------------- /Timer.h: -------------------------------------------------------------------------------- 1 | #ifndef _TIMER_H_ 2 | #define _TIMER_H_ 3 | 4 | typedef void (*funcPtr_t)(); 5 | 6 | class TimerClass { 7 | public: 8 | TimerClass(int timer = 1, int channel = 0); 9 | void attachInterrupt(funcPtr_t callback, int microsec); 10 | inline void detachInterrupt(); 11 | private: 12 | NRF_TIMER_Type* nrf_timer; 13 | nrf_timer_cc_channel_t cc_channel; 14 | 15 | void NVIC_set(IRQn_Type IRQn); 16 | }; 17 | 18 | extern NRF_TIMER_Type* nrf_timers[5]; 19 | extern TimerClass* Timers[5]; 20 | 21 | #endif // _TIMER_H_ 22 | 23 | -------------------------------------------------------------------------------- /communication.cpp: -------------------------------------------------------------------------------- 1 | #include // BLEPeripheral depends on SPI 2 | #include 3 | #include "BLESerial.h" 4 | 5 | #include "pulse.h" 6 | #include "pinout.h" // important to keep it last for the undefs to work 7 | #include "communication.h" 8 | #include "firmware.h" 9 | 10 | byte message[10]; 11 | BLESerial bleSerial; 12 | #define BLE_NAME "HT-UART" 13 | 14 | int LEDpins[] = {14, 12}; // G, B 15 | int LEDNum = sizeof LEDpins / sizeof LEDpins[0]; 16 | 17 | void pinsSetup() 18 | { 19 | // LEDs & debug pins 20 | for (int i = 0; i < LEDNum; i++) 21 | { 22 | pinMode(LEDpins[i], OUTPUT); 23 | digitalWrite(LEDpins[i], 0); // 0 = ON (inverted logic) 24 | delay(100); 25 | digitalWrite(LEDpins[i], 1); // 1 = OFF (inverted logic) 26 | } 27 | 28 | pinMode(PIN_SERIAL_RX, OUTPUT); // TODO REMOVE (TMP) 29 | } 30 | 31 | void serialSetup() 32 | { 33 | Serial.setPins(0, PIN_SERIAL_TX); // RX is not used here 34 | Serial.begin(230400); 35 | Serial.println("Serial OK!"); 36 | } 37 | 38 | void wirelessSetup() 39 | { 40 | Serial.println("Starting BLE-UART..."); 41 | bleSerial.setLocalName(BLE_NAME); 42 | bleSerial.setDeviceName(BLE_NAME); 43 | bleSerial.setConnectionInterval(0x0006, 0x0006); 44 | bleSerial.begin(); 45 | } 46 | 47 | void sendPulseData() 48 | { 49 | // Send binary metadata (base ID and axis) 50 | uint8_t base_axis = pulse_data.baseID << 1 | pulse_data.axis; 51 | message[0] = base_axis; 52 | message[1] = 0; 53 | for (int t = 0, i = 0; t < 2; t++) 54 | { 55 | // send captures 56 | for (int c = 0; c < sensors_num; c += 2, i++) 57 | { 58 | int pulseStart = pulse_data.sweep_captures[t][c]; 59 | int pulseEnd = pulse_data.sweep_captures[t][c + 1]; 60 | int pulseWidthTicks16 = pulseEnd - pulseStart; 61 | // TODO: deport data verification to higher level? 62 | if (pulseWidthTicks16 < minSweepPulseWidth || // ticks 63 | pulseWidthTicks16 > maxSweepPulseWidth || // ticks 64 | pulseStart < sweepStartTicks || // ticks 65 | pulseEnd > sweepEndTicks) // ticks 66 | { 67 | // mark the measures if they are invalid 68 | pulseStart = 0; 69 | pulseEnd = 0; 70 | } 71 | 72 | // get centroid + remove 2 LSb (non-significant) to stay in 16bit 73 | // TODO: use differential loss-less compression 74 | int centroid = ((pulseEnd + pulseStart) / 2) >> 2; 75 | message[i * 2 + 2] = (centroid >> 8) & 0xFF; // MSB first 76 | message[i * 2 + 3] = (centroid >> 0) & 0xFF; // LSB last 77 | message[1] += centroid & 0xFF; // add LSB to checksum 78 | } 79 | } 80 | 81 | // set the high-bits and metadata on message separator (base/axis + checksum) 82 | message[0] = 0x80 | (message[0] << 5) & 0x60 | (message[1] >> 4) & 0x0F; 83 | message[1] = 0x80 | (message[1] >> 0) & 0x0F; 84 | if (bleSerial) { 85 | bleSerial.write(message, 10); 86 | bleSerial.poll(); 87 | } 88 | if (Serial) 89 | Serial.write(message, 10); 90 | } 91 | -------------------------------------------------------------------------------- /communication.h: -------------------------------------------------------------------------------- 1 | #ifndef _COMMUNICATION_H_ 2 | 3 | void pinsSetup(); 4 | void serialSetup(); 5 | void wirelessSetup(); 6 | 7 | void sendPulseData(); 8 | 9 | #endif // _COMMUNICATION_H_ 10 | 11 | -------------------------------------------------------------------------------- /firmware.h: -------------------------------------------------------------------------------- 1 | #ifndef _FIRMWARE_H_ 2 | #define _FIRMWARE_H_ 3 | 4 | #define DEBUG 5 | 6 | #ifdef DEBUG 7 | #include "Arduino.h" 8 | #define DEBUG_PRINT(...) Serial.print(__VA_ARGS__) 9 | #define DEBUG_PRINTLN(...) Serial.println(__VA_ARGS__) 10 | #define DEBUG_WRITE(...) Serial.write(__VA_ARGS__) 11 | #else 12 | #define DEBUG_PRINT(...) 13 | #define DEBUG_PRINTLN(...) 14 | #define DEBUG_WRITE(...) 15 | #endif 16 | 17 | #endif // _FIRMWARE_H_ 18 | -------------------------------------------------------------------------------- /firmware.ino: -------------------------------------------------------------------------------- 1 | #include "pinout.h" 2 | #include "communication.h" 3 | #include "pulse.h" 4 | 5 | 6 | void sendData() { 7 | sendPulseData(); 8 | // sendOrientations(); // TODO 9 | // sendAccelerations(); // TODO 10 | } 11 | 12 | void setup() { 13 | pinsSetup(); 14 | serialSetup(); 15 | 16 | // Start pulse measurements and set data TX callback function (using timers) 17 | pulseSetup(NULL); // NULL => use pulseDataIsReady() to know when ready 18 | 19 | // IMUsetup(); // TODO 20 | 21 | wirelessSetup(); // IMPORTANT: KEEP IT LAST! 22 | } 23 | 24 | void loop() { 25 | if (pulseDataIsReady()) { // should be called as often as possible 26 | sendData(); 27 | } 28 | } 29 | 30 | -------------------------------------------------------------------------------- /nRF_SDK/nrf_gpiote.h: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2010 - 2017, Nordic Semiconductor ASA All rights reserved. 2 | * 3 | * Redistribution and use in source and binary forms, with or without 4 | * modification, are permitted provided that the following conditions are met: 5 | * 6 | * 1. Redistributions of source code must retain the above copyright notice, this 7 | * list of conditions and the following disclaimer. 8 | * 9 | * 2. Redistributions in binary form must reproduce the above copyright 10 | * notice, this list of conditions and the following disclaimer in the 11 | * documentation and/or other materials provided with the distribution. 12 | * 13 | * 3. Neither the name of Nordic Semiconductor ASA nor the names of its 14 | * contributors may be used to endorse or promote products derived from this 15 | * software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY, AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | */ 29 | #ifndef NRF_GPIOTE_H__ 30 | #define NRF_GPIOTE_H__ 31 | 32 | #include "nrf.h" 33 | #include 34 | #include 35 | #include 36 | 37 | /** 38 | * @defgroup nrf_gpiote_abs GPIOTE abstraction 39 | * @{ 40 | * @ingroup nrf_gpiote 41 | * @brief GPIOTE abstraction for configuration of channels. 42 | */ 43 | #ifdef NRF51 44 | #define NUMBER_OF_GPIO_TE 4 45 | #elif defined(NRF52) 46 | #define NUMBER_OF_GPIO_TE 8 47 | #else 48 | #error "Chip family not specified" 49 | #endif 50 | 51 | /** 52 | * @enum nrf_gpiote_polarity_t 53 | * @brief Polarity for the GPIOTE channel. 54 | */ 55 | typedef enum 56 | { 57 | NRF_GPIOTE_POLARITY_LOTOHI = GPIOTE_CONFIG_POLARITY_LoToHi, ///< Low to high. 58 | NRF_GPIOTE_POLARITY_HITOLO = GPIOTE_CONFIG_POLARITY_HiToLo, ///< High to low. 59 | NRF_GPIOTE_POLARITY_TOGGLE = GPIOTE_CONFIG_POLARITY_Toggle ///< Toggle. 60 | } nrf_gpiote_polarity_t; 61 | 62 | 63 | /** 64 | * @enum nrf_gpiote_outinit_t 65 | * @brief Initial output value for the GPIOTE channel. 66 | */ 67 | typedef enum 68 | { 69 | NRF_GPIOTE_INITIAL_VALUE_LOW = GPIOTE_CONFIG_OUTINIT_Low, ///< Low to high. 70 | NRF_GPIOTE_INITIAL_VALUE_HIGH = GPIOTE_CONFIG_OUTINIT_High ///< High to low. 71 | } nrf_gpiote_outinit_t; 72 | 73 | /** 74 | * @brief Tasks. 75 | */ 76 | typedef enum /*lint -save -e30 -esym(628,__INTADDR__) */ 77 | { 78 | NRF_GPIOTE_TASKS_OUT_0 = offsetof(NRF_GPIOTE_Type, TASKS_OUT[0]), /**< Out task 0.*/ 79 | NRF_GPIOTE_TASKS_OUT_1 = offsetof(NRF_GPIOTE_Type, TASKS_OUT[1]), /**< Out task 1.*/ 80 | NRF_GPIOTE_TASKS_OUT_2 = offsetof(NRF_GPIOTE_Type, TASKS_OUT[2]), /**< Out task 2.*/ 81 | NRF_GPIOTE_TASKS_OUT_3 = offsetof(NRF_GPIOTE_Type, TASKS_OUT[3]), /**< Out task 3.*/ 82 | #if (NUMBER_OF_GPIO_TE == 8) 83 | NRF_GPIOTE_TASKS_OUT_4 = offsetof(NRF_GPIOTE_Type, TASKS_OUT[4]), /**< Out task 4.*/ 84 | NRF_GPIOTE_TASKS_OUT_5 = offsetof(NRF_GPIOTE_Type, TASKS_OUT[5]), /**< Out task 5.*/ 85 | NRF_GPIOTE_TASKS_OUT_6 = offsetof(NRF_GPIOTE_Type, TASKS_OUT[6]), /**< Out task 6.*/ 86 | NRF_GPIOTE_TASKS_OUT_7 = offsetof(NRF_GPIOTE_Type, TASKS_OUT[7]), /**< Out task 7.*/ 87 | #endif 88 | #ifdef NRF52 89 | NRF_GPIOTE_TASKS_SET_0 = offsetof(NRF_GPIOTE_Type, TASKS_SET[0]), /**< Set task 0.*/ 90 | NRF_GPIOTE_TASKS_SET_1 = offsetof(NRF_GPIOTE_Type, TASKS_SET[1]), /**< Set task 1.*/ 91 | NRF_GPIOTE_TASKS_SET_2 = offsetof(NRF_GPIOTE_Type, TASKS_SET[2]), /**< Set task 2.*/ 92 | NRF_GPIOTE_TASKS_SET_3 = offsetof(NRF_GPIOTE_Type, TASKS_SET[3]), /**< Set task 3.*/ 93 | NRF_GPIOTE_TASKS_SET_4 = offsetof(NRF_GPIOTE_Type, TASKS_SET[4]), /**< Set task 4.*/ 94 | NRF_GPIOTE_TASKS_SET_5 = offsetof(NRF_GPIOTE_Type, TASKS_SET[5]), /**< Set task 5.*/ 95 | NRF_GPIOTE_TASKS_SET_6 = offsetof(NRF_GPIOTE_Type, TASKS_SET[6]), /**< Set task 6.*/ 96 | NRF_GPIOTE_TASKS_SET_7 = offsetof(NRF_GPIOTE_Type, TASKS_SET[7]), /**< Set task 7.*/ 97 | NRF_GPIOTE_TASKS_CLR_0 = offsetof(NRF_GPIOTE_Type, TASKS_CLR[0]), /**< Clear task 0.*/ 98 | NRF_GPIOTE_TASKS_CLR_1 = offsetof(NRF_GPIOTE_Type, TASKS_CLR[1]), /**< Clear task 1.*/ 99 | NRF_GPIOTE_TASKS_CLR_2 = offsetof(NRF_GPIOTE_Type, TASKS_CLR[2]), /**< Clear task 2.*/ 100 | NRF_GPIOTE_TASKS_CLR_3 = offsetof(NRF_GPIOTE_Type, TASKS_CLR[3]), /**< Clear task 3.*/ 101 | NRF_GPIOTE_TASKS_CLR_4 = offsetof(NRF_GPIOTE_Type, TASKS_CLR[4]), /**< Clear task 4.*/ 102 | NRF_GPIOTE_TASKS_CLR_5 = offsetof(NRF_GPIOTE_Type, TASKS_CLR[5]), /**< Clear task 5.*/ 103 | NRF_GPIOTE_TASKS_CLR_6 = offsetof(NRF_GPIOTE_Type, TASKS_CLR[6]), /**< Clear task 6.*/ 104 | NRF_GPIOTE_TASKS_CLR_7 = offsetof(NRF_GPIOTE_Type, TASKS_CLR[7]), /**< Clear task 7.*/ 105 | #endif 106 | /*lint -restore*/ 107 | } nrf_gpiote_tasks_t; 108 | 109 | /** 110 | * @brief Events. 111 | */ 112 | typedef enum /*lint -save -e30 -esym(628,__INTADDR__) */ 113 | { 114 | NRF_GPIOTE_EVENTS_IN_0 = offsetof(NRF_GPIOTE_Type, EVENTS_IN[0]), /**< In event 0.*/ 115 | NRF_GPIOTE_EVENTS_IN_1 = offsetof(NRF_GPIOTE_Type, EVENTS_IN[1]), /**< In event 1.*/ 116 | NRF_GPIOTE_EVENTS_IN_2 = offsetof(NRF_GPIOTE_Type, EVENTS_IN[2]), /**< In event 2.*/ 117 | NRF_GPIOTE_EVENTS_IN_3 = offsetof(NRF_GPIOTE_Type, EVENTS_IN[3]), /**< In event 3.*/ 118 | #if (NUMBER_OF_GPIO_TE == 8) 119 | NRF_GPIOTE_EVENTS_IN_4 = offsetof(NRF_GPIOTE_Type, EVENTS_IN[4]), /**< In event 4.*/ 120 | NRF_GPIOTE_EVENTS_IN_5 = offsetof(NRF_GPIOTE_Type, EVENTS_IN[5]), /**< In event 5.*/ 121 | NRF_GPIOTE_EVENTS_IN_6 = offsetof(NRF_GPIOTE_Type, EVENTS_IN[6]), /**< In event 6.*/ 122 | NRF_GPIOTE_EVENTS_IN_7 = offsetof(NRF_GPIOTE_Type, EVENTS_IN[7]), /**< In event 7.*/ 123 | #endif 124 | NRF_GPIOTE_EVENTS_PORT = offsetof(NRF_GPIOTE_Type, EVENTS_PORT), /**< Port event.*/ 125 | /*lint -restore*/ 126 | } nrf_gpiote_events_t; 127 | 128 | /** 129 | * @enum nrf_gpiote_int_t 130 | * @brief GPIOTE interrupts. 131 | */ 132 | typedef enum 133 | { 134 | NRF_GPIOTE_INT_IN0_MASK = GPIOTE_INTENSET_IN0_Msk, /**< GPIOTE interrupt from IN0. */ 135 | NRF_GPIOTE_INT_IN1_MASK = GPIOTE_INTENSET_IN1_Msk, /**< GPIOTE interrupt from IN1. */ 136 | NRF_GPIOTE_INT_IN2_MASK = GPIOTE_INTENSET_IN2_Msk, /**< GPIOTE interrupt from IN2. */ 137 | NRF_GPIOTE_INT_IN3_MASK = GPIOTE_INTENSET_IN3_Msk, /**< GPIOTE interrupt from IN3. */ 138 | #if (NUMBER_OF_GPIO_TE == 8) 139 | NRF_GPIOTE_INT_IN4_MASK = GPIOTE_INTENSET_IN4_Msk, /**< GPIOTE interrupt from IN4. */ 140 | NRF_GPIOTE_INT_IN5_MASK = GPIOTE_INTENSET_IN5_Msk, /**< GPIOTE interrupt from IN5. */ 141 | NRF_GPIOTE_INT_IN6_MASK = GPIOTE_INTENSET_IN6_Msk, /**< GPIOTE interrupt from IN6. */ 142 | NRF_GPIOTE_INT_IN7_MASK = GPIOTE_INTENSET_IN7_Msk, /**< GPIOTE interrupt from IN7. */ 143 | #endif 144 | NRF_GPIOTE_INT_PORT_MASK = (int)GPIOTE_INTENSET_PORT_Msk, /**< GPIOTE interrupt from PORT event. */ 145 | } nrf_gpiote_int_t; 146 | 147 | #if (NUMBER_OF_GPIO_TE == 4) 148 | #define NRF_GPIOTE_INT_IN_MASK (NRF_GPIOTE_INT_IN0_MASK | NRF_GPIOTE_INT_IN1_MASK |\ 149 | NRF_GPIOTE_INT_IN2_MASK | NRF_GPIOTE_INT_IN3_MASK) 150 | #elif (NUMBER_OF_GPIO_TE == 8) 151 | #define NRF_GPIOTE_INT_IN_MASK (NRF_GPIOTE_INT_IN0_MASK | NRF_GPIOTE_INT_IN1_MASK |\ 152 | NRF_GPIOTE_INT_IN2_MASK | NRF_GPIOTE_INT_IN3_MASK |\ 153 | NRF_GPIOTE_INT_IN4_MASK | NRF_GPIOTE_INT_IN5_MASK |\ 154 | NRF_GPIOTE_INT_IN6_MASK | NRF_GPIOTE_INT_IN7_MASK) 155 | #else 156 | #error "Unexpected number of GPIO Tasks and Events" 157 | #endif 158 | /** 159 | * @brief Function for activating a specific GPIOTE task. 160 | * 161 | * @param[in] task Task. 162 | */ 163 | __STATIC_INLINE void nrf_gpiote_task_set(nrf_gpiote_tasks_t task); 164 | 165 | /** 166 | * @brief Function for getting the address of a specific GPIOTE task. 167 | * 168 | * @param[in] task Task. 169 | * 170 | * @returns Address. 171 | */ 172 | __STATIC_INLINE uint32_t nrf_gpiote_task_addr_get(nrf_gpiote_tasks_t task); 173 | 174 | /** 175 | * @brief Function for getting the state of a specific GPIOTE event. 176 | * 177 | * @param[in] event Event. 178 | */ 179 | __STATIC_INLINE bool nrf_gpiote_event_is_set(nrf_gpiote_events_t event); 180 | 181 | /** 182 | * @brief Function for clearing a specific GPIOTE event. 183 | * 184 | * @param[in] event Event. 185 | */ 186 | __STATIC_INLINE void nrf_gpiote_event_clear(nrf_gpiote_events_t event); 187 | 188 | /** 189 | * @brief Function for getting the address of a specific GPIOTE event. 190 | * 191 | * @param[in] event Event. 192 | * 193 | * @return Address 194 | */ 195 | __STATIC_INLINE uint32_t nrf_gpiote_event_addr_get(nrf_gpiote_events_t event); 196 | 197 | /**@brief Function for enabling interrupts. 198 | * 199 | * @param[in] mask Interrupt mask to be enabled. 200 | */ 201 | __STATIC_INLINE void nrf_gpiote_int_enable(uint32_t mask); 202 | 203 | /**@brief Function for disabling interrupts. 204 | * 205 | * @param[in] mask Interrupt mask to be disabled. 206 | */ 207 | __STATIC_INLINE void nrf_gpiote_int_disable(uint32_t mask); 208 | 209 | /**@brief Function for checking if interrupts are enabled. 210 | * 211 | * @param[in] mask Mask of interrupt flags to check. 212 | * 213 | * @return Mask with enabled interrupts. 214 | */ 215 | __STATIC_INLINE uint32_t nrf_gpiote_int_is_enabled(uint32_t mask); 216 | 217 | /**@brief Function for enabling a GPIOTE event. 218 | * 219 | * @param[in] idx Task-Event index. 220 | */ 221 | __STATIC_INLINE void nrf_gpiote_event_enable(uint32_t idx); 222 | 223 | /**@brief Function for disabling a GPIOTE event. 224 | * 225 | * @param[in] idx Task-Event index. 226 | */ 227 | __STATIC_INLINE void nrf_gpiote_event_disable(uint32_t idx); 228 | 229 | /**@brief Function for configuring a GPIOTE event. 230 | * 231 | * @param[in] idx Task-Event index. 232 | * @param[in] pin Pin associated with event. 233 | * @param[in] polarity Transition that should generate an event. 234 | */ 235 | __STATIC_INLINE void nrf_gpiote_event_configure(uint32_t idx, uint32_t pin, 236 | nrf_gpiote_polarity_t polarity); 237 | 238 | /**@brief Function for getting the pin associated with a GPIOTE event. 239 | * 240 | * @param[in] idx Task-Event index. 241 | * 242 | * @return Pin number. 243 | */ 244 | __STATIC_INLINE uint32_t nrf_gpiote_event_pin_get(uint32_t idx); 245 | 246 | /**@brief Function for getting the polarity associated with a GPIOTE event. 247 | * 248 | * @param[in] idx Task-Event index. 249 | * 250 | * @return Polarity. 251 | */ 252 | __STATIC_INLINE nrf_gpiote_polarity_t nrf_gpiote_event_polarity_get(uint32_t idx); 253 | 254 | /**@brief Function for enabling a GPIOTE task. 255 | * 256 | * @param[in] idx Task-Event index. 257 | */ 258 | __STATIC_INLINE void nrf_gpiote_task_enable(uint32_t idx); 259 | 260 | /**@brief Function for disabling a GPIOTE task. 261 | * 262 | * @param[in] idx Task-Event index. 263 | */ 264 | __STATIC_INLINE void nrf_gpiote_task_disable(uint32_t idx); 265 | 266 | /**@brief Function for configuring a GPIOTE task. 267 | * @note Function is not configuring mode field so task is disabled after this function is called. 268 | * 269 | * @param[in] idx Task-Event index. 270 | * @param[in] pin Pin associated with event. 271 | * @param[in] polarity Transition that should generate an event. 272 | * @param[in] init_val Initial value of pin. 273 | */ 274 | __STATIC_INLINE void nrf_gpiote_task_configure(uint32_t idx, uint32_t pin, 275 | nrf_gpiote_polarity_t polarity, 276 | nrf_gpiote_outinit_t init_val); 277 | 278 | /**@brief Function for forcing a specific state on the pin connected to GPIOTE. 279 | * 280 | * @param[in] idx Task-Event index. 281 | * @param[in] init_val Pin state. 282 | */ 283 | __STATIC_INLINE void nrf_gpiote_task_force(uint32_t idx, nrf_gpiote_outinit_t init_val); 284 | 285 | /**@brief Function for resetting a GPIOTE task event configuration to the default state. 286 | * 287 | * @param[in] idx Task-Event index. 288 | */ 289 | __STATIC_INLINE void nrf_gpiote_te_default(uint32_t idx); 290 | 291 | #ifndef SUPPRESS_INLINE_IMPLEMENTATION 292 | __STATIC_INLINE void nrf_gpiote_task_set(nrf_gpiote_tasks_t task) 293 | { 294 | *(__IO uint32_t *)((uint32_t)NRF_GPIOTE + task) = 0x1UL; 295 | } 296 | 297 | __STATIC_INLINE uint32_t nrf_gpiote_task_addr_get(nrf_gpiote_tasks_t task) 298 | { 299 | return ((uint32_t)NRF_GPIOTE + task); 300 | } 301 | 302 | __STATIC_INLINE bool nrf_gpiote_event_is_set(nrf_gpiote_events_t event) 303 | { 304 | return (*(uint32_t *)nrf_gpiote_event_addr_get(event) == 0x1UL) ? true : false; 305 | } 306 | 307 | __STATIC_INLINE void nrf_gpiote_event_clear(nrf_gpiote_events_t event) 308 | { 309 | *(uint32_t *)nrf_gpiote_event_addr_get(event) = 0; 310 | #if __CORTEX_M == 0x04 311 | volatile uint32_t dummy = *((volatile uint32_t *)nrf_gpiote_event_addr_get(event)); 312 | (void)dummy; 313 | #endif 314 | } 315 | 316 | __STATIC_INLINE uint32_t nrf_gpiote_event_addr_get(nrf_gpiote_events_t event) 317 | { 318 | return ((uint32_t)NRF_GPIOTE + event); 319 | } 320 | 321 | __STATIC_INLINE void nrf_gpiote_int_enable(uint32_t mask) 322 | { 323 | NRF_GPIOTE->INTENSET = mask; 324 | } 325 | 326 | __STATIC_INLINE void nrf_gpiote_int_disable(uint32_t mask) 327 | { 328 | NRF_GPIOTE->INTENCLR = mask; 329 | } 330 | 331 | __STATIC_INLINE uint32_t nrf_gpiote_int_is_enabled(uint32_t mask) 332 | { 333 | return (NRF_GPIOTE->INTENSET & mask); 334 | } 335 | 336 | __STATIC_INLINE void nrf_gpiote_event_enable(uint32_t idx) 337 | { 338 | NRF_GPIOTE->CONFIG[idx] |= GPIOTE_CONFIG_MODE_Event; 339 | } 340 | 341 | __STATIC_INLINE void nrf_gpiote_event_disable(uint32_t idx) 342 | { 343 | NRF_GPIOTE->CONFIG[idx] &= ~GPIOTE_CONFIG_MODE_Event; 344 | } 345 | 346 | #include 347 | #include 348 | 349 | __STATIC_INLINE void nrf_gpiote_event_configure(uint32_t idx, uint32_t pin, nrf_gpiote_polarity_t polarity) 350 | { 351 | NRF_GPIOTE->CONFIG[idx] &= ~(GPIOTE_CONFIG_PSEL_Msk | GPIOTE_CONFIG_POLARITY_Msk); 352 | NRF_GPIOTE->CONFIG[idx] |= ((pin << GPIOTE_CONFIG_PSEL_Pos) & GPIOTE_CONFIG_PSEL_Msk) | 353 | ((polarity << GPIOTE_CONFIG_POLARITY_Pos) & GPIOTE_CONFIG_POLARITY_Msk); 354 | } 355 | 356 | __STATIC_INLINE uint32_t nrf_gpiote_event_pin_get(uint32_t idx) 357 | { 358 | return ((NRF_GPIOTE->CONFIG[idx] & GPIOTE_CONFIG_PSEL_Msk) >> GPIOTE_CONFIG_PSEL_Pos); 359 | } 360 | 361 | __STATIC_INLINE nrf_gpiote_polarity_t nrf_gpiote_event_polarity_get(uint32_t idx) 362 | { 363 | return (nrf_gpiote_polarity_t)((NRF_GPIOTE->CONFIG[idx] & GPIOTE_CONFIG_POLARITY_Msk) >> GPIOTE_CONFIG_POLARITY_Pos); 364 | } 365 | 366 | __STATIC_INLINE void nrf_gpiote_task_enable(uint32_t idx) 367 | { 368 | uint32_t final_config = NRF_GPIOTE->CONFIG[idx] | GPIOTE_CONFIG_MODE_Task; 369 | /* Workaround for the OUTINIT PAN. When nrf_gpiote_task_config() is called a glitch happens 370 | on the GPIO if the GPIO in question is already assigned to GPIOTE and the pin is in the 371 | correct state in GPIOTE but not in the OUT register. */ 372 | /* Configure channel to Pin31, not connected to the pin, and configure as a tasks that will set it to proper level */ 373 | NRF_GPIOTE->CONFIG[idx] = final_config | ((31 << GPIOTE_CONFIG_PSEL_Pos) & GPIOTE_CONFIG_PSEL_Msk); 374 | __NOP(); 375 | __NOP(); 376 | __NOP(); 377 | NRF_GPIOTE->CONFIG[idx] = final_config; 378 | } 379 | 380 | __STATIC_INLINE void nrf_gpiote_task_disable(uint32_t idx) 381 | { 382 | NRF_GPIOTE->CONFIG[idx] &= ~GPIOTE_CONFIG_MODE_Task; 383 | } 384 | 385 | __STATIC_INLINE void nrf_gpiote_task_configure(uint32_t idx, uint32_t pin, 386 | nrf_gpiote_polarity_t polarity, 387 | nrf_gpiote_outinit_t init_val) 388 | { 389 | NRF_GPIOTE->CONFIG[idx] &= ~(GPIOTE_CONFIG_PSEL_Msk | 390 | GPIOTE_CONFIG_POLARITY_Msk | 391 | GPIOTE_CONFIG_OUTINIT_Msk); 392 | 393 | NRF_GPIOTE->CONFIG[idx] |= ((pin << GPIOTE_CONFIG_PSEL_Pos) & GPIOTE_CONFIG_PSEL_Msk) | 394 | ((polarity << GPIOTE_CONFIG_POLARITY_Pos) & GPIOTE_CONFIG_POLARITY_Msk) | 395 | ((init_val << GPIOTE_CONFIG_OUTINIT_Pos) & GPIOTE_CONFIG_OUTINIT_Msk); 396 | } 397 | 398 | __STATIC_INLINE void nrf_gpiote_task_force(uint32_t idx, nrf_gpiote_outinit_t init_val) 399 | { 400 | NRF_GPIOTE->CONFIG[idx] = (NRF_GPIOTE->CONFIG[idx] & ~GPIOTE_CONFIG_OUTINIT_Msk) 401 | | ((init_val << GPIOTE_CONFIG_OUTINIT_Pos) & GPIOTE_CONFIG_OUTINIT_Msk); 402 | } 403 | 404 | __STATIC_INLINE void nrf_gpiote_te_default(uint32_t idx) 405 | { 406 | NRF_GPIOTE->CONFIG[idx] = 0; 407 | } 408 | #endif //SUPPRESS_INLINE_IMPLEMENTATION 409 | /** @} */ 410 | 411 | #endif 412 | -------------------------------------------------------------------------------- /nRF_SDK/nrf_ppi.h: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2010 - 2017, Nordic Semiconductor ASA All rights reserved. 2 | * 3 | * Redistribution and use in source and binary forms, with or without 4 | * modification, are permitted provided that the following conditions are met: 5 | * 6 | * 1. Redistributions of source code must retain the above copyright notice, this 7 | * list of conditions and the following disclaimer. 8 | * 9 | * 2. Redistributions in binary form must reproduce the above copyright 10 | * notice, this list of conditions and the following disclaimer in the 11 | * documentation and/or other materials provided with the distribution. 12 | * 13 | * 3. Neither the name of Nordic Semiconductor ASA nor the names of its 14 | * contributors may be used to endorse or promote products derived from this 15 | * software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY, AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | */ 29 | 30 | #ifndef NRF_PPI_H__ 31 | #define NRF_PPI_H__ 32 | 33 | #include 34 | #include "nrf.h" 35 | 36 | /** 37 | * @defgroup nrf_ppi_hal PPI HAL 38 | * @{ 39 | * @ingroup nrf_ppi 40 | * @brief Hardware access layer for setting up Programmable Peripheral Interconnect (PPI) channels. 41 | */ 42 | 43 | #define NRF_PPI_TASK_SET (1UL) 44 | 45 | /** 46 | * @enum nrf_ppi_channel_t 47 | * @brief PPI channels. 48 | */ 49 | typedef enum 50 | { 51 | NRF_PPI_CHANNEL0 = PPI_CHEN_CH0_Pos, /**< Channel 0. */ 52 | NRF_PPI_CHANNEL1 = PPI_CHEN_CH1_Pos, /**< Channel 1. */ 53 | NRF_PPI_CHANNEL2 = PPI_CHEN_CH2_Pos, /**< Channel 2. */ 54 | NRF_PPI_CHANNEL3 = PPI_CHEN_CH3_Pos, /**< Channel 3. */ 55 | NRF_PPI_CHANNEL4 = PPI_CHEN_CH4_Pos, /**< Channel 4. */ 56 | NRF_PPI_CHANNEL5 = PPI_CHEN_CH5_Pos, /**< Channel 5. */ 57 | NRF_PPI_CHANNEL6 = PPI_CHEN_CH6_Pos, /**< Channel 6. */ 58 | NRF_PPI_CHANNEL7 = PPI_CHEN_CH7_Pos, /**< Channel 7. */ 59 | NRF_PPI_CHANNEL8 = PPI_CHEN_CH8_Pos, /**< Channel 8. */ 60 | NRF_PPI_CHANNEL9 = PPI_CHEN_CH9_Pos, /**< Channel 9. */ 61 | NRF_PPI_CHANNEL10 = PPI_CHEN_CH10_Pos, /**< Channel 10. */ 62 | NRF_PPI_CHANNEL11 = PPI_CHEN_CH11_Pos, /**< Channel 11. */ 63 | NRF_PPI_CHANNEL12 = PPI_CHEN_CH12_Pos, /**< Channel 12. */ 64 | NRF_PPI_CHANNEL13 = PPI_CHEN_CH13_Pos, /**< Channel 13. */ 65 | NRF_PPI_CHANNEL14 = PPI_CHEN_CH14_Pos, /**< Channel 14. */ 66 | NRF_PPI_CHANNEL15 = PPI_CHEN_CH15_Pos, /**< Channel 15. */ 67 | #ifdef NRF52 68 | NRF_PPI_CHANNEL16 = PPI_CHEN_CH16_Pos, /**< Channel 16. */ 69 | NRF_PPI_CHANNEL17 = PPI_CHEN_CH17_Pos, /**< Channel 17. */ 70 | NRF_PPI_CHANNEL18 = PPI_CHEN_CH18_Pos, /**< Channel 18. */ 71 | NRF_PPI_CHANNEL19 = PPI_CHEN_CH19_Pos, /**< Channel 19. */ 72 | #endif 73 | NRF_PPI_CHANNEL20 = PPI_CHEN_CH20_Pos, /**< Channel 20. */ 74 | NRF_PPI_CHANNEL21 = PPI_CHEN_CH21_Pos, /**< Channel 21. */ 75 | NRF_PPI_CHANNEL22 = PPI_CHEN_CH22_Pos, /**< Channel 22. */ 76 | NRF_PPI_CHANNEL23 = PPI_CHEN_CH23_Pos, /**< Channel 23. */ 77 | NRF_PPI_CHANNEL24 = PPI_CHEN_CH24_Pos, /**< Channel 24. */ 78 | NRF_PPI_CHANNEL25 = PPI_CHEN_CH25_Pos, /**< Channel 25. */ 79 | NRF_PPI_CHANNEL26 = PPI_CHEN_CH26_Pos, /**< Channel 26. */ 80 | NRF_PPI_CHANNEL27 = PPI_CHEN_CH27_Pos, /**< Channel 27. */ 81 | NRF_PPI_CHANNEL28 = PPI_CHEN_CH28_Pos, /**< Channel 28. */ 82 | NRF_PPI_CHANNEL29 = PPI_CHEN_CH29_Pos, /**< Channel 29. */ 83 | NRF_PPI_CHANNEL30 = PPI_CHEN_CH30_Pos, /**< Channel 30. */ 84 | NRF_PPI_CHANNEL31 = PPI_CHEN_CH31_Pos /**< Channel 31. */ 85 | } nrf_ppi_channel_t; 86 | 87 | /** 88 | * @enum nrf_ppi_channel_group_t 89 | * @brief PPI channel groups. 90 | */ 91 | typedef enum 92 | { 93 | NRF_PPI_CHANNEL_GROUP0 = 0, /**< Channel group 0. */ 94 | NRF_PPI_CHANNEL_GROUP1 = 1, /**< Channel group 1. */ 95 | NRF_PPI_CHANNEL_GROUP2 = 2, /**< Channel group 2. */ 96 | NRF_PPI_CHANNEL_GROUP3 = 3, /**< Channel group 3. */ 97 | #ifdef NRF52 98 | NRF_PPI_CHANNEL_GROUP4 = 4, /**< Channel group 4. */ 99 | NRF_PPI_CHANNEL_GROUP5 = 5 /**< Channel group 5. */ 100 | #endif 101 | } nrf_ppi_channel_group_t; 102 | 103 | /** 104 | * @enum nrf_ppi_channel_include_t 105 | * @brief Definition of which PPI channels belong to a group. 106 | */ 107 | typedef enum 108 | { 109 | NRF_PPI_CHANNEL_EXCLUDE = PPI_CHG_CH0_Excluded, /**< Channel excluded from a group. */ 110 | NRF_PPI_CHANNEL_INCLUDE = PPI_CHG_CH0_Included /**< Channel included in a group. */ 111 | } nrf_ppi_channel_include_t; 112 | 113 | /** 114 | * @enum nrf_ppi_channel_enable_t 115 | * @brief Definition if a PPI channel is enabled. 116 | */ 117 | typedef enum 118 | { 119 | NRF_PPI_CHANNEL_DISABLED = PPI_CHEN_CH0_Disabled, /**< Channel disabled. */ 120 | NRF_PPI_CHANNEL_ENABLED = PPI_CHEN_CH0_Enabled /**< Channel enabled. */ 121 | } nrf_ppi_channel_enable_t; 122 | 123 | /** 124 | * @enum nrf_ppi_task_t 125 | * @brief PPI tasks. 126 | */ 127 | typedef enum 128 | { 129 | /*lint -save -e30 -esym(628,__INTADDR__)*/ 130 | NRF_PPI_TASK_CHG0_EN = offsetof(NRF_PPI_Type, TASKS_CHG[0].EN), /**< Task for enabling channel group 0 */ 131 | NRF_PPI_TASK_CHG0_DIS = offsetof(NRF_PPI_Type, TASKS_CHG[0].DIS), /**< Task for disabling channel group 0 */ 132 | NRF_PPI_TASK_CHG1_EN = offsetof(NRF_PPI_Type, TASKS_CHG[1].EN), /**< Task for enabling channel group 1 */ 133 | NRF_PPI_TASK_CHG1_DIS = offsetof(NRF_PPI_Type, TASKS_CHG[1].DIS), /**< Task for disabling channel group 1 */ 134 | NRF_PPI_TASK_CHG2_EN = offsetof(NRF_PPI_Type, TASKS_CHG[2].EN), /**< Task for enabling channel group 2 */ 135 | NRF_PPI_TASK_CHG2_DIS = offsetof(NRF_PPI_Type, TASKS_CHG[2].DIS), /**< Task for disabling channel group 2 */ 136 | NRF_PPI_TASK_CHG3_EN = offsetof(NRF_PPI_Type, TASKS_CHG[3].EN), /**< Task for enabling channel group 3 */ 137 | NRF_PPI_TASK_CHG3_DIS = offsetof(NRF_PPI_Type, TASKS_CHG[3].DIS), /**< Task for disabling channel group 3 */ 138 | #ifdef NRF52 139 | NRF_PPI_TASK_CHG4_EN = offsetof(NRF_PPI_Type, TASKS_CHG[4].EN), /**< Task for enabling channel group 4 */ 140 | NRF_PPI_TASK_CHG4_DIS = offsetof(NRF_PPI_Type, TASKS_CHG[4].DIS), /**< Task for disabling channel group 4 */ 141 | NRF_PPI_TASK_CHG5_EN = offsetof(NRF_PPI_Type, TASKS_CHG[5].EN), /**< Task for enabling channel group 5 */ 142 | NRF_PPI_TASK_CHG5_DIS = offsetof(NRF_PPI_Type, TASKS_CHG[5].DIS) /**< Task for disabling channel group 5 */ 143 | #endif 144 | /*lint -restore*/ 145 | } nrf_ppi_task_t; 146 | 147 | /** 148 | * @brief Function for enabling a given PPI channel. 149 | * 150 | * @details This function enables only one channel. 151 | * 152 | * @param[in] channel Channel to enable. 153 | * 154 | * */ 155 | __STATIC_INLINE void nrf_ppi_channel_enable(nrf_ppi_channel_t channel) 156 | { 157 | NRF_PPI->CHENSET = PPI_CHENSET_CH0_Set << ((uint32_t) channel); 158 | } 159 | 160 | 161 | /** 162 | * @brief Function for disabling a given PPI channel. 163 | * 164 | * @details This function disables only one channel. 165 | * 166 | * @param[in] channel Channel to disable. 167 | */ 168 | __STATIC_INLINE void nrf_ppi_channel_disable(nrf_ppi_channel_t channel) 169 | { 170 | NRF_PPI->CHENCLR = PPI_CHENCLR_CH0_Clear << ((uint32_t) channel); 171 | } 172 | 173 | 174 | /** 175 | * @brief Function for checking if a given PPI channel is enabled. 176 | * 177 | * @details This function checks only one channel. 178 | * 179 | * @param[in] channel Channel to check. 180 | * 181 | * @retval NRF_PPI_CHANNEL_ENABLED If the channel is enabled. 182 | * @retval NRF_PPI_CHANNEL_DISABLED If the channel is not enabled. 183 | * 184 | */ 185 | __STATIC_INLINE nrf_ppi_channel_enable_t nrf_ppi_channel_enable_get(nrf_ppi_channel_t channel) 186 | { 187 | if (NRF_PPI->CHEN & (PPI_CHEN_CH0_Msk << ((uint32_t) channel))) 188 | { 189 | return NRF_PPI_CHANNEL_ENABLED; 190 | } 191 | else 192 | { 193 | return NRF_PPI_CHANNEL_DISABLED; 194 | } 195 | } 196 | 197 | 198 | /** 199 | * @brief Function for disabling all PPI channels. 200 | */ 201 | __STATIC_INLINE void nrf_ppi_channel_disable_all(void) 202 | { 203 | NRF_PPI->CHENCLR = ((uint32_t)0xFFFFFFFFuL); 204 | } 205 | 206 | /** 207 | * @brief Function for disabling multiple PPI channels. 208 | * 209 | * @param[in] mask Channel mask. 210 | */ 211 | __STATIC_INLINE void nrf_ppi_channels_disable(uint32_t mask) 212 | { 213 | NRF_PPI->CHENCLR = mask; 214 | } 215 | 216 | /** 217 | * @brief Function for setting up event and task endpoints for a given PPI channel. 218 | * 219 | * @param[in] eep Event register address. 220 | * 221 | * @param[in] tep Task register address. 222 | * 223 | * @param[in] channel Channel to which the given endpoints are assigned. 224 | */ 225 | #include 226 | #include 227 | 228 | __STATIC_INLINE void nrf_ppi_channel_endpoint_setup(nrf_ppi_channel_t channel, 229 | uint32_t eep, 230 | uint32_t tep) 231 | { 232 | NRF_PPI->CH[(uint32_t) channel].EEP = eep; 233 | NRF_PPI->CH[(uint32_t) channel].TEP = tep; 234 | } 235 | 236 | #ifdef NRF52 237 | /** 238 | * @brief Function for setting up task endpoint for a given PPI fork. 239 | * 240 | * @param[in] fork_tep Task register address. 241 | * 242 | * @param[in] channel Channel to which the given fork endpoint is assigned. 243 | */ 244 | __STATIC_INLINE void nrf_ppi_fork_endpoint_setup(nrf_ppi_channel_t channel, 245 | uint32_t fork_tep) 246 | { 247 | NRF_PPI->FORK[(uint32_t) channel].TEP = fork_tep; 248 | } 249 | 250 | /** 251 | * @brief Function for setting up event and task endpoints for a given PPI channel and fork. 252 | * 253 | * @param[in] eep Event register address. 254 | * 255 | * @param[in] tep Task register address. 256 | * 257 | * @param[in] fork_tep Fork task register address (register value). 258 | * 259 | * @param[in] channel Channel to which the given endpoints are assigned. 260 | */ 261 | __STATIC_INLINE void nrf_ppi_channel_and_fork_endpoint_setup(nrf_ppi_channel_t channel, 262 | uint32_t eep, 263 | uint32_t tep, 264 | uint32_t fork_tep) 265 | { 266 | nrf_ppi_channel_endpoint_setup(channel, eep, tep); 267 | nrf_ppi_fork_endpoint_setup(channel, fork_tep); 268 | } 269 | #endif 270 | 271 | /** 272 | * @brief Function for including a PPI channel in a channel group. 273 | * 274 | * @details This function adds only one channel to the group. 275 | * 276 | * @param[in] channel Channel to be included in the group. 277 | * 278 | * @param[in] channel_group Channel group. 279 | * 280 | */ 281 | __STATIC_INLINE void nrf_ppi_channel_include_in_group(nrf_ppi_channel_t channel, 282 | nrf_ppi_channel_group_t channel_group) 283 | { 284 | NRF_PPI->CHG[(uint32_t) channel_group] = 285 | NRF_PPI->CHG[(uint32_t) channel_group] | (PPI_CHG_CH0_Included << ((uint32_t) channel)); 286 | } 287 | 288 | /** 289 | * @brief Function for including multiple PPI channels in a channel group. 290 | * 291 | * @details This function adds all specified channels to the group. 292 | * 293 | * @param[in] channel_mask Channels to be included in the group. 294 | * 295 | * @param[in] channel_group Channel group. 296 | * 297 | */ 298 | __STATIC_INLINE void nrf_ppi_channels_include_in_group(uint32_t channel_mask, 299 | nrf_ppi_channel_group_t channel_group) 300 | { 301 | NRF_PPI->CHG[(uint32_t) channel_group] = 302 | NRF_PPI->CHG[(uint32_t) channel_group] | (channel_mask); 303 | } 304 | 305 | 306 | /** 307 | * @brief Function for removing a PPI channel from a channel group. 308 | * 309 | * @details This function removes only one channel from the group. 310 | * 311 | * @param[in] channel Channel to be removed from the group. 312 | * 313 | * @param[in] channel_group Channel group. 314 | */ 315 | __STATIC_INLINE void nrf_ppi_channel_remove_from_group(nrf_ppi_channel_t channel, 316 | nrf_ppi_channel_group_t channel_group) 317 | { 318 | NRF_PPI->CHG[(uint32_t) channel_group] = 319 | NRF_PPI->CHG[(uint32_t) channel_group] & ~(PPI_CHG_CH0_Included << ((uint32_t) channel)); 320 | } 321 | 322 | /** 323 | * @brief Function for removing multiple PPI channels from a channel group. 324 | * 325 | * @details This function removes all specified channels from the group. 326 | * 327 | * @param[in] channel_mask Channels to be removed from the group. 328 | * 329 | * @param[in] channel_group Channel group. 330 | */ 331 | __STATIC_INLINE void nrf_ppi_channels_remove_from_group(uint32_t channel_mask, 332 | nrf_ppi_channel_group_t channel_group) 333 | { 334 | NRF_PPI->CHG[(uint32_t) channel_group] = 335 | NRF_PPI->CHG[(uint32_t) channel_group] & ~(channel_mask); 336 | } 337 | 338 | 339 | /** 340 | * @brief Function for removing all PPI channels from a channel group. 341 | * 342 | * @param[in] group Channel group. 343 | * 344 | */ 345 | __STATIC_INLINE void nrf_ppi_channel_group_clear(nrf_ppi_channel_group_t group) 346 | { 347 | NRF_PPI->CHG[(uint32_t) group] = 0; 348 | } 349 | 350 | 351 | /** 352 | * @brief Function for enabling a channel group. 353 | * 354 | * @param[in] group Channel group. 355 | * 356 | */ 357 | __STATIC_INLINE void nrf_ppi_group_enable(nrf_ppi_channel_group_t group) 358 | { 359 | NRF_PPI->TASKS_CHG[(uint32_t) group].EN = NRF_PPI_TASK_SET; 360 | } 361 | 362 | 363 | /** 364 | * @brief Function for disabling a channel group. 365 | * 366 | * @param[in] group Channel group. 367 | * 368 | */ 369 | __STATIC_INLINE void nrf_ppi_group_disable(nrf_ppi_channel_group_t group) 370 | { 371 | NRF_PPI->TASKS_CHG[(uint32_t) group].DIS = NRF_PPI_TASK_SET; 372 | } 373 | 374 | 375 | /** 376 | * @brief Function for setting a PPI task. 377 | * 378 | * @param[in] ppi_task PPI task to set. 379 | */ 380 | __STATIC_INLINE void nrf_ppi_task_trigger(nrf_ppi_task_t ppi_task) 381 | { 382 | *((volatile uint32_t *) ((uint8_t *) NRF_PPI_BASE + (uint32_t) ppi_task)) = NRF_PPI_TASK_SET; 383 | } 384 | 385 | 386 | /** 387 | * @brief Function for returning the address of a specific PPI task register. 388 | * 389 | * @param[in] ppi_task PPI task. 390 | */ 391 | __STATIC_INLINE uint32_t * nrf_ppi_task_address_get(nrf_ppi_task_t ppi_task) 392 | { 393 | return (uint32_t *) ((uint8_t *) NRF_PPI_BASE + (uint32_t) ppi_task); 394 | } 395 | 396 | /** 397 | * @brief Function for returning the PPI enable task address of a specific group. 398 | * 399 | * @param[in] group PPI group. 400 | */ 401 | __STATIC_INLINE uint32_t * nrf_ppi_task_group_enable_address_get(nrf_ppi_channel_group_t group) 402 | { 403 | return (uint32_t *) &NRF_PPI->TASKS_CHG[(uint32_t) group].EN; 404 | } 405 | 406 | /** 407 | * @brief Function for returning the PPI disable task address of a specific group. 408 | * 409 | * @param[in] group PPI group. 410 | */ 411 | __STATIC_INLINE uint32_t * nrf_ppi_task_group_disable_address_get(nrf_ppi_channel_group_t group) 412 | { 413 | return (uint32_t *) &NRF_PPI->TASKS_CHG[(uint32_t) group].DIS; 414 | } 415 | 416 | 417 | /** 418 | *@} 419 | **/ 420 | 421 | /*lint --flb "Leave library region" */ 422 | #endif // NRF_PPI_H__ 423 | -------------------------------------------------------------------------------- /nRF_SDK/nrf_timer.h: -------------------------------------------------------------------------------- 1 | /* Copyright (c) 2010 - 2017, Nordic Semiconductor ASA All rights reserved. 2 | * 3 | * Redistribution and use in source and binary forms, with or without 4 | * modification, are permitted provided that the following conditions are met: 5 | * 6 | * 1. Redistributions of source code must retain the above copyright notice, this 7 | * list of conditions and the following disclaimer. 8 | * 9 | * 2. Redistributions in binary form must reproduce the above copyright 10 | * notice, this list of conditions and the following disclaimer in the 11 | * documentation and/or other materials provided with the distribution. 12 | * 13 | * 3. Neither the name of Nordic Semiconductor ASA nor the names of its 14 | * contributors may be used to endorse or promote products derived from this 15 | * software without specific prior written permission. 16 | * 17 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | * IMPLIED WARRANTIES OF MERCHANTABILITY, AND FITNESS FOR A PARTICULAR PURPOSE 20 | * ARE DISCLAIMED. IN NO EVENT SHALL NORDIC SEMICONDUCTOR ASA OR CONTRIBUTORS BE 21 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | * POSSIBILITY OF SUCH DAMAGE. 28 | */ 29 | 30 | /** 31 | * @defgroup nrf_timer_hal Timer HAL 32 | * @{ 33 | * @ingroup nrf_timer 34 | * 35 | * @brief Hardware access layer for accessing the timer peripheral. 36 | */ 37 | 38 | #ifndef NRF_TIMER_H__ 39 | #define NRF_TIMER_H__ 40 | 41 | #include 42 | #include 43 | #include 44 | 45 | #include "nrf.h" 46 | 47 | 48 | /** 49 | * @brief Macro for validating the correctness of the BIT_WIDTH setting. 50 | */ 51 | #ifdef NRF51 52 | /** 53 | * In the nRF51 Series, timer instance 0 supports all available bit widths. 54 | * The other two instances support only 8 and 16 bits. 55 | */ 56 | #define NRF_TIMER_IS_BIT_WIDTH_VALID(p_timer, bit_width) \ 57 | ((p_timer == NRF_TIMER0) || (bit_width <= NRF_TIMER_BIT_WIDTH_16)) 58 | #else 59 | /** 60 | * In the nRF52 Series, all timer instances support all available bit widths. 61 | */ 62 | #define NRF_TIMER_IS_BIT_WIDTH_VALID(p_timer, bit_width) true 63 | #endif 64 | 65 | /** 66 | * @brief Macro for getting the number of capture/compare channels available 67 | * in a given timer instance. 68 | */ 69 | #ifdef NRF51 70 | #define NRF_TIMER_CC_CHANNEL_COUNT(id) 4 71 | #else 72 | #define NRF_TIMER_CC_CHANNEL_COUNT(id) ((id) <= 2 ? 4 : 6) 73 | #endif 74 | 75 | 76 | /** 77 | * @brief Timer tasks. 78 | */ 79 | typedef enum 80 | { 81 | /*lint -save -e30 -esym(628,__INTADDR__)*/ 82 | NRF_TIMER_TASK_START = offsetof(NRF_TIMER_Type, TASKS_START), ///< Task for starting the timer. 83 | NRF_TIMER_TASK_STOP = offsetof(NRF_TIMER_Type, TASKS_STOP), ///< Task for stopping the timer. 84 | NRF_TIMER_TASK_COUNT = offsetof(NRF_TIMER_Type, TASKS_COUNT), ///< Task for incrementing the timer (in counter mode). 85 | NRF_TIMER_TASK_CLEAR = offsetof(NRF_TIMER_Type, TASKS_CLEAR), ///< Task for resetting the timer value. 86 | NRF_TIMER_TASK_SHUTDOWN = offsetof(NRF_TIMER_Type, TASKS_SHUTDOWN), ///< Task for powering off the timer. 87 | NRF_TIMER_TASK_CAPTURE0 = offsetof(NRF_TIMER_Type, TASKS_CAPTURE[0]), ///< Task for capturing the timer value on channel 0. 88 | NRF_TIMER_TASK_CAPTURE1 = offsetof(NRF_TIMER_Type, TASKS_CAPTURE[1]), ///< Task for capturing the timer value on channel 1. 89 | NRF_TIMER_TASK_CAPTURE2 = offsetof(NRF_TIMER_Type, TASKS_CAPTURE[2]), ///< Task for capturing the timer value on channel 2. 90 | NRF_TIMER_TASK_CAPTURE3 = offsetof(NRF_TIMER_Type, TASKS_CAPTURE[3]), ///< Task for capturing the timer value on channel 3. 91 | #ifdef NRF52 92 | NRF_TIMER_TASK_CAPTURE4 = offsetof(NRF_TIMER_Type, TASKS_CAPTURE[4]), ///< Task for capturing the timer value on channel 4. 93 | NRF_TIMER_TASK_CAPTURE5 = offsetof(NRF_TIMER_Type, TASKS_CAPTURE[5]), ///< Task for capturing the timer value on channel 5. 94 | #endif 95 | /*lint -restore*/ 96 | } nrf_timer_task_t; 97 | 98 | /** 99 | * @brief Timer events. 100 | */ 101 | typedef enum 102 | { 103 | /*lint -save -e30*/ 104 | NRF_TIMER_EVENT_COMPARE0 = offsetof(NRF_TIMER_Type, EVENTS_COMPARE[0]), ///< Event from compare channel 0. 105 | NRF_TIMER_EVENT_COMPARE1 = offsetof(NRF_TIMER_Type, EVENTS_COMPARE[1]), ///< Event from compare channel 1. 106 | NRF_TIMER_EVENT_COMPARE2 = offsetof(NRF_TIMER_Type, EVENTS_COMPARE[2]), ///< Event from compare channel 2. 107 | NRF_TIMER_EVENT_COMPARE3 = offsetof(NRF_TIMER_Type, EVENTS_COMPARE[3]), ///< Event from compare channel 3. 108 | #ifdef NRF52 109 | NRF_TIMER_EVENT_COMPARE4 = offsetof(NRF_TIMER_Type, EVENTS_COMPARE[4]), ///< Event from compare channel 4. 110 | NRF_TIMER_EVENT_COMPARE5 = offsetof(NRF_TIMER_Type, EVENTS_COMPARE[5]), ///< Event from compare channel 5. 111 | #endif 112 | /*lint -restore*/ 113 | } nrf_timer_event_t; 114 | 115 | /** 116 | * @brief Types of timer shortcuts. 117 | */ 118 | typedef enum 119 | { 120 | NRF_TIMER_SHORT_COMPARE0_STOP_MASK = TIMER_SHORTS_COMPARE0_STOP_Msk, ///< Shortcut for stopping the timer based on compare 0. 121 | NRF_TIMER_SHORT_COMPARE1_STOP_MASK = TIMER_SHORTS_COMPARE1_STOP_Msk, ///< Shortcut for stopping the timer based on compare 1. 122 | NRF_TIMER_SHORT_COMPARE2_STOP_MASK = TIMER_SHORTS_COMPARE2_STOP_Msk, ///< Shortcut for stopping the timer based on compare 2. 123 | NRF_TIMER_SHORT_COMPARE3_STOP_MASK = TIMER_SHORTS_COMPARE3_STOP_Msk, ///< Shortcut for stopping the timer based on compare 3. 124 | #ifdef NRF52 125 | NRF_TIMER_SHORT_COMPARE4_STOP_MASK = TIMER_SHORTS_COMPARE4_STOP_Msk, ///< Shortcut for stopping the timer based on compare 4. 126 | NRF_TIMER_SHORT_COMPARE5_STOP_MASK = TIMER_SHORTS_COMPARE5_STOP_Msk, ///< Shortcut for stopping the timer based on compare 5. 127 | #endif 128 | NRF_TIMER_SHORT_COMPARE0_CLEAR_MASK = TIMER_SHORTS_COMPARE0_CLEAR_Msk, ///< Shortcut for clearing the timer based on compare 0. 129 | NRF_TIMER_SHORT_COMPARE1_CLEAR_MASK = TIMER_SHORTS_COMPARE1_CLEAR_Msk, ///< Shortcut for clearing the timer based on compare 1. 130 | NRF_TIMER_SHORT_COMPARE2_CLEAR_MASK = TIMER_SHORTS_COMPARE2_CLEAR_Msk, ///< Shortcut for clearing the timer based on compare 2. 131 | NRF_TIMER_SHORT_COMPARE3_CLEAR_MASK = TIMER_SHORTS_COMPARE3_CLEAR_Msk, ///< Shortcut for clearing the timer based on compare 3. 132 | #ifdef NRF52 133 | NRF_TIMER_SHORT_COMPARE4_CLEAR_MASK = TIMER_SHORTS_COMPARE4_CLEAR_Msk, ///< Shortcut for clearing the timer based on compare 4. 134 | NRF_TIMER_SHORT_COMPARE5_CLEAR_MASK = TIMER_SHORTS_COMPARE5_CLEAR_Msk, ///< Shortcut for clearing the timer based on compare 5. 135 | #endif 136 | } nrf_timer_short_mask_t; 137 | 138 | /** 139 | * @brief Timer modes. 140 | */ 141 | typedef enum 142 | { 143 | NRF_TIMER_MODE_TIMER = TIMER_MODE_MODE_Timer, ///< Timer mode: timer. 144 | NRF_TIMER_MODE_COUNTER = TIMER_MODE_MODE_Counter, ///< Timer mode: counter. 145 | #ifdef NRF52 146 | NRF_TIMER_MODE_LOW_POWER_COUNTER = TIMER_MODE_MODE_LowPowerCounter, ///< Timer mode: low-power counter. 147 | #endif 148 | } nrf_timer_mode_t; 149 | 150 | /** 151 | * @brief Timer bit width. 152 | */ 153 | typedef enum 154 | { 155 | NRF_TIMER_BIT_WIDTH_8 = TIMER_BITMODE_BITMODE_08Bit, ///< Timer bit width 8 bit. 156 | NRF_TIMER_BIT_WIDTH_16 = TIMER_BITMODE_BITMODE_16Bit, ///< Timer bit width 16 bit. 157 | NRF_TIMER_BIT_WIDTH_24 = TIMER_BITMODE_BITMODE_24Bit, ///< Timer bit width 24 bit. 158 | NRF_TIMER_BIT_WIDTH_32 = TIMER_BITMODE_BITMODE_32Bit ///< Timer bit width 32 bit. 159 | } nrf_timer_bit_width_t; 160 | 161 | /** 162 | * @brief Timer prescalers. 163 | */ 164 | typedef enum 165 | { 166 | NRF_TIMER_FREQ_16MHz = 0, ///< Timer frequency 16 MHz. 167 | NRF_TIMER_FREQ_8MHz, ///< Timer frequency 8 MHz. 168 | NRF_TIMER_FREQ_4MHz, ///< Timer frequency 4 MHz. 169 | NRF_TIMER_FREQ_2MHz, ///< Timer frequency 2 MHz. 170 | NRF_TIMER_FREQ_1MHz, ///< Timer frequency 1 MHz. 171 | NRF_TIMER_FREQ_500kHz, ///< Timer frequency 500 kHz. 172 | NRF_TIMER_FREQ_250kHz, ///< Timer frequency 250 kHz. 173 | NRF_TIMER_FREQ_125kHz, ///< Timer frequency 125 kHz. 174 | NRF_TIMER_FREQ_62500Hz, ///< Timer frequency 62500 Hz. 175 | NRF_TIMER_FREQ_31250Hz ///< Timer frequency 31250 Hz. 176 | } nrf_timer_frequency_t; 177 | 178 | /** 179 | * @brief Timer capture/compare channels. 180 | */ 181 | typedef enum 182 | { 183 | NRF_TIMER_CC_CHANNEL0 = 0, ///< Timer capture/compare channel 0. 184 | NRF_TIMER_CC_CHANNEL1, ///< Timer capture/compare channel 1. 185 | NRF_TIMER_CC_CHANNEL2, ///< Timer capture/compare channel 2. 186 | NRF_TIMER_CC_CHANNEL3, ///< Timer capture/compare channel 3. 187 | #ifdef NRF52 188 | NRF_TIMER_CC_CHANNEL4, ///< Timer capture/compare channel 4. 189 | NRF_TIMER_CC_CHANNEL5, ///< Timer capture/compare channel 5. 190 | #endif 191 | } nrf_timer_cc_channel_t; 192 | 193 | /** 194 | * @brief Timer interrupts. 195 | */ 196 | typedef enum 197 | { 198 | NRF_TIMER_INT_COMPARE0_MASK = TIMER_INTENSET_COMPARE0_Msk, ///< Timer interrupt from compare event on channel 0. 199 | NRF_TIMER_INT_COMPARE1_MASK = TIMER_INTENSET_COMPARE1_Msk, ///< Timer interrupt from compare event on channel 1. 200 | NRF_TIMER_INT_COMPARE2_MASK = TIMER_INTENSET_COMPARE2_Msk, ///< Timer interrupt from compare event on channel 2. 201 | NRF_TIMER_INT_COMPARE3_MASK = TIMER_INTENSET_COMPARE3_Msk, ///< Timer interrupt from compare event on channel 3. 202 | #ifdef NRF52 203 | NRF_TIMER_INT_COMPARE4_MASK = TIMER_INTENSET_COMPARE4_Msk, ///< Timer interrupt from compare event on channel 4. 204 | NRF_TIMER_INT_COMPARE5_MASK = TIMER_INTENSET_COMPARE5_Msk, ///< Timer interrupt from compare event on channel 5. 205 | #endif 206 | } nrf_timer_int_mask_t; 207 | 208 | 209 | /** 210 | * @brief Function for activating a specific timer task. 211 | * 212 | * @param[in] p_timer Timer instance. 213 | * @param[in] task Task to activate. 214 | */ 215 | __STATIC_INLINE void nrf_timer_task_trigger(NRF_TIMER_Type * p_timer, 216 | nrf_timer_task_t task); 217 | 218 | /** 219 | * @brief Function for getting the address of a specific timer task register. 220 | * 221 | * @param[in] p_timer Timer instance. 222 | * @param[in] task Requested task. 223 | * 224 | * @return Address of the specified task register. 225 | */ 226 | __STATIC_INLINE uint32_t * nrf_timer_task_address_get(NRF_TIMER_Type * p_timer, 227 | nrf_timer_task_t task); 228 | 229 | /** 230 | * @brief Function for clearing a specific timer event. 231 | * 232 | * @param[in] p_timer Timer instance. 233 | * @param[in] event Event to clear. 234 | */ 235 | __STATIC_INLINE void nrf_timer_event_clear(NRF_TIMER_Type * p_timer, 236 | nrf_timer_event_t event); 237 | 238 | /** 239 | * @brief Function for checking the state of a specific timer event. 240 | * 241 | * @param[in] p_timer Timer instance. 242 | * @param[in] event Event to check. 243 | * 244 | * @retval true If the event is set. 245 | * @retval false If the event is not set. 246 | */ 247 | __STATIC_INLINE bool nrf_timer_event_check(NRF_TIMER_Type * p_timer, 248 | nrf_timer_event_t event); 249 | 250 | /** 251 | * @brief Function for getting the address of a specific timer event register. 252 | * 253 | * @param[in] p_timer Timer instance. 254 | * @param[in] event Requested event. 255 | * 256 | * @return Address of the specified event register. 257 | */ 258 | __STATIC_INLINE uint32_t * nrf_timer_event_address_get(NRF_TIMER_Type * p_timer, 259 | nrf_timer_event_t event); 260 | 261 | /** 262 | * @brief Function for enabling specified shortcuts. 263 | * 264 | * @param[in] p_timer Timer instance. 265 | * @param[in] timer_shorts_mask Shortcuts to enable. 266 | */ 267 | __STATIC_INLINE void nrf_timer_shorts_enable(NRF_TIMER_Type * p_timer, 268 | uint32_t timer_shorts_mask); 269 | 270 | /** 271 | * @brief Function for disabling specified shortcuts. 272 | * 273 | * @param[in] p_timer Timer instance. 274 | * @param[in] timer_shorts_mask Shortcuts to disable. 275 | */ 276 | __STATIC_INLINE void nrf_timer_shorts_disable(NRF_TIMER_Type * p_timer, 277 | uint32_t timer_shorts_mask); 278 | 279 | /** 280 | * @brief Function for enabling specified interrupts. 281 | * 282 | * @param[in] p_timer Timer instance. 283 | * @param[in] timer_int_mask Interrupts to enable. 284 | */ 285 | __STATIC_INLINE void nrf_timer_int_enable(NRF_TIMER_Type * p_timer, 286 | uint32_t timer_int_mask); 287 | 288 | /** 289 | * @brief Function for disabling specified interrupts. 290 | * 291 | * @param[in] p_timer Timer instance. 292 | * @param[in] timer_int_mask Interrupts to disable. 293 | */ 294 | __STATIC_INLINE void nrf_timer_int_disable(NRF_TIMER_Type * p_timer, 295 | uint32_t timer_int_mask); 296 | 297 | /** 298 | * @brief Function for retrieving the state of a given interrupt. 299 | * 300 | * @param[in] p_timer Timer instance. 301 | * @param[in] timer_int Interrupt to check. 302 | * 303 | * @retval true If the interrupt is enabled. 304 | * @retval false If the interrupt is not enabled. 305 | */ 306 | __STATIC_INLINE bool nrf_timer_int_enable_check(NRF_TIMER_Type * p_timer, 307 | uint32_t timer_int); 308 | 309 | /** 310 | * @brief Function for setting the timer mode. 311 | * 312 | * @param[in] p_timer Timer instance. 313 | * @param[in] mode Timer mode. 314 | */ 315 | __STATIC_INLINE void nrf_timer_mode_set(NRF_TIMER_Type * p_timer, 316 | nrf_timer_mode_t mode); 317 | 318 | /** 319 | * @brief Function for retrieving the timer mode. 320 | * 321 | * @param[in] p_timer Timer instance. 322 | * 323 | * @return Timer mode. 324 | */ 325 | __STATIC_INLINE nrf_timer_mode_t nrf_timer_mode_get(NRF_TIMER_Type * p_timer); 326 | 327 | /** 328 | * @brief Function for setting the timer bit width. 329 | * 330 | * @param[in] p_timer Timer instance. 331 | * @param[in] bit_width Timer bit width. 332 | */ 333 | __STATIC_INLINE void nrf_timer_bit_width_set(NRF_TIMER_Type * p_timer, 334 | nrf_timer_bit_width_t bit_width); 335 | 336 | /** 337 | * @brief Function for retrieving the timer bit width. 338 | * 339 | * @param[in] p_timer Timer instance. 340 | * 341 | * @return Timer bit width. 342 | */ 343 | __STATIC_INLINE nrf_timer_bit_width_t nrf_timer_bit_width_get(NRF_TIMER_Type * p_timer); 344 | 345 | /** 346 | * @brief Function for setting the timer frequency. 347 | * 348 | * @param[in] p_timer Timer instance. 349 | * @param[in] frequency Timer frequency. 350 | */ 351 | __STATIC_INLINE void nrf_timer_frequency_set(NRF_TIMER_Type * p_timer, 352 | nrf_timer_frequency_t frequency); 353 | 354 | /** 355 | * @brief Function for retrieving the timer frequency. 356 | * 357 | * @param[in] p_timer Timer instance. 358 | * 359 | * @return Timer frequency. 360 | */ 361 | __STATIC_INLINE nrf_timer_frequency_t nrf_timer_frequency_get(NRF_TIMER_Type * p_timer); 362 | 363 | /** 364 | * @brief Function for writing the capture/compare register for a specified channel. 365 | * 366 | * @param[in] p_timer Timer instance. 367 | * @param[in] cc_channel Requested capture/compare channel. 368 | * @param[in] cc_value Value to write to the capture/compare register. 369 | */ 370 | __STATIC_INLINE void nrf_timer_cc_write(NRF_TIMER_Type * p_timer, 371 | nrf_timer_cc_channel_t cc_channel, 372 | uint32_t cc_value); 373 | 374 | /** 375 | * @brief Function for retrieving the capture/compare value for a specified channel. 376 | * 377 | * @param[in] p_timer Timer instance. 378 | * @param[in] cc_channel Requested capture/compare channel. 379 | * 380 | * @return Value from the requested capture/compare register. 381 | */ 382 | __STATIC_INLINE uint32_t nrf_timer_cc_read(NRF_TIMER_Type * p_timer, 383 | nrf_timer_cc_channel_t cc_channel); 384 | 385 | /** 386 | * @brief Function for getting a specific timer capture task. 387 | * 388 | * @param[in] channel Capture channel. 389 | * 390 | * @return Capture task. 391 | */ 392 | __STATIC_INLINE nrf_timer_task_t nrf_timer_capture_task_get(uint32_t channel); 393 | 394 | /** 395 | * @brief Function for getting a specific timer compare event. 396 | * 397 | * @param[in] channel Compare channel. 398 | * 399 | * @return Compare event. 400 | */ 401 | __STATIC_INLINE nrf_timer_event_t nrf_timer_compare_event_get(uint32_t channel); 402 | 403 | /** 404 | * @brief Function for getting a specific timer compare interrupt. 405 | * 406 | * @param[in] channel Compare channel. 407 | * 408 | * @return Compare interrupt. 409 | */ 410 | __STATIC_INLINE nrf_timer_int_mask_t nrf_timer_compare_int_get(uint32_t channel); 411 | 412 | /** 413 | * @brief Function for calculating the number of timer ticks for a given time 414 | * (in microseconds) and timer frequency. 415 | * 416 | * @param[in] time_us Time in microseconds. 417 | * @param[in] frequency Timer frequency. 418 | * 419 | * @return Number of timer ticks. 420 | */ 421 | __STATIC_INLINE uint32_t nrf_timer_us_to_ticks(uint32_t time_us, 422 | nrf_timer_frequency_t frequency); 423 | 424 | /** 425 | * @brief Function for calculating the number of timer ticks for a given time 426 | * (in milliseconds) and timer frequency. 427 | * 428 | * @param[in] time_ms Time in milliseconds. 429 | * @param[in] frequency Timer frequency. 430 | * 431 | * @return Number of timer ticks. 432 | */ 433 | __STATIC_INLINE uint32_t nrf_timer_ms_to_ticks(uint32_t time_ms, 434 | nrf_timer_frequency_t frequency); 435 | 436 | 437 | #ifndef SUPPRESS_INLINE_IMPLEMENTATION 438 | 439 | __STATIC_INLINE void nrf_timer_task_trigger(NRF_TIMER_Type * p_timer, 440 | nrf_timer_task_t task) 441 | { 442 | *((volatile uint32_t *)((uint8_t *)p_timer + (uint32_t)task)) = 0x1UL; 443 | } 444 | 445 | __STATIC_INLINE uint32_t * nrf_timer_task_address_get(NRF_TIMER_Type * p_timer, 446 | nrf_timer_task_t task) 447 | { 448 | return (uint32_t *)((uint8_t *)p_timer + (uint32_t)task); 449 | } 450 | 451 | __STATIC_INLINE void nrf_timer_event_clear(NRF_TIMER_Type * p_timer, 452 | nrf_timer_event_t event) 453 | { 454 | *((volatile uint32_t *)((uint8_t *)p_timer + (uint32_t)event)) = 0x0UL; 455 | } 456 | 457 | __STATIC_INLINE bool nrf_timer_event_check(NRF_TIMER_Type * p_timer, 458 | nrf_timer_event_t event) 459 | { 460 | return (bool)*(volatile uint32_t *)((uint8_t *)p_timer + (uint32_t)event); 461 | } 462 | 463 | __STATIC_INLINE uint32_t * nrf_timer_event_address_get(NRF_TIMER_Type * p_timer, 464 | nrf_timer_event_t event) 465 | { 466 | return (uint32_t *)((uint8_t *)p_timer + (uint32_t)event); 467 | } 468 | 469 | __STATIC_INLINE void nrf_timer_shorts_enable(NRF_TIMER_Type * p_timer, 470 | uint32_t timer_shorts_mask) 471 | { 472 | p_timer->SHORTS |= timer_shorts_mask; 473 | } 474 | 475 | __STATIC_INLINE void nrf_timer_shorts_disable(NRF_TIMER_Type * p_timer, 476 | uint32_t timer_shorts_mask) 477 | { 478 | p_timer->SHORTS &= ~(timer_shorts_mask); 479 | } 480 | 481 | __STATIC_INLINE void nrf_timer_int_enable(NRF_TIMER_Type * p_timer, 482 | uint32_t timer_int_mask) 483 | { 484 | p_timer->INTENSET = timer_int_mask; 485 | } 486 | 487 | __STATIC_INLINE void nrf_timer_int_disable(NRF_TIMER_Type * p_timer, 488 | uint32_t timer_int_mask) 489 | { 490 | p_timer->INTENCLR = timer_int_mask; 491 | } 492 | 493 | __STATIC_INLINE bool nrf_timer_int_enable_check(NRF_TIMER_Type * p_timer, 494 | uint32_t timer_int) 495 | { 496 | return (bool)(p_timer->INTENSET & timer_int); 497 | } 498 | 499 | __STATIC_INLINE void nrf_timer_mode_set(NRF_TIMER_Type * p_timer, 500 | nrf_timer_mode_t mode) 501 | { 502 | p_timer->MODE = (p_timer->MODE & ~TIMER_MODE_MODE_Msk) | 503 | ((mode << TIMER_MODE_MODE_Pos) & TIMER_MODE_MODE_Msk); 504 | } 505 | 506 | __STATIC_INLINE nrf_timer_mode_t nrf_timer_mode_get(NRF_TIMER_Type * p_timer) 507 | { 508 | return (nrf_timer_mode_t)(p_timer->MODE); 509 | } 510 | 511 | __STATIC_INLINE void nrf_timer_bit_width_set(NRF_TIMER_Type * p_timer, 512 | nrf_timer_bit_width_t bit_width) 513 | { 514 | p_timer->BITMODE = (p_timer->BITMODE & ~TIMER_BITMODE_BITMODE_Msk) | 515 | ((bit_width << TIMER_BITMODE_BITMODE_Pos) & 516 | TIMER_BITMODE_BITMODE_Msk); 517 | } 518 | 519 | __STATIC_INLINE nrf_timer_bit_width_t nrf_timer_bit_width_get(NRF_TIMER_Type * p_timer) 520 | { 521 | return (nrf_timer_bit_width_t)(p_timer->BITMODE); 522 | } 523 | 524 | __STATIC_INLINE void nrf_timer_frequency_set(NRF_TIMER_Type * p_timer, 525 | nrf_timer_frequency_t frequency) 526 | { 527 | p_timer->PRESCALER = (p_timer->PRESCALER & ~TIMER_PRESCALER_PRESCALER_Msk) | 528 | ((frequency << TIMER_PRESCALER_PRESCALER_Pos) & 529 | TIMER_PRESCALER_PRESCALER_Msk); 530 | } 531 | 532 | __STATIC_INLINE nrf_timer_frequency_t nrf_timer_frequency_get(NRF_TIMER_Type * p_timer) 533 | { 534 | return (nrf_timer_frequency_t)(p_timer->PRESCALER); 535 | } 536 | 537 | __STATIC_INLINE void nrf_timer_cc_write(NRF_TIMER_Type * p_timer, 538 | nrf_timer_cc_channel_t cc_channel, 539 | uint32_t cc_value) 540 | { 541 | p_timer->CC[cc_channel] = cc_value; 542 | } 543 | 544 | __STATIC_INLINE uint32_t nrf_timer_cc_read(NRF_TIMER_Type * p_timer, 545 | nrf_timer_cc_channel_t cc_channel) 546 | { 547 | return (uint32_t)p_timer->CC[cc_channel]; 548 | } 549 | 550 | __STATIC_INLINE nrf_timer_task_t nrf_timer_capture_task_get(uint32_t channel) 551 | { 552 | return (nrf_timer_task_t) 553 | ((uint32_t)NRF_TIMER_TASK_CAPTURE0 + (channel * sizeof(uint32_t))); 554 | } 555 | 556 | __STATIC_INLINE nrf_timer_event_t nrf_timer_compare_event_get(uint32_t channel) 557 | { 558 | return (nrf_timer_event_t) 559 | ((uint32_t)NRF_TIMER_EVENT_COMPARE0 + (channel * sizeof(uint32_t))); 560 | } 561 | 562 | __STATIC_INLINE nrf_timer_int_mask_t nrf_timer_compare_int_get(uint32_t channel) 563 | { 564 | return (nrf_timer_int_mask_t) 565 | ((uint32_t)NRF_TIMER_INT_COMPARE0_MASK << channel); 566 | } 567 | 568 | __STATIC_INLINE uint32_t nrf_timer_us_to_ticks(uint32_t time_us, 569 | nrf_timer_frequency_t frequency) 570 | { 571 | // The "frequency" parameter here is actually the prescaler value, and the 572 | // timer runs at the following frequency: f = 16 MHz / 2^prescaler. 573 | uint32_t prescaler = (uint32_t)frequency; 574 | return ((time_us * 16UL) >> prescaler); 575 | } 576 | 577 | __STATIC_INLINE uint32_t nrf_timer_ms_to_ticks(uint32_t time_ms, 578 | nrf_timer_frequency_t frequency) 579 | { 580 | // The "frequency" parameter here is actually the prescaler value, and the 581 | // timer runs at the following frequency: f = 16000 kHz / 2^prescaler. 582 | uint32_t prescaler = (uint32_t)frequency; 583 | return ((time_ms * 16000UL) >> prescaler); 584 | } 585 | 586 | #endif // SUPPRESS_INLINE_IMPLEMENTATION 587 | 588 | #endif // NRF_TIMER_H__ 589 | 590 | /** @} */ 591 | -------------------------------------------------------------------------------- /photosensors.cpp: -------------------------------------------------------------------------------- 1 | #include "pinout.h" 2 | #include "ts4231.h" 3 | #include "photosensors.h" 4 | #include "firmware.h" 5 | 6 | #define light_timeout 500 // 500ms is a placeholder - system dependent 7 | 8 | 9 | TS4231 devices[] = { TS4231(sensors_e[0], sensors_d[0]), 10 | TS4231(sensors_e[1], sensors_d[1]), 11 | TS4231(sensors_e[2], sensors_d[2]), 12 | TS4231(sensors_e[3], sensors_d[3]) }; 13 | 14 | void photosensorSetup() { 15 | uint8_t config_result = -1; 16 | 17 | for (int i = 0; i < sensors_num; i++) { 18 | bool exit = 0; 19 | 20 | while (!exit) { 21 | DEBUG_PRINTLN(i); 22 | if (!devices[i].waitForLight(light_timeout)) { 23 | DEBUG_PRINTLN("TIMEOUT"); 24 | static bool state = 0; 25 | digitalWrite(LED_G, state = !state); // display problem 26 | continue; 27 | } 28 | 29 | DEBUG_PRINTLN("LD"); // Light Detected 30 | 31 | config_result = devices[i].configDevice(); 32 | 33 | switch (config_result) { 34 | case CONFIG_PASS: 35 | exit = 1; 36 | DEBUG_PRINTLN("OK"); 37 | break; 38 | case BUS_FAIL: 39 | // unable to resolve state of TS4231 (3 samples of the bus 40 | // signals resulted in 3 different states) 41 | exit = 1; 42 | DEBUG_PRINTLN("ERROR: BUS_FAIL"); 43 | break; 44 | case VERIFY_FAIL: 45 | // configuration read value did not match configuration write 46 | // value, run configuration again 47 | exit = 0; 48 | digitalWrite(LED_B, !digitalRead(LED_B)); // toggle 49 | DEBUG_PRINTLN("ERROR: VERIFY_FAIL"); 50 | break; 51 | case WATCH_FAIL: 52 | // verify succeeded but entry into WATCH mode failed, run 53 | // configuration again 54 | exit = 0; 55 | digitalWrite(LED_G, !digitalRead(LED_G)); // toggle 56 | DEBUG_PRINTLN("ERROR: WATCH_FAIL"); 57 | break; 58 | default: //value returned was unknown 59 | exit = 1; 60 | DEBUG_PRINTLN("ERROR: unknown value"); 61 | break; 62 | } 63 | } 64 | } 65 | 66 | if (config_result != CONFIG_PASS) { 67 | DEBUG_PRINTLN("TS4231 BUS_FAIL -> Let's assume we use the TS4112"); 68 | } 69 | 70 | // Turn off LED warnings (inverted logic) 71 | digitalWrite(LED_G, 1); 72 | digitalWrite(LED_B, 1); 73 | DEBUG_PRINTLN("EVERYTHING OK"); 74 | } 75 | 76 | -------------------------------------------------------------------------------- /photosensors.h: -------------------------------------------------------------------------------- 1 | #ifndef _PHOTOSENSORS_H_ 2 | #define _PHOTOSENSORS_H_ 3 | 4 | void photosensorSetup(); 5 | 6 | #endif // _PHOTOSENSORS_H_ 7 | -------------------------------------------------------------------------------- /pinout.h: -------------------------------------------------------------------------------- 1 | // This file adapts the pinout for the HiveTracker V1.0 2 | 3 | #ifndef _PINOUT_ 4 | #define _PINOUT_ 5 | 6 | // LEDs 7 | #define LED_R (10) 8 | #define LED_G (14) 9 | #define LED_B (12) 10 | #undef PIN_LED 11 | #define PIN_LED LED_G 12 | #define LED_BUILTIN PIN_LED 13 | #define BUILTIN_LED PIN_LED 14 | 15 | // Button 16 | #define BUTTON (26) 17 | 18 | // Serial 19 | #undef PIN_SERIAL_RX 20 | #undef PIN_SERIAL_TX 21 | #define PIN_SERIAL_RX (25) /* J4 - E */ 22 | #define PIN_SERIAL_TX (27) /* J4 - D */ 23 | 24 | // I2C 25 | #undef PIN_WIRE_SDA 26 | #undef PIN_WIRE_SCL 27 | #define PIN_WIRE_SDA (29) 28 | #define PIN_WIRE_SCL (28) 29 | 30 | // Photodiodes 31 | const int sensors_num = 4; // 0, 1, 2, 3 32 | const int sensors_e[] = {22, 18, 20, 19}; // Envelope line 33 | const int sensors_d[] = {24, 21, 4, 11}; // Data line - not used for now 34 | 35 | #endif // _PINOUT_ 36 | 37 | -------------------------------------------------------------------------------- /pulse.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "pulse.h" 3 | #include "PPI.h" 4 | #include "Timer.h" 5 | #include "photosensors.h" 6 | #include "firmware.h" 7 | #include "pinout.h" // important to keep it last for the undefs to work 8 | 9 | typedef struct { 10 | bool valid; 11 | bool skip; 12 | } sync_pulse_t; 13 | 14 | sync_pulse_t newPulse, oldPulse; 15 | 16 | TimerClass timer(2); 17 | 18 | 19 | // forward declarations (below order should help readability) 20 | void armSyncPulse(); 21 | void measureSyncPulse(); 22 | void readSyncPulse(sync_pulse_t &pulse); 23 | void armSweepPulse(); 24 | void measureSweepPulse(); 25 | bool allAreHigh(); 26 | 27 | 28 | 29 | static void defaultFunc() {}; 30 | static funcPtr_t dataTXcallback; 31 | 32 | void pulseSetup(funcPtr_t callback) { 33 | 34 | dataTXcallback = (callback) ? callback : defaultFunc; 35 | 36 | photosensorSetup(); 37 | 38 | // start timers, they will be sync'ed (reset) in PPI 39 | nrf_timer_task_trigger(nrf_timers[syncTimer], NRF_TIMER_TASK_START); 40 | nrf_timer_task_trigger(nrf_timers[forkTimer], NRF_TIMER_TASK_START); 41 | 42 | armSyncPulse(); 43 | } 44 | 45 | 46 | void armSyncPulse() { 47 | PPI.resetChannels(); 48 | 49 | // Clear old measures in case of missed signal: 50 | for (int i = 0; i < sensors_num; i++) { 51 | nrf_timer_cc_write(nrf_timers[syncTimer], 52 | nrf_timer_cc_channel_t(i), 0); 53 | nrf_timer_cc_write(nrf_timers[forkTimer], 54 | nrf_timer_cc_channel_t(i), 0); 55 | } 56 | 57 | PPI.setTimer(syncTimer); 58 | 59 | // sync timers using all photodiodes 60 | for (int i = 0; i < sensors_num; i++) { 61 | PPI.setInputPin(sensors_e[i]); 62 | 63 | // clear both timers using all photodiodes... 64 | PPI.setShortcut(PIN_LOW, TIMER_CLEAR, forkTimer); 65 | 66 | // ...and capture pulse widths on timer 1 67 | PPI.setShortcut(PIN_HIGH, TIMER_CAPTURE); 68 | } 69 | 70 | // Active wait till the end of sync pulses of multiple photodiodes 71 | while (allAreHigh()); // wait till we get low 72 | while (!allAreHigh()); // wait till we get high 73 | 74 | measureSyncPulse(); 75 | } 76 | 77 | 78 | bool allAreHigh() { 79 | // TODO: timer or GPIO interrupt should work with the right priority: 80 | // https://github.com/HiveTracker/firmware/blob/2afe9f1/Timer.cpp#L25-L30 81 | // https://github.com/HiveTracker/PPI/commit/d3a54ad 82 | 83 | // photodiodes are high by default (low when light is detected) 84 | bool allHigh = digitalRead(sensors_e[0]) & digitalRead(sensors_e[1]) & 85 | digitalRead(sensors_e[2]) & digitalRead(sensors_e[3]); 86 | return allHigh; 87 | } 88 | 89 | 90 | 91 | void measureSyncPulse() { 92 | PPI.resetChannels(); 93 | 94 | readSyncPulse(newPulse); 95 | 96 | if (newPulse.valid && !newPulse.skip) { 97 | // if old pulse is valid then the emitting base is B 98 | pulse_data.baseID = oldPulse.valid; // 0 = A - B = 1 99 | oldPulse.valid = false; 100 | armSweepPulse(); 101 | } else { 102 | // otherwise try again 103 | oldPulse = newPulse; 104 | armSyncPulse(); // TODO implement a fail counter 105 | } 106 | } 107 | 108 | 109 | void readSyncPulse(sync_pulse_t &pulse) { 110 | for (int i = 0; i < sensors_num; i++) { 111 | pulse_data.pulse_captures[i] = 112 | nrf_timer_cc_read(nrf_timers[syncTimer], 113 | nrf_timer_cc_channel_t(i)); 114 | 115 | // Look for at least 1 valid pulse TODO: make it smarter!!! 116 | int pulseWidthTicks16 = pulse_data.pulse_captures[i]; // 16 MHz 117 | 118 | if ( pulseWidthTicks16 > minSyncPulseWidth && // ticks 119 | pulseWidthTicks16 < maxSyncPulseWidth ) { // ticks 120 | 121 | float pulseWidthTicks48 = pulseWidthTicks16 * 3; // convert to 48MHz ticks 122 | 123 | // for the following calculation, consult "Sync pulse timings" in .h file 124 | pulse_data.axis = (int(round(pulseWidthTicks48 / 500.)) % 2); 125 | 126 | pulse.skip = (pulse_data.pulse_captures[i] > skipThreshold); // 100us to ticks 127 | 128 | pulse.valid = true; 129 | break; 130 | } 131 | } 132 | } 133 | 134 | 135 | // Time stamp both rising and falling edges for the 4 photodiodes 136 | // Timer S: sensor 0: channels: 0, 1 captures: 0, 1 (rising, falling edge) 137 | // sensor 1: channels: 2, 3 captures: 2, 3 (rising, falling edge) 138 | // Timer F: sensor 2: channels: 0, 1 captures: 4, 5 (rising, falling edge) 139 | // sensor 3: channels: 2, 3 captures: 6, 7 (rising, falling edge) 140 | void armSweepPulse() { 141 | PPI.resetChannels(); 142 | 143 | for (int i = 0; i < sensors_num; i++) { 144 | PPI.setTimer(timerNumbers[i/2]); // sync & fork timers 145 | 146 | PPI.setInputPin(sensors_e[i]); // diode 0 to 3 147 | PPI.setShortcut(PIN_LOW, TIMER_CAPTURE); // channel i*2 148 | PPI.setShortcut(PIN_HIGH, TIMER_CAPTURE); // channel i*2 + 1 149 | } 150 | 151 | // compute data collection time by removing the base offset 152 | int collectionTime = sweepEndTime; 153 | if (pulse_data.baseID == 1) 154 | collectionTime -= interSyncOffset; // microsec 155 | 156 | timer.attachInterrupt(&measureSweepPulse, collectionTime); 157 | } 158 | 159 | 160 | void measureSweepPulse() { 161 | // Timers S and F, on 4 channels (0 to 3) 162 | for (int t = 0; t < 2; t++) { 163 | for (int c = 0; c < sensors_num; c++) { 164 | pulse_data.sweep_captures[t][c] = nrf_timer_cc_read(nrf_timers[timerNumbers[t]], 165 | nrf_timer_cc_channel_t(c)); 166 | } 167 | } 168 | 169 | // If CPU is sleeping most of the time, then it's probably OK to call it from an interrupt: 170 | // dataTXcallback(); 171 | // otherwise, let's poll the follwing flag in the main loop: 172 | pulse_data.isReady = true; 173 | armSyncPulse(); // prepare for next loop 174 | } 175 | 176 | 177 | bool pulseDataIsReady() { 178 | if (pulse_data.isReady) { 179 | pulse_data.isReady = false; 180 | return true; 181 | } else { 182 | return false; 183 | } 184 | } 185 | 186 | 187 | pulse_data_t pulse_data; 188 | 189 | -------------------------------------------------------------------------------- /pulse.h: -------------------------------------------------------------------------------- 1 | #ifndef PULSE_H 2 | #define PULSE_H 3 | 4 | #include 5 | 6 | 7 | typedef struct { 8 | int pulse_captures[4] = {{0}}; 9 | int sweep_captures[2][4] = {{0}}; // 2 timers, 4 channels 10 | bool baseID; 11 | bool axis; // 0 horizontal (x), 1 vertical (y) - TODO: check it! 12 | bool isReady; 13 | } pulse_data_t; 14 | 15 | const int syncTimer = 3; 16 | const int forkTimer = 4; 17 | 18 | const int timerNumbers[] = {syncTimer, forkTimer}; 19 | 20 | const int ticksPerMicrosec = 16; // because 16MHz 21 | 22 | const int margin = 10; // microsec 23 | const int minSyncPulseWidth = (62.5 - margin) * ticksPerMicrosec; 24 | const int maxSyncPulseWidth = (135 + margin) * ticksPerMicrosec; 25 | const int skipThreshold = ((104 + ceil(93.8)) / 2) * ticksPerMicrosec; 26 | 27 | const int interSyncOffset = 400; // microsec 28 | 29 | 30 | /* Sync pulse timings - a 10us margins is good practice 31 | j0 0 0 0 3000 62.5 32 | k0 0 0 1 3500 72.9 33 | j1 0 1 0 4000 83.3 34 | k1 0 1 1 4500 93.8 35 | j2 1 0 0 5000 104 36 | k2 1 0 1 5500 115 37 | j3 1 1 0 6000 125 38 | k3 1 1 1 6500 135 39 | */ 40 | 41 | const int minSweepPulseWidth = 1 * ticksPerMicrosec; 42 | const int maxSweepPulseWidth = 35 * ticksPerMicrosec; 43 | 44 | const int sweepStartTime = 1222 - margin; // microsec 45 | const int sweepEndTime = 6777 + margin; // microsec 46 | 47 | const int sweepStartTicks = sweepStartTime * ticksPerMicrosec; 48 | const int sweepEndTicks = sweepEndTime * ticksPerMicrosec; 49 | 50 | typedef void (*funcPtr_t)(); 51 | void pulseSetup(funcPtr_t callback); 52 | 53 | bool pulseDataIsReady(); 54 | 55 | 56 | extern pulse_data_t pulse_data; 57 | 58 | #endif // PULSE_H 59 | -------------------------------------------------------------------------------- /reception/reception.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/python 2 | 3 | import glob 4 | import serial 5 | import sys 6 | import platform 7 | 8 | DEBUG_PRINT = 0 9 | 10 | 11 | ############################################################################### 12 | def main(): 13 | port = serial_init() 14 | while True: 15 | # base = 0 or 1 (B or C) 16 | # axis = 0 or 1 (horizontal or vertical) 17 | # centroids = array of 4 floats in microseconds 18 | base, axis, centroids = parse_data(port) 19 | 20 | if not DEBUG_PRINT: 21 | print( base, axis, centroids ) 22 | 23 | 24 | ############################################################################### 25 | def serial_init(): 26 | PLATFORM = platform.system() 27 | if "Linux" in PLATFORM: 28 | SERIAL_PATH = "/dev/ttyUSB*" 29 | elif "Darwin" in PLATFORM: 30 | SERIAL_PATH = "/dev/tty.usb*" # TODO: test it 31 | else: # Windows 32 | SERIAL_PATH = "COM*" # TODO: test it 33 | 34 | devices = glob.glob(SERIAL_PATH) 35 | 36 | if DEBUG_PRINT: print(devices) 37 | port = serial.Serial(devices[0], 115200 * 2) 38 | success = port.isOpen() 39 | 40 | if success: 41 | if DEBUG_PRINT: print("Port open.") 42 | lookForHeader(port) 43 | else: 44 | print("\n!!! Error: serial device not found !!!") 45 | exit(-1) 46 | return port 47 | 48 | 49 | ############################################################################### 50 | def lookForHeader(port): 51 | if DEBUG_PRINT: print("seeking header\n") 52 | 53 | # packets structure: 54 | # 2 headers + 1 base_axis + (4 photodiodes * 2 bytes) + (3 accel * 2 bytes) 55 | 56 | while True: 57 | 58 | while readByte(port) != 255: 59 | pass # consume 60 | 61 | if readByte(port) != 255: 62 | continue 63 | 64 | break 65 | 66 | 67 | ############################################################################### 68 | def readByte(port): 69 | byte = ord(port.read(1)) 70 | if DEBUG_PRINT: print(byte) 71 | return byte 72 | 73 | 74 | ############################################################################### 75 | def parse_data(port): 76 | centroidNum = 4 77 | 78 | base_axis = readByte(port) 79 | base = (base_axis >> 1) & 1 80 | axis = (base_axis >> 0) & 1 81 | 82 | if DEBUG_PRINT: print("\nbase, axis:", base, axis) 83 | 84 | centroids = [0 for i in range(centroidNum)] 85 | 86 | for i in range(centroidNum): 87 | centroids[i] = getCentroid(port) 88 | if DEBUG_PRINT: print("centroids[", i, "] =", centroids[i]) 89 | 90 | # consumes header 91 | for i in range(2): 92 | b = readByte(port) 93 | if (b != 255): 94 | if DEBUG_PRINT: print("header problem", i) 95 | lookForHeader(port) 96 | break 97 | 98 | return base, axis, centroids 99 | 100 | 101 | ############################################################################### 102 | def getCentroid(port): 103 | rxl = readByte(port) # LSB first 104 | rxh = readByte(port) # MSB last 105 | time = (rxh << 8) + rxl # reconstruct packets 106 | time <<= 2 # (non-significantly lossy) decompression 107 | time /= 16. # convert to us 108 | 109 | if (time >= 6777 or time < 1222): 110 | print(" >>> INVALID TIME:", str(time)) 111 | time = 0 112 | 113 | return time 114 | 115 | 116 | 117 | ############################################################################### 118 | if __name__ == "__main__": 119 | main() 120 | 121 | -------------------------------------------------------------------------------- /ts4231.cpp: -------------------------------------------------------------------------------- 1 | /******************************************************************* 2 | Copyright (C) 2017 Triad Semiconductor 3 | 4 | ts4231.h - Library for configuring the Triad Semiconductor TS4231 Light 5 | to Digital converter. 6 | Created by: John Seibel 7 | *******************************************************************/ 8 | 9 | #include "ts4231.h" 10 | #include 11 | 12 | //IMPORTANT NOTES: 13 | //1) If porting the TS4231 library code to a non-Arduino architecture, 14 | // be sure that the INPUT ports assigned to the E and D signals are configured as 15 | // floating inputs with NO pull-up or pull-down function. Using a pull-up or 16 | // pull-down function on the inputs will cause the TS4231 to operate incorrectly. 17 | //2) The TS4231 library omits delays between E and D signal transitions when going 18 | // from S3_STATE to WATCH_STATE or SLEEP_STATE to WATCH_STATE in function 19 | // goToWatch() for the purpose of transitioning into WATCH_STATE as quickly as 20 | // possible. If a microcontroller is being used that can change states on 21 | // the E and D outputs faster than approximately 100ns, the TS4231 datasheet 22 | // must be consulted to verify timing parameters are not being violated to 23 | // assure proper TS4231 operation. A suitable solution would be to include 24 | // a short delay in function ts_digitalWrite() to allow enough time between 25 | // output pin signal changes to meet the TS4231 timing parameters as stated 26 | // in the datasheet. See the ts_digitalWrite() function for more information. 27 | 28 | TS4231::TS4231(int device_E_pin, int device_D_pin) { 29 | configured = false; 30 | E_pin = device_E_pin; 31 | D_pin = device_D_pin; 32 | ts_pinMode(E_pin, INPUT); 33 | ts_pinMode(D_pin, INPUT); 34 | } 35 | 36 | void TS4231::ts_delayUs(unsigned int delay_val) { 37 | delayMicroseconds(delay_val); 38 | } 39 | 40 | void TS4231::ts_pinMode(int pin, uint8_t mode) { 41 | pinMode(pin, mode); 42 | } 43 | 44 | uint8_t TS4231::ts_digitalRead(int pin) { 45 | uint8_t read_val; 46 | 47 | read_val = digitalRead(pin); 48 | return read_val; 49 | } 50 | 51 | void TS4231::ts_digitalWrite(int pin, uint8_t write_val) { 52 | digitalWrite(pin, write_val); 53 | //A short delay function can be inserted here to extend the time between writes to 54 | //the E and D outputs if TS4231 timing parameters are being violated. Consult 55 | //the TS4231 datasheet for more information on timing parameters. It is recommended 56 | //that any added delay be no longer than approximately 1us. 57 | delayMicroseconds(1); 58 | } 59 | 60 | unsigned long TS4231::ts_millis() { 61 | unsigned long current_time; 62 | 63 | current_time = millis(); 64 | return current_time; 65 | } 66 | 67 | //Function waitForLight() should be executed after power-up and prior to 68 | //configuring the device. Upon power-up, D is a 0 and will output a 1 69 | //when light is detected. D will return to 0 at the end of light detection. 70 | //This funciton looks for the falling edge of D to indicate that the end of 71 | //light detection has occurred. 72 | bool TS4231::waitForLight(uint16_t light_timeout) { 73 | bool light = false; 74 | bool exit = false; 75 | unsigned long time0; 76 | 77 | if (checkBus() == S0_STATE) { 78 | time0 = ts_millis(); 79 | while (exit == false) { 80 | if (ts_digitalRead(D_pin) > 0) { 81 | while (exit == false) { 82 | if (ts_digitalRead(D_pin) == 0) { 83 | exit = true; 84 | light = true; 85 | } 86 | else if (ts_millis() > (time0 + light_timeout)) { 87 | exit = true; 88 | light = false; 89 | } 90 | else { 91 | exit = false; 92 | light = false; 93 | } 94 | } 95 | } 96 | else if (ts_millis() > (time0 + light_timeout)) { 97 | exit = true; 98 | light = false; 99 | } 100 | else { 101 | exit = false; 102 | light = false; 103 | } 104 | } 105 | } 106 | else light = true; //if not in state S0_state, light has already been detected 107 | return light; 108 | } 109 | 110 | bool TS4231::goToSleep(void) { 111 | bool sleep_success; 112 | 113 | if (configured == false) sleep_success = false; 114 | else { 115 | switch (checkBus()) { 116 | case S0_STATE: 117 | sleep_success = false; 118 | break; 119 | case SLEEP_STATE: 120 | sleep_success = true; 121 | break; 122 | case WATCH_STATE: 123 | ts_digitalWrite(E_pin, LOW); 124 | ts_pinMode(E_pin, OUTPUT); 125 | ts_delayUs(BUS_DRV_DLY); 126 | ts_pinMode(E_pin, INPUT); 127 | ts_delayUs(BUS_DRV_DLY); 128 | if (checkBus() == SLEEP_STATE) sleep_success = true; 129 | else sleep_success = false; 130 | break; 131 | case S3_STATE: 132 | sleep_success = false; 133 | break; 134 | default: 135 | sleep_success = false; 136 | break; 137 | } 138 | } 139 | return sleep_success; 140 | } 141 | 142 | 143 | uint8_t TS4231::configDevice(uint16_t config_val) { 144 | uint8_t config_success = 0x00; 145 | uint16_t readback; 146 | 147 | configured = false; 148 | ts_pinMode(D_pin, INPUT); 149 | ts_pinMode(E_pin, INPUT); 150 | ts_digitalWrite(D_pin, LOW); 151 | ts_digitalWrite(E_pin, LOW); 152 | ts_pinMode(E_pin, OUTPUT); 153 | ts_delayUs(BUS_DRV_DLY); 154 | ts_digitalWrite(E_pin, HIGH); 155 | ts_delayUs(BUS_DRV_DLY); 156 | ts_digitalWrite(E_pin, LOW); 157 | ts_delayUs(BUS_DRV_DLY); 158 | ts_digitalWrite(E_pin, HIGH); 159 | ts_delayUs(BUS_DRV_DLY); 160 | ts_pinMode(D_pin, OUTPUT); 161 | ts_delayUs(BUS_DRV_DLY); 162 | ts_digitalWrite(D_pin, HIGH); 163 | ts_delayUs(BUS_DRV_DLY); 164 | ts_pinMode(E_pin, INPUT); 165 | ts_pinMode(D_pin, INPUT); 166 | if (checkBus() == S3_STATE) { 167 | writeConfig(config_val); 168 | readback = readConfig(); 169 | if (readback == config_val) { 170 | configured = true; 171 | if (goToWatch()) config_success = CONFIG_PASS; 172 | else config_success = WATCH_FAIL; 173 | } 174 | else config_success = VERIFY_FAIL; 175 | } 176 | else config_success = BUS_FAIL; 177 | 178 | return config_success; 179 | } 180 | 181 | void TS4231::writeConfig(uint16_t config_val) { 182 | ts_digitalWrite(E_pin, HIGH); 183 | ts_digitalWrite(D_pin, HIGH); 184 | ts_pinMode(E_pin, OUTPUT); 185 | ts_pinMode(D_pin, OUTPUT); 186 | ts_delayUs(BUS_DRV_DLY); 187 | ts_digitalWrite(D_pin, LOW); 188 | ts_delayUs(BUS_DRV_DLY); 189 | ts_digitalWrite(E_pin, LOW); 190 | ts_delayUs(BUS_DRV_DLY); 191 | for (uint8_t i = 0; i < 15; i++) { 192 | config_val = config_val << 1; 193 | if ((config_val & 0x8000) > 0) ts_digitalWrite(D_pin, HIGH); 194 | else ts_digitalWrite(D_pin, LOW); 195 | ts_delayUs(BUS_DRV_DLY); 196 | ts_digitalWrite(E_pin, HIGH); 197 | ts_delayUs(BUS_DRV_DLY); 198 | ts_digitalWrite(E_pin, LOW); 199 | ts_delayUs(BUS_DRV_DLY); 200 | } 201 | ts_digitalWrite(D_pin, LOW); 202 | ts_delayUs(BUS_DRV_DLY); 203 | ts_digitalWrite(E_pin, HIGH); 204 | ts_delayUs(BUS_DRV_DLY); 205 | ts_digitalWrite(D_pin, HIGH); 206 | ts_delayUs(BUS_DRV_DLY); 207 | ts_pinMode(E_pin, INPUT); 208 | ts_pinMode(D_pin, INPUT); 209 | } 210 | 211 | uint16_t TS4231::readConfig(void) { 212 | uint16_t readback; 213 | 214 | readback = 0x0000; 215 | ts_digitalWrite(E_pin, HIGH); 216 | ts_digitalWrite(D_pin, HIGH); 217 | ts_pinMode(E_pin, OUTPUT); 218 | ts_pinMode(D_pin, OUTPUT); 219 | ts_delayUs(BUS_DRV_DLY); 220 | ts_digitalWrite(D_pin, LOW); 221 | ts_delayUs(BUS_DRV_DLY); 222 | ts_digitalWrite(E_pin, LOW); 223 | ts_delayUs(BUS_DRV_DLY); 224 | ts_digitalWrite(D_pin, HIGH); 225 | ts_delayUs(BUS_DRV_DLY); 226 | ts_digitalWrite(E_pin, HIGH); 227 | ts_delayUs(BUS_DRV_DLY); 228 | ts_pinMode(D_pin, INPUT); 229 | ts_delayUs(BUS_DRV_DLY); 230 | ts_digitalWrite(E_pin, LOW); 231 | ts_delayUs(BUS_DRV_DLY); 232 | for (uint8_t i = 0; i < 14; i++) { 233 | ts_digitalWrite(E_pin, HIGH); 234 | ts_delayUs(BUS_DRV_DLY); 235 | readback = (readback << 1) | (ts_digitalRead(D_pin) & 0x0001); 236 | ts_digitalWrite(E_pin, LOW); 237 | ts_delayUs(BUS_DRV_DLY); 238 | } 239 | ts_digitalWrite(D_pin, LOW); 240 | ts_pinMode(D_pin, OUTPUT); 241 | ts_delayUs(BUS_DRV_DLY); 242 | ts_digitalWrite(E_pin, HIGH); 243 | ts_delayUs(BUS_DRV_DLY); 244 | ts_digitalWrite(D_pin, HIGH); 245 | ts_delayUs(BUS_DRV_DLY); 246 | ts_pinMode(E_pin, INPUT); 247 | ts_pinMode(D_pin, INPUT); 248 | return readback; 249 | } 250 | 251 | //checkBus() performs a voting function where the bus is sampled 3 times 252 | //to find 2 identical results. This is necessary since light detection is 253 | //asynchronous and can indicate a false state. 254 | uint8_t TS4231::checkBus(void) { 255 | uint8_t state; 256 | uint8_t E_state; 257 | uint8_t D_state; 258 | uint8_t S0_count = 0; 259 | uint8_t SLEEP_count = 0; 260 | uint8_t WATCH_count = 0; 261 | uint8_t S3_count = 0; 262 | 263 | for (uint8_t i=0; i<3; i++) { 264 | E_state = ts_digitalRead(E_pin); 265 | D_state = ts_digitalRead(D_pin); 266 | if (D_state == HIGH) { 267 | if (E_state == HIGH) S3_count++; 268 | else SLEEP_count++; 269 | } 270 | else { 271 | if (E_state == HIGH) WATCH_count++; 272 | else S0_count++; 273 | } 274 | ts_delayUs(BUS_CHECK_DLY); 275 | } 276 | if (SLEEP_count >= 2) state = SLEEP_STATE; 277 | else if (WATCH_count >= 2) state = WATCH_STATE; 278 | else if (S3_count >= 2) state = S3_STATE; 279 | else if (S0_count >= 2) state = S0_STATE; 280 | else state = UNKNOWN_STATE; 281 | 282 | return state; 283 | } 284 | 285 | bool TS4231::goToWatch(void) { 286 | bool watch_success; 287 | 288 | if (configured == false) watch_success = false; 289 | else { 290 | switch (checkBus()) { 291 | case S0_STATE: 292 | watch_success = false; 293 | break; 294 | case SLEEP_STATE: 295 | ts_digitalWrite(D_pin, HIGH); 296 | ts_pinMode(D_pin, OUTPUT); 297 | ts_digitalWrite(E_pin, LOW); 298 | ts_pinMode(E_pin, OUTPUT); 299 | ts_digitalWrite(D_pin, LOW); 300 | ts_pinMode(D_pin, INPUT); 301 | ts_digitalWrite(E_pin, HIGH); 302 | ts_pinMode(E_pin, INPUT); 303 | ts_delayUs(SLEEP_RECOVERY); 304 | if (checkBus() == WATCH_STATE) watch_success = true; 305 | else watch_success = false; 306 | break; 307 | case WATCH_STATE: 308 | watch_success = true; 309 | break; 310 | case S3_STATE: 311 | ts_digitalWrite(E_pin, HIGH); 312 | ts_pinMode(E_pin, OUTPUT); 313 | ts_digitalWrite(D_pin, HIGH); 314 | ts_pinMode(D_pin, OUTPUT); 315 | ts_digitalWrite(E_pin, LOW); 316 | ts_digitalWrite(D_pin, LOW); 317 | ts_pinMode(D_pin, INPUT); 318 | ts_digitalWrite(E_pin, HIGH); 319 | ts_pinMode(E_pin, INPUT); 320 | ts_delayUs(SLEEP_RECOVERY); 321 | if (checkBus() == WATCH_STATE) watch_success = true; 322 | else watch_success = false; 323 | break; 324 | default: 325 | watch_success = false; 326 | break; 327 | } 328 | } 329 | return watch_success; 330 | } 331 | -------------------------------------------------------------------------------- /ts4231.h: -------------------------------------------------------------------------------- 1 | /******************************************************************* 2 | Copyright (C) 2017 Triad Semiconductor 3 | 4 | ts4231.h - Library for configuring the Triad Semiconductor TS4231 Light 5 | to Digital converter. 6 | Created by: John Seibel 7 | *******************************************************************/ 8 | 9 | #ifndef ts4231_h 10 | #define ts4231_h 11 | 12 | #include 13 | 14 | #define BUS_DRV_DLY 1 //delay in microseconds between bus level changes 15 | #define BUS_CHECK_DLY 500 //delay in microseconds for the checkBus() function 16 | #define SLEEP_RECOVERY 100 //delay in microseconds for analog wake-up after exiting SLEEP mode 17 | #define UNKNOWN_STATE 0x04 //checkBus() function state 18 | #define S3_STATE 0x03 //checkBus() function state 19 | #define WATCH_STATE 0x02 //checkBus() function state 20 | #define SLEEP_STATE 0x01 //checkBus() function state 21 | #define S0_STATE 0x00 //checkBus() function state 22 | #define CFG_WORD 0x392B //configuration value 23 | #define BUS_FAIL 0x01 //configDevice() function status return value 24 | #define VERIFY_FAIL 0x02 //configDevice() function status return value 25 | #define WATCH_FAIL 0x03 //configDevice() function status return value 26 | #define CONFIG_PASS 0x04 //configDevice() function status return value 27 | 28 | class TS4231 { 29 | 30 | public: 31 | TS4231(int device_E_pin, int device_D_pin); 32 | bool waitForLight(uint16_t light_timeout); //timeout in milliseconds 33 | bool goToSleep(void); 34 | uint8_t configDevice(uint16_t config_val = CFG_WORD); 35 | bool goToWatch(void); 36 | 37 | private: 38 | uint8_t checkBus(void); 39 | void ts_delayUs(unsigned int delay_val); //delay in microseconds 40 | void ts_pinMode(int pin, uint8_t mode); 41 | uint8_t ts_digitalRead(int pin); 42 | void ts_digitalWrite(int pin, uint8_t write_val); 43 | unsigned long ts_millis(void); 44 | void writeConfig(uint16_t config_val); 45 | uint16_t readConfig(void); 46 | int E_pin; 47 | int D_pin; 48 | bool configured; 49 | }; 50 | 51 | #endif 52 | --------------------------------------------------------------------------------