spi_master for AVR (#8299)

* Change _delay_ms/us() to wait_ms/us()

* Switch to platform-agnostic GPIO macros

* Add AVR spi_master and migrate Adafruit BLE code

* Set verbose back to false

* Add clock divisor, bit order and SPI mode configuration for init

* Add start and stop functions

* Move configuration of mode, endianness and speed to `spi_start()`

* Some breaks here would be good

* Default Adafruit BLE clock divisor to 4 (2MHz on the Feather 32U4)

* Remove mode and divisor enums

* Add some docs

* No hr at EOF

* Add links in sidebar
This commit is contained in:
Ryan 2020-04-08 11:04:31 +10:00 committed by GitHub
parent e409fb47f2
commit 400ca2d035
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
14 changed files with 397 additions and 125 deletions

View File

@ -121,6 +121,7 @@
* [Drivers](hardware_drivers.md)
* [ADC Driver](adc_driver.md)
* [I2C Driver](i2c_driver.md)
* [SPI Driver](spi_driver.md)
* [WS2812 Driver](ws2812_driver.md)
* [EEPROM Driver](eeprom_driver.md)
* [GPIO Controls](internals_gpio_control.md)

View File

@ -98,6 +98,7 @@
* [ISP Flashing Guide](de/isp_flashing_guide.md)
* [ARM Debugging Guide](de/arm_debugging.md)
* [I2C Driver](de/i2c_driver.md)
* [SPI Driver](de/spi_driver.md)
* [GPIO Controls](de/internals_gpio_control.md)
* [Proton C Conversion](de/proton_c_conversion.md)

View File

@ -98,6 +98,7 @@
* [Guía de flasheado de ISP](es/isp_flashing_guide.md)
* [Guía de depuración de ARM](es/arm_debugging.md)
* [Driver I2C](es/i2c_driver.md)
* [Driver SPI](es/spi_driver.md)
* [Controles GPIO](es/internals_gpio_control.md)
* [Conversión Proton C](es/proton_c_conversion.md)

View File

@ -101,7 +101,8 @@
* [Guide des claviers soudés à la main](fr-fr/hand_wire.md)
* [Guide de flash de lISP](fr-fr/isp_flashing_guide.md)
* [Guide du débogage ARM](fr-fr/arm_debugging.md)
* [Drivers i2c](fr-fr/i2c_driver.md)
* [Drivers I2C](fr-fr/i2c_driver.md)
* [Drivers SPI](fr-fr/spi_driver.md)
* [Contrôles des GPIO](fr-fr/internals_gpio_control.md)
* [Conversion en Proton C](fr-fr/proton_c_conversion.md)

View File

@ -114,6 +114,7 @@
* [מדריך לצריבת ISP](he-il/isp_flashing_guide.md)
* [מדריך לדיבאגינג ARM](he-il/arm_debugging.md)
* [מנהל התקן I2C](he-il/i2c_driver.md)
* [מנהל התקן SPI](he-il/spi_driver.md)
* [בקרת GPIO](he-il/internals_gpio_control.md)
* [המרת Proton C](he-il/proton_c_conversion.md)

View File

@ -121,6 +121,7 @@
* [ドライバ](ja/hardware_drivers.md)
* [ADC ドライバ](ja/adc_driver.md)
* [I2C ドライバ](ja/i2c_driver.md)
* [SPI ドライバ](ja/spi_driver.md)
* [WS2812 ドライバ](ja/ws2812_driver.md)
* [EEPROM ドライバ](ja/eeprom_driver.md)
* [GPIO コントロール](ja/internals_gpio_control.md)

View File

@ -98,6 +98,7 @@
* [ISP Flashing Guide](pt-br/isp_flashing_guide.md)
* [ARM Debugging Guide](pt-br/arm_debugging.md)
* [I2C Driver](pt-br/i2c_driver.md)
* [SPI Driver](pt-br/spi_driver.md)
* [GPIO Controls](pt-br/internals_gpio_control.md)
* [Proton C Conversion](pt-br/proton_c_conversion.md)

View File

@ -99,6 +99,7 @@
* [ISP Flashing Guide](ru-ru/isp_flashing_guide.md)
* [ARM Debugging Guide](ru-ru/arm_debugging.md)
* [I2C Driver](ru-ru/i2c_driver.md)
* [SPI Driver](ru-ru/spi_driver.md)
* [WS2812 Driver](ru-ru/ws2812_driver.md)
* [GPIO Controls](ru-ru/internals_gpio_control.md)
* [Proton C Conversion](ru-ru/proton_c_conversion.md)

128
docs/spi_driver.md Normal file
View File

@ -0,0 +1,128 @@
# SPI Master Driver
The SPI Master drivers used in QMK have a set of common functions to allow portability between MCUs.
## AVR Configuration
No special setup is required - just connect the `SS`, `SCK`, `MOSI` and `MISO` pins of your SPI devices to the matching pins on the MCU:
|MCU |`SS`|`SCK`|`MOSI`|`MISO`|
|---------------|----|-----|------|------|
|ATMega16/32U2/4|`B0`|`B1` |`B2` |`B3` |
|AT90USB64/128 |`B0`|`B1` |`B2` |`B3` |
|ATmega32A |`B4`|`B7` |`B5` |`B6` |
|ATmega328P |`B2`|`B5` |`B3` |`B4` |
You may use more than one slave select pin, not just the `SS` pin. This is useful when you have multiple devices connected and need to communicate with them individually.
`SPI_SS_PIN` can be passed to `spi_start()` to refer to `SS`.
## ARM Configuration
ARM support for this driver is not ready yet. Check back later!
## Functions
### `void spi_init(void)`
Initialize the SPI driver. This function must be called only once, before any of the below functions can be called.
---
### `void spi_start(pin_t slavePin, bool lsbFirst, uint8_t mode, uint8_t divisor)`
Start an SPI transaction.
#### Arguments
- `pin_t slavePin`
The QMK pin to assert as the slave select pin, eg. `B4`.
- `bool lsbFirst`
Determines the endianness of the transmission. If `true`, the least significant bit of each byte is sent first.
- `uint8_t mode`
The SPI mode to use:
|Mode|Clock Polarity |Clock Phase |
|----|--------------------|-----------------------|
|`0` |Leading edge rising |Sample on leading edge |
|`1` |Leading edge rising |Sample on trailing edge|
|`2` |Leading edge falling|Sample on leading edge |
|`3` |Leading edge falling|Sample on trailing edge|
- `uint8_t divisor`
The SPI clock divisor, will be rounded up to the nearest power of two. This number can be calculated by dividing the MCU's clock speed by the desired SPI clock speed. For example, an MCU running at 8 MHz wanting to talk to an SPI device at 4 MHz would set the divisor to `2`.
---
### `spi_status_t spi_write(uint8_t data, uint16_t timeout)`
Write a byte to the selected SPI device.
#### Arguments
- `uint8_t data`
The byte to write.
- `uint16_t timeout`
The amount of time to wait, in milliseconds, before timing out.
#### Return Value
`SPI_STATUS_TIMEOUT` if the timeout period elapses, or `SPI_STATUS_SUCCESS`.
---
### `spi_status_t spi_read(uint16_t timeout)`
Read a byte from the selected SPI device.
#### Arguments
- `uint16_t timeout`
The amount of time to wait, in milliseconds, before timing out.
#### Return Value
`SPI_STATUS_TIMEOUT` if the timeout period elapses, or the byte read from the device.
---
### `spi_status_t spi_transmit(const uint8_t *data, uint16_t length, uint16_t timeout)`
Send multiple bytes to the selected SPI device.
#### Arguments
- `const uint8_t *data`
A pointer to the data to write from.
- `uint16_t length`
The number of bytes to write. Take care not to overrun the length of `data`.
- `uint16_t timeout`
The amount of time to wait, in milliseconds, before timing out.
#### Return Value
`SPI_STATUS_TIMEOUT` if the timeout period elapses, `SPI_STATUS_SUCCESS` on success, or `SPI_STATUS_ERROR` otherwise.
---
### `spi_status_t spi_receive(uint8_t *data, uint16_t length, uint16_t timeout)`
Receive multiple bytes from the selected SPI device.
#### Arguments
- `uint8_t *data`
A pointer to the buffer to read into.
- `uint16_t length`
The number of bytes to read. Take care not to overrun the length of `data`.
- `uint16_t timeout`
The amount of time to wait, in milliseconds, before timing out.
#### Return Value
`SPI_STATUS_TIMEOUT` if the timeout period elapses, `SPI_STATUS_SUCCESS` on success, or `SPI_STATUS_ERROR` otherwise.
---
### `void spi_stop(void)`
End the current SPI transaction. This will deassert the slave select pin and reset the endianness, mode and divisor configured by `spi_start()`.

View File

@ -104,6 +104,7 @@
* [ARM调试指南](zh-cn/arm_debugging.md)
* [ADC设备](zh-cn/adc_driver.md)
* [I2C设备](zh-cn/i2c_driver.md)
* [SPI设备](zh-cn/spi_driver.md)
* [WS2812设备](zh-cn/ws2812_driver.md)
* [EEPROM设备](zh-cn/eeprom_driver.md)
* [GPIO控制](zh-cn/internals_gpio_control.md)

163
drivers/avr/spi_master.c Normal file
View File

@ -0,0 +1,163 @@
/* Copyright 2020
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
#include <avr/io.h>
#include "spi_master.h"
#include "quantum.h"
#include "timer.h"
#if defined(__AVR_ATmega16U2__) || defined(__AVR_ATmega32U2__) || defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1287__)
# define SPI_SCK_PIN B1
# define SPI_MOSI_PIN B2
# define SPI_MISO_PIN B3
#elif defined(__AVR_ATmega32A__)
# define SPI_SCK_PIN B7
# define SPI_MOSI_PIN B5
# define SPI_MISO_PIN B6
#elif defined(__AVR_ATmega328P__)
# define SPI_SCK_PIN B5
# define SPI_MOSI_PIN B3
# define SPI_MISO_PIN B4
#endif
static pin_t currentSlavePin = NO_PIN;
static uint8_t currentSlaveConfig = 0;
static bool currentSlave2X = false;
void spi_init(void) {
writePinHigh(SPI_SS_PIN);
setPinOutput(SPI_SCK_PIN);
setPinOutput(SPI_MOSI_PIN);
setPinInput(SPI_MISO_PIN);
SPCR = (_BV(SPE) | _BV(MSTR));
}
void spi_start(pin_t slavePin, bool lsbFirst, uint8_t mode, uint8_t divisor) {
if (currentSlavePin == NO_PIN && slavePin != NO_PIN) {
if (lsbFirst) {
currentSlaveConfig |= _BV(DORD);
}
switch (mode) {
case 1:
currentSlaveConfig |= _BV(CPHA);
break;
case 2:
currentSlaveConfig |= _BV(CPOL);
break;
case 3:
currentSlaveConfig |= (_BV(CPOL) | _BV(CPHA));
break;
}
uint8_t roundedDivisor = 1;
while (roundedDivisor < divisor) {
roundedDivisor <<= 1;
}
switch (roundedDivisor) {
case 16:
currentSlaveConfig |= _BV(SPR0);
break;
case 64:
currentSlaveConfig |= _BV(SPR1);
break;
case 128:
currentSlaveConfig |= (_BV(SPR1) | _BV(SPR0));
break;
case 2:
currentSlave2X = true;
break;
case 8:
currentSlave2X = true;
currentSlaveConfig |= _BV(SPR0);
break;
case 32:
currentSlave2X = true;
currentSlaveConfig |= _BV(SPR1);
break;
}
SPSR |= currentSlaveConfig;
currentSlavePin = slavePin;
setPinOutput(currentSlavePin);
writePinLow(currentSlavePin);
}
}
spi_status_t spi_write(uint8_t data, uint16_t timeout) {
SPDR = data;
uint16_t timeout_timer = timer_read();
while (!(SPSR & _BV(SPIF))) {
if ((timeout != SPI_TIMEOUT_INFINITE) && ((timer_read() - timeout_timer) >= timeout)) {
return SPI_STATUS_TIMEOUT;
}
}
return SPDR;
}
spi_status_t spi_read(uint16_t timeout) {
SPDR = 0x00; // Dummy
uint16_t timeout_timer = timer_read();
while (!(SPSR & _BV(SPIF))) {
if ((timeout != SPI_TIMEOUT_INFINITE) && ((timer_read() - timeout_timer) >= timeout)) {
return SPI_STATUS_TIMEOUT;
}
}
return SPDR;
}
spi_status_t spi_transmit(const uint8_t *data, uint16_t length, uint16_t timeout) {
spi_status_t status = SPI_STATUS_ERROR;
for (uint16_t i = 0; i < length; i++) {
status = spi_write(data[i], timeout);
}
return status;
}
spi_status_t spi_receive(uint8_t *data, uint16_t length, uint16_t timeout) {
spi_status_t status = SPI_STATUS_ERROR;
for (uint16_t i = 0; i < length; i++) {
status = spi_read(timeout);
if (status > 0) {
data[i] = status;
}
}
return (status < 0) ? status : SPI_STATUS_SUCCESS;
}
void spi_stop(void) {
if (currentSlavePin != NO_PIN) {
setPinOutput(currentSlavePin);
writePinHigh(currentSlavePin);
currentSlavePin = NO_PIN;
SPCR &= ~(currentSlaveConfig);
currentSlaveConfig = 0;
SPSR = 0;
currentSlave2X = false;
}
}

57
drivers/avr/spi_master.h Normal file
View File

@ -0,0 +1,57 @@
/* Copyright 2020
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
#pragma once
#include "quantum.h"
typedef int16_t spi_status_t;
// Hardware SS pin is defined in the header so that user code can refer to it
#if defined(__AVR_ATmega16U2__) || defined(__AVR_ATmega32U2__) || defined(__AVR_ATmega16U4__) || defined(__AVR_ATmega32U4__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1287__)
# define SPI_SS_PIN B0
#elif defined(__AVR_ATmega32A__)
# define SPI_SS_PIN B4
#elif defined(__AVR_ATmega328P__)
# define SPI_SS_PIN B2
#endif
#define SPI_STATUS_SUCCESS (0)
#define SPI_STATUS_ERROR (-1)
#define SPI_STATUS_TIMEOUT (-2)
#define SPI_TIMEOUT_IMMEDIATE (0)
#define SPI_TIMEOUT_INFINITE (0xFFFF)
#ifdef __cplusplus
extern "C" {
#endif
void spi_init(void);
void spi_start(pin_t slavePin, bool lsbFirst, uint8_t mode, uint8_t divisor);
spi_status_t spi_write(uint8_t data, uint16_t timeout);
spi_status_t spi_read(uint16_t timeout);
spi_status_t spi_transmit(const uint8_t *data, uint16_t length, uint16_t timeout);
spi_status_t spi_receive(uint8_t *data, uint16_t length, uint16_t timeout);
void spi_stop(void);
#ifdef __cplusplus
}
#endif

View File

@ -29,6 +29,7 @@ ifeq ($(strip $(BLUETOOTH_ENABLE)), yes)
endif
ifeq ($(strip $(BLUETOOTH)), AdafruitBLE)
LUFA_SRC += spi_master.c
LUFA_SRC += analog.c
LUFA_SRC += $(LUFA_DIR)/adafruit_ble.cpp
endif

View File

@ -1,15 +1,15 @@
#include "adafruit_ble.h"
#include <stdio.h>
#include <stdlib.h>
#include <alloca.h>
#include <util/delay.h>
#include <util/atomic.h>
#include "debug.h"
#include "pincontrol.h"
#include "timer.h"
#include "action_util.h"
#include "ringbuffer.hpp"
#include <string.h>
#include "spi_master.h"
#include "wait.h"
#include "analog.h"
// These are the pin assignments for the 32u4 boards.
@ -27,6 +27,12 @@
# define AdafruitBleIRQPin E6
#endif
#ifndef AdafruitBleSpiClockSpeed
# define AdafruitBleSpiClockSpeed 4000000UL // SCK frequency
#endif
#define SCK_DIVISOR (F_CPU / AdafruitBleSpiClockSpeed)
#define SAMPLE_BATTERY
#define ConnectionUpdateInterval 1000 /* milliseconds */
@ -130,10 +136,6 @@ enum ble_system_event_bits {
BleSystemMidiRx = 10,
};
// The SDEP.md file says 2MHz but the web page and the sample driver
// both use 4MHz
#define SpiBusSpeed 4000000
#define SdepTimeout 150 /* milliseconds */
#define SdepShortTimeout 10 /* milliseconds */
#define SdepBackOff 25 /* microseconds */
@ -142,116 +144,32 @@ enum ble_system_event_bits {
static bool at_command(const char *cmd, char *resp, uint16_t resplen, bool verbose, uint16_t timeout = SdepTimeout);
static bool at_command_P(const char *cmd, char *resp, uint16_t resplen, bool verbose = false);
struct SPI_Settings {
uint8_t spcr, spsr;
};
static struct SPI_Settings spi;
// Initialize 4Mhz MSBFIRST MODE0
void SPI_init(struct SPI_Settings *spi) {
spi->spcr = _BV(SPE) | _BV(MSTR);
#if F_CPU == 8000000
// For MCUs running at 8MHz (such as Feather 32U4, or 3.3V Pro Micros) we set the SPI doublespeed bit
spi->spsr = _BV(SPI2X);
#endif
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
// Ensure that SS is OUTPUT High
digitalWrite(B0, PinLevelHigh);
pinMode(B0, PinDirectionOutput);
SPCR |= _BV(MSTR);
SPCR |= _BV(SPE);
pinMode(B1 /* SCK */, PinDirectionOutput);
pinMode(B2 /* MOSI */, PinDirectionOutput);
}
}
static inline void SPI_begin(struct SPI_Settings *spi) {
SPCR = spi->spcr;
SPSR = spi->spsr;
}
static inline uint8_t SPI_TransferByte(uint8_t data) {
SPDR = data;
asm volatile("nop");
while (!(SPSR & _BV(SPIF))) {
; // wait
}
return SPDR;
}
static inline void spi_send_bytes(const uint8_t *buf, uint8_t len) {
if (len == 0) return;
const uint8_t *end = buf + len;
while (buf < end) {
SPDR = *buf;
while (!(SPSR & _BV(SPIF))) {
; // wait
}
++buf;
}
}
static inline uint16_t spi_read_byte(void) { return SPI_TransferByte(0x00 /* dummy */); }
static inline void spi_recv_bytes(uint8_t *buf, uint8_t len) {
const uint8_t *end = buf + len;
if (len == 0) return;
while (buf < end) {
SPDR = 0; // write a dummy to initiate read
while (!(SPSR & _BV(SPIF))) {
; // wait
}
*buf = SPDR;
++buf;
}
}
#if 0
static void dump_pkt(const struct sdep_msg *msg) {
print("pkt: type=");
print_hex8(msg->type);
print(" cmd=");
print_hex8(msg->cmd_high);
print_hex8(msg->cmd_low);
print(" len=");
print_hex8(msg->len);
print(" more=");
print_hex8(msg->more);
print("\n");
}
#endif
// Send a single SDEP packet
static bool sdep_send_pkt(const struct sdep_msg *msg, uint16_t timeout) {
SPI_begin(&spi);
digitalWrite(AdafruitBleCSPin, PinLevelLow);
spi_start(AdafruitBleCSPin, false, 0, SCK_DIVISOR);
uint16_t timerStart = timer_read();
bool success = false;
bool ready = false;
do {
ready = SPI_TransferByte(msg->type) != SdepSlaveNotReady;
ready = spi_write(msg->type, 100) != SdepSlaveNotReady;
if (ready) {
break;
}
// Release it and let it initialize
digitalWrite(AdafruitBleCSPin, PinLevelHigh);
_delay_us(SdepBackOff);
digitalWrite(AdafruitBleCSPin, PinLevelLow);
spi_stop();
wait_us(SdepBackOff);
spi_start(AdafruitBleCSPin, false, 0, SCK_DIVISOR);
} while (timer_elapsed(timerStart) < timeout);
if (ready) {
// Slave is ready; send the rest of the packet
spi_send_bytes(&msg->cmd_low, sizeof(*msg) - (1 + sizeof(msg->payload)) + msg->len);
spi_transmit(&msg->cmd_low, sizeof(*msg) - (1 + sizeof(msg->payload)) + msg->len, 100);
success = true;
}
digitalWrite(AdafruitBleCSPin, PinLevelHigh);
spi_stop();
return success;
}
@ -275,41 +193,39 @@ static bool sdep_recv_pkt(struct sdep_msg *msg, uint16_t timeout) {
bool ready = false;
do {
ready = digitalRead(AdafruitBleIRQPin);
ready = readPin(AdafruitBleIRQPin);
if (ready) {
break;
}
_delay_us(1);
wait_us(1);
} while (timer_elapsed(timerStart) < timeout);
if (ready) {
SPI_begin(&spi);
digitalWrite(AdafruitBleCSPin, PinLevelLow);
spi_start(AdafruitBleCSPin, false, 0, SCK_DIVISOR);
do {
// Read the command type, waiting for the data to be ready
msg->type = spi_read_byte();
msg->type = spi_read(100);
if (msg->type == SdepSlaveNotReady || msg->type == SdepSlaveOverflow) {
// Release it and let it initialize
digitalWrite(AdafruitBleCSPin, PinLevelHigh);
_delay_us(SdepBackOff);
digitalWrite(AdafruitBleCSPin, PinLevelLow);
spi_stop();
wait_us(SdepBackOff);
spi_start(AdafruitBleCSPin, false, 0, SCK_DIVISOR);
continue;
}
// Read the rest of the header
spi_recv_bytes(&msg->cmd_low, sizeof(*msg) - (1 + sizeof(msg->payload)));
spi_receive(&msg->cmd_low, sizeof(*msg) - (1 + sizeof(msg->payload)), 100);
// and get the payload if there is any
if (msg->len <= SdepMaxPayload) {
spi_recv_bytes(msg->payload, msg->len);
spi_receive(msg->payload, msg->len, 100);
}
success = true;
break;
} while (timer_elapsed(timerStart) < timeout);
digitalWrite(AdafruitBleCSPin, PinLevelHigh);
spi_stop();
}
return success;
}
@ -320,7 +236,7 @@ static void resp_buf_read_one(bool greedy) {
return;
}
if (digitalRead(AdafruitBleIRQPin)) {
if (readPin(AdafruitBleIRQPin)) {
struct sdep_msg msg;
again:
@ -331,7 +247,7 @@ static void resp_buf_read_one(bool greedy) {
dprintf("recv latency %dms\n", TIMER_DIFF_16(timer_read(), last_send));
}
if (greedy && resp_buf.peek(last_send) && digitalRead(AdafruitBleIRQPin)) {
if (greedy && resp_buf.peek(last_send) && readPin(AdafruitBleIRQPin)) {
goto again;
}
}
@ -361,7 +277,7 @@ static void send_buf_send_one(uint16_t timeout = SdepTimeout) {
dprintf("send_buf_send_one: have %d remaining\n", (int)send_buf.size());
} else {
dprint("failed to send, will retry\n");
_delay_ms(SdepTimeout);
wait_ms(SdepTimeout);
resp_buf_read_one(true);
}
}
@ -382,20 +298,18 @@ static bool ble_init(void) {
state.configured = false;
state.is_connected = false;
pinMode(AdafruitBleIRQPin, PinDirectionInput);
pinMode(AdafruitBleCSPin, PinDirectionOutput);
digitalWrite(AdafruitBleCSPin, PinLevelHigh);
setPinInput(AdafruitBleIRQPin);
SPI_init(&spi);
spi_init();
// Perform a hardware reset
pinMode(AdafruitBleResetPin, PinDirectionOutput);
digitalWrite(AdafruitBleResetPin, PinLevelHigh);
digitalWrite(AdafruitBleResetPin, PinLevelLow);
_delay_ms(10);
digitalWrite(AdafruitBleResetPin, PinLevelHigh);
setPinOutput(AdafruitBleResetPin);
writePinHigh(AdafruitBleResetPin);
writePinLow(AdafruitBleResetPin);
wait_ms(10);
writePinHigh(AdafruitBleResetPin);
_delay_ms(1000); // Give it a second to initialize
wait_ms(1000); // Give it a second to initialize
state.initialized = true;
return state.initialized;
@ -596,7 +510,7 @@ void adafruit_ble_task(void) {
resp_buf_read_one(true);
send_buf_send_one(SdepShortTimeout);
if (resp_buf.empty() && (state.event_flags & UsingEvents) && digitalRead(AdafruitBleIRQPin)) {
if (resp_buf.empty() && (state.event_flags & UsingEvents) && readPin(AdafruitBleIRQPin)) {
// Must be an event update
if (at_command_P(PSTR("AT+EVENTSTATUS"), resbuf, sizeof(resbuf))) {
uint32_t mask = strtoul(resbuf, NULL, 16);